From cc4fc28fe09eefe9a04c5521c47fa8ed796d8594 Mon Sep 17 00:00:00 2001 From: tombrazier <68918209+tombrazier@users.noreply.github.com> Date: Sat, 16 Jul 2022 00:15:51 +0100 Subject: [PATCH 01/54] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Optimize=20Planner?= =?UTF-8?q?=20calculations=20(#24484)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/planner.cpp | 164 ++++++++++++++++------------------ Marlin/src/module/planner.h | 26 +----- 2 files changed, 80 insertions(+), 110 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 7b00552dff..de1351babf 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -28,12 +28,14 @@ * Derived from Grbl * Copyright (c) 2009-2011 Simen Svale Skogsrud * - * The ring buffer implementation gleaned from the wiring_serial library by David A. Mellis. + * Ring buffer gleaned from wiring_serial library by David A. Mellis. * + * Fast inverse function needed for Bézier interpolation for AVR + * was designed, written and tested by Eduardo José Tagle, April 2018. * - * Reasoning behind the mathematics in this module (in the key of 'Mathematica'): + * Planner mathematics (Mathematica-style): * - * s == speed, a == acceleration, t == time, d == distance + * Where: s == speed, a == acceleration, t == time, d == distance * * Basic definitions: * Speed[s_, a_, t_] := s + (a*t) @@ -41,7 +43,7 @@ * * Distance to reach a specific speed with a constant acceleration: * Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t] - * d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance() + * d -> (m^2 - s^2) / (2 a) * * Speed after a given distance of travel with constant acceleration: * Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t] @@ -49,17 +51,18 @@ * * DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2] * - * When to start braking (di) to reach a specified destination speed (s2) after accelerating - * from initial speed s1 without ever stopping at a plateau: + * When to start braking (di) to reach a specified destination speed (s2) after + * acceleration from initial speed s1 without ever reaching a plateau: * Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di] - * di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance() + * di -> (2 a d - s1^2 + s2^2)/(4 a) * - * IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a) + * We note, as an optimization, that if we have already calculated an + * acceleration distance d1 from s1 to m and a deceration distance d2 + * from m to s2 then * - * -- - * - * The fast inverse function needed for Bézier interpolation for AVR - * was designed, written and tested by Eduardo José Tagle on April/2018 + * d1 -> (m^2 - s1^2) / (2 a) + * d2 -> (m^2 - s2^2) / (2 a) + * di -> (d + d1 - d2) / 2 */ #include "planner.h" @@ -211,7 +214,7 @@ xyze_long_t Planner::position{0}; uint32_t Planner::acceleration_long_cutoff; xyze_float_t Planner::previous_speed; -float Planner::previous_nominal_speed_sqr; +float Planner::previous_nominal_speed; #if ENABLED(DISABLE_INACTIVE_EXTRUDER) last_move_t Planner::g_uc_extruder_last_move[E_STEPPERS] = { 0 }; @@ -220,7 +223,7 @@ float Planner::previous_nominal_speed_sqr; #ifdef XY_FREQUENCY_LIMIT int8_t Planner::xy_freq_limit_hz = XY_FREQUENCY_LIMIT; float Planner::xy_freq_min_speed_factor = (XY_FREQUENCY_MIN_PERCENT) * 0.01f; - int32_t Planner::xy_freq_min_interval_us = LROUND(1000000.0 / (XY_FREQUENCY_LIMIT)); + int32_t Planner::xy_freq_min_interval_us = LROUND(1000000.0f / (XY_FREQUENCY_LIMIT)); #endif #if ENABLED(LIN_ADVANCE) @@ -250,7 +253,7 @@ void Planner::init() { TERN_(HAS_POSITION_FLOAT, position_float.reset()); TERN_(IS_KINEMATIC, position_cart.reset()); previous_speed.reset(); - previous_nominal_speed_sqr = 0; + previous_nominal_speed = 0; TERN_(ABL_PLANAR, bed_level_matrix.set_to_identity()); clear_block_buffer(); delay_before_delivering = 0; @@ -786,41 +789,48 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t NOLESS(final_rate, uint32_t(MINIMAL_STEP_RATE)); #if ENABLED(S_CURVE_ACCELERATION) - uint32_t cruise_rate = initial_rate; + // If we have some plateau time, the cruise rate will be the nominal rate + uint32_t cruise_rate = block->nominal_rate; #endif const int32_t accel = block->acceleration_steps_per_s2; - // Steps required for acceleration, deceleration to/from nominal rate - uint32_t accelerate_steps = CEIL(estimate_acceleration_distance(initial_rate, block->nominal_rate, accel)), - decelerate_steps = FLOOR(estimate_acceleration_distance(block->nominal_rate, final_rate, -accel)); - // Steps between acceleration and deceleration, if any - int32_t plateau_steps = block->step_event_count - accelerate_steps - decelerate_steps; - - // Does accelerate_steps + decelerate_steps exceed step_event_count? - // Then we can't possibly reach the nominal rate, there will be no cruising. - // Use intersection_distance() to calculate accel / braking time in order to - // reach the final_rate exactly at the end of this block. - if (plateau_steps < 0) { - const float accelerate_steps_float = CEIL(intersection_distance(initial_rate, final_rate, accel, block->step_event_count)); - accelerate_steps = _MIN(uint32_t(_MAX(accelerate_steps_float, 0)), block->step_event_count); - decelerate_steps = block->step_event_count - accelerate_steps; - plateau_steps = 0; - - #if ENABLED(S_CURVE_ACCELERATION) - // We won't reach the cruising rate. Let's calculate the speed we will reach - cruise_rate = final_speed(initial_rate, accel, accelerate_steps); - #endif + // Steps for acceleration, plateau and deceleration + int32_t plateau_steps = block->step_event_count; + uint32_t accelerate_steps = 0, + decelerate_steps = 0; + + if (accel != 0) { + // Steps required for acceleration, deceleration to/from nominal rate + const float nominal_rate_sq = sq(float(block->nominal_rate)); + float accelerate_steps_float = (nominal_rate_sq - sq(float(initial_rate))) * (0.5f / accel); + accelerate_steps = CEIL(accelerate_steps_float); + const float decelerate_steps_float = (nominal_rate_sq - sq(float(final_rate))) * (0.5f / accel); + decelerate_steps = decelerate_steps_float; + + // Steps between acceleration and deceleration, if any + plateau_steps -= accelerate_steps + decelerate_steps; + + // Does accelerate_steps + decelerate_steps exceed step_event_count? + // Then we can't possibly reach the nominal rate, there will be no cruising. + // Calculate accel / braking time in order to reach the final_rate exactly + // at the end of this block. + if (plateau_steps < 0) { + accelerate_steps_float = CEIL((block->step_event_count + accelerate_steps_float - decelerate_steps_float) * 0.5f); + accelerate_steps = _MIN(uint32_t(_MAX(accelerate_steps_float, 0)), block->step_event_count); + decelerate_steps = block->step_event_count - accelerate_steps; + + #if ENABLED(S_CURVE_ACCELERATION) + // We won't reach the cruising rate. Let's calculate the speed we will reach + cruise_rate = final_speed(initial_rate, accel, accelerate_steps); + #endif + } } - #if ENABLED(S_CURVE_ACCELERATION) - else // We have some plateau time, so the cruise rate will be the nominal rate - cruise_rate = block->nominal_rate; - #endif #if ENABLED(S_CURVE_ACCELERATION) // Jerk controlled speed requires to express speed versus time, NOT steps - uint32_t acceleration_time = ((float)(cruise_rate - initial_rate) / accel) * (STEPPER_TIMER_RATE), - deceleration_time = ((float)(cruise_rate - final_rate) / accel) * (STEPPER_TIMER_RATE), + uint32_t acceleration_time = (float(cruise_rate - initial_rate) / accel) * (STEPPER_TIMER_RATE), + deceleration_time = (float(cruise_rate - final_rate) / accel) * (STEPPER_TIMER_RATE), // And to offload calculations from the ISR, we also calculate the inverse of those times here acceleration_time_inverse = get_period_inverse(acceleration_time), deceleration_time_inverse = get_period_inverse(deceleration_time); @@ -1175,7 +1185,7 @@ void Planner::recalculate_trapezoids(TERN_(HINTS_SAFE_EXIT_SPEED, const_float_t // Go from the tail (currently executed block) to the first block, without including it) block_t *block = nullptr, *next = nullptr; - float current_entry_speed = 0.0, next_entry_speed = 0.0; + float current_entry_speed = 0.0f, next_entry_speed = 0.0f; while (block_index != head_block_index) { next = &block_buffer[block_index]; @@ -1199,13 +1209,12 @@ void Planner::recalculate_trapezoids(TERN_(HINTS_SAFE_EXIT_SPEED, const_float_t // Block is not BUSY, we won the race against the Stepper ISR: // NOTE: Entry and exit factors always > 0 by all previous logic operations. - const float current_nominal_speed = SQRT(block->nominal_speed_sqr), - nomr = 1.0f / current_nominal_speed; + const float nomr = 1.0f / block->nominal_speed; calculate_trapezoid_for_block(block, current_entry_speed * nomr, next_entry_speed * nomr); #if ENABLED(LIN_ADVANCE) if (block->use_advance_lead) { const float comp = block->e_D_ratio * extruder_advance_K[active_extruder] * settings.axis_steps_per_mm[E_AXIS]; - block->max_adv_steps = current_nominal_speed * comp; + block->max_adv_steps = block->nominal_speed * comp; block->final_adv_steps = next_entry_speed * comp; } #endif @@ -1240,13 +1249,12 @@ void Planner::recalculate_trapezoids(TERN_(HINTS_SAFE_EXIT_SPEED, const_float_t if (!stepper.is_block_busy(block)) { // Block is not BUSY, we won the race against the Stepper ISR: - const float current_nominal_speed = SQRT(block->nominal_speed_sqr), - nomr = 1.0f / current_nominal_speed; + const float nomr = 1.0f / block->nominal_speed; calculate_trapezoid_for_block(block, current_entry_speed * nomr, next_entry_speed * nomr); #if ENABLED(LIN_ADVANCE) if (block->use_advance_lead) { const float comp = block->e_D_ratio * extruder_advance_K[active_extruder] * settings.axis_steps_per_mm[E_AXIS]; - block->max_adv_steps = current_nominal_speed * comp; + block->max_adv_steps = block->nominal_speed * comp; block->final_adv_steps = next_entry_speed * comp; } #endif @@ -1290,14 +1298,10 @@ void Planner::recalculate(TERN_(HINTS_SAFE_EXIT_SPEED, const_float_t safe_exit_s #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0) const millis_t ms = millis(); - TERN_(HAS_FAN0, FAN_SET(0)); - TERN_(HAS_FAN1, FAN_SET(1)); - TERN_(HAS_FAN2, FAN_SET(2)); - TERN_(HAS_FAN3, FAN_SET(3)); - TERN_(HAS_FAN4, FAN_SET(4)); - TERN_(HAS_FAN5, FAN_SET(5)); - TERN_(HAS_FAN6, FAN_SET(6)); - TERN_(HAS_FAN7, FAN_SET(7)); + TERN_(HAS_FAN0, FAN_SET(0)); TERN_(HAS_FAN1, FAN_SET(1)); + TERN_(HAS_FAN2, FAN_SET(2)); TERN_(HAS_FAN3, FAN_SET(3)); + TERN_(HAS_FAN4, FAN_SET(4)); TERN_(HAS_FAN5, FAN_SET(5)); + TERN_(HAS_FAN6, FAN_SET(6)); TERN_(HAS_FAN7, FAN_SET(7)); } #if FAN_KICKSTART_TIME @@ -1485,7 +1489,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 (NUM_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, || block->steps.i, || block->steps.j, || block->steps.k, || block->steps.u, || block->steps.v, || block->steps.w)) { - 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 * block->nominal_speed; // mm/sec NOLESS(high, se); } } @@ -1936,7 +1940,7 @@ bool Planner::_populate_block( #if ENABLED(MIXING_EXTRUDER) bool ignore_e = false; float collector[MIXING_STEPPERS]; - mixer.refresh_collector(1.0, mixer.get_current_vtool(), collector); + mixer.refresh_collector(1.0f, mixer.get_current_vtool(), collector); MIXER_STEPPER_LOOP(e) if (e_steps * collector[e] > max_e_steps) { ignore_e = true; break; } #else @@ -2193,7 +2197,7 @@ bool Planner::_populate_block( #if SECONDARY_LINEAR_AXES >= 1 && NONE(FOAMCUTTER_XYUV, ARTICULATED_ROBOT_ARM) if (NEAR_ZERO(distance_sqr)) { // Move does not involve any primary linear axes (xyz) but might involve secondary linear axes - distance_sqr = (0.0 + distance_sqr = (0.0f SECONDARY_AXIS_GANG( IF_DISABLED(AXIS4_ROTATES, + sq(steps_dist_mm.i)), IF_DISABLED(AXIS5_ROTATES, + sq(steps_dist_mm.j)), @@ -2396,7 +2400,7 @@ bool Planner::_populate_block( if (was_enabled) stepper.wake_up(); #endif - block->nominal_speed_sqr = sq(block->millimeters * inverse_secs); // (mm/sec)^2 Always > 0 + block->nominal_speed = block->millimeters * inverse_secs; // (mm/sec) Always > 0 block->nominal_rate = CEIL(block->step_event_count * inverse_secs); // (step/sec) Always > 0 #if ENABLED(FILAMENT_WIDTH_SENSOR) @@ -2492,7 +2496,7 @@ bool Planner::_populate_block( 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 *= speed_factor; } // Compute and limit the acceleration rate for the trapezoid generator. @@ -2592,7 +2596,7 @@ bool Planner::_populate_block( if (block->use_advance_lead) { block->advance_speed = (STEPPER_TIMER_RATE) / (extruder_advance_K[active_extruder] * block->e_D_ratio * block->acceleration * settings.axis_steps_per_mm[E_AXIS_N(extruder)]); #if ENABLED(LA_DEBUG) - if (extruder_advance_K[active_extruder] * block->e_D_ratio * block->acceleration * 2 < SQRT(block->nominal_speed_sqr) * block->e_D_ratio) + if (extruder_advance_K[active_extruder] * block->e_D_ratio * block->acceleration * 2 < block->nominal_speed * block->e_D_ratio) SERIAL_ECHOLNPGM("More than 2 steps per eISR loop executed."); if (block->advance_speed < 200) SERIAL_ECHOLNPGM("eISR running at > 10kHz."); @@ -2663,7 +2667,7 @@ bool Planner::_populate_block( unit_vec *= inverse_millimeters; // Use pre-calculated (1 / SQRT(x^2 + y^2 + z^2)) // Skip first block or when previous_nominal_speed is used as a flag for homing and offset cycles. - if (moves_queued && !UNEAR_ZERO(previous_nominal_speed_sqr)) { + if (moves_queued && !UNEAR_ZERO(previous_nominal_speed)) { // Compute cosine of angle between previous and current path. (prev_unit_vec is negative) // NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity. float junction_cos_theta = LOGICAL_AXIS_GANG( @@ -2792,7 +2796,7 @@ bool Planner::_populate_block( } // Get the lowest speed - vmax_junction_sqr = _MIN(vmax_junction_sqr, block->nominal_speed_sqr, previous_nominal_speed_sqr); + vmax_junction_sqr = _MIN(vmax_junction_sqr, sq(block->nominal_speed), sq(previous_nominal_speed)); } else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later. vmax_junction_sqr = 0; @@ -2801,27 +2805,17 @@ bool Planner::_populate_block( #endif - #ifdef USE_CACHED_SQRT - #define CACHED_SQRT(N, V) \ - static float saved_V, N; \ - if (V != saved_V) { N = SQRT(V); saved_V = V; } - #else - #define CACHED_SQRT(N, V) const float N = SQRT(V) - #endif - #if HAS_CLASSIC_JERK /** * Adapted from Průša MKS firmware * https://github.com/prusa3d/Prusa-Firmware */ - CACHED_SQRT(nominal_speed, block->nominal_speed_sqr); - // Exit speed limited by a jerk to full halt of a previous last segment static float previous_safe_speed; // Start with a safe speed (from which the machine may halt to stop immediately). - float safe_speed = nominal_speed; + float safe_speed = block->nominal_speed; #ifndef TRAVEL_EXTRA_XYJERK #define TRAVEL_EXTRA_XYJERK 0 @@ -2834,7 +2828,7 @@ bool Planner::_populate_block( maxj = (max_jerk[i] + (i == X_AXIS || i == Y_AXIS ? extra_xyjerk : 0.0f)); // mj : The max jerk setting for this axis if (jerk > maxj) { // cs > mj : New current speed too fast? if (limited) { // limited already? - const float mjerk = nominal_speed * maxj; // ns*mj + const float mjerk = block->nominal_speed * maxj; // ns*mj if (jerk * safe_speed > mjerk) safe_speed = mjerk / jerk; // ns*mj/cs } else { @@ -2845,7 +2839,7 @@ bool Planner::_populate_block( } float vmax_junction; - if (moves_queued && !UNEAR_ZERO(previous_nominal_speed_sqr)) { + if (moves_queued && !UNEAR_ZERO(previous_nominal_speed)) { // Estimate a maximum velocity allowed at a joint of two successive segments. // If this maximum velocity allowed is lower than the minimum of the entry / exit safe velocities, // then the machine is not coasting anymore and the safe entry / exit velocities shall be used. @@ -2856,11 +2850,9 @@ bool Planner::_populate_block( // The junction velocity will be shared between successive segments. Limit the junction velocity to their minimum. // Pick the smaller of the nominal speeds. Higher speed shall not be achieved at the junction during coasting. - CACHED_SQRT(previous_nominal_speed, previous_nominal_speed_sqr); - float smaller_speed_factor = 1.0f; - if (nominal_speed < previous_nominal_speed) { - vmax_junction = nominal_speed; + if (block->nominal_speed < previous_nominal_speed) { + vmax_junction = block->nominal_speed; smaller_speed_factor = vmax_junction / previous_nominal_speed; } else @@ -2927,11 +2919,11 @@ bool Planner::_populate_block( // 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.set_nominal(block->nominal_speed_sqr <= v_allowable_sqr); + block->flag.set_nominal(sq(block->nominal_speed) <= v_allowable_sqr); // Update previous path unit_vector and nominal speed previous_speed = current_speed; - previous_nominal_speed_sqr = block->nominal_speed_sqr; + previous_nominal_speed = block->nominal_speed; position = target; // Update the position @@ -3268,7 +3260,7 @@ void Planner::set_machine_position_mm(const abce_pos_t &abce) { ); if (has_blocks_queued()) { - //previous_nominal_speed_sqr = 0.0; // Reset planner junction speeds. Assume start from rest. + //previous_nominal_speed = 0.0f; // Reset planner junction speeds. Assume start from rest. //previous_speed.reset(); buffer_sync_block(BLOCK_BIT_SYNC_POSITION); } @@ -3344,7 +3336,7 @@ void Planner::refresh_positioning() { inline void limit_and_warn(float &val, const AxisEnum axis, PGM_P const setting_name, const xyze_float_t &max_limit) { const uint8_t lim_axis = TERN_(HAS_EXTRUDERS, axis > E_AXIS ? E_AXIS :) axis; const float before = val; - LIMIT(val, 0.1, max_limit[lim_axis]); + LIMIT(val, 0.1f, max_limit[lim_axis]); if (before != val) { SERIAL_CHAR(AXIS_CHAR(lim_axis)); SERIAL_ECHOPGM(" Max "); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 389ae6d4bf..6eb5272071 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -199,7 +199,7 @@ typedef struct PlannerBlock { 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 + float nominal_speed, // The nominal speed for this block in (mm/sec) entry_speed_sqr, // Entry speed at previous-current junction in (mm/sec)^2 max_entry_speed_sqr, // Maximum allowable junction entry speed in (mm/sec)^2 millimeters, // The total travel of this block in mm @@ -510,7 +510,7 @@ class Planner { /** * Nominal speed of previous path line segment (mm/s)^2 */ - static float previous_nominal_speed_sqr; + static float previous_nominal_speed; /** * Limit where 64bit math is necessary for acceleration calculation @@ -1009,28 +1009,6 @@ class Planner { static constexpr uint8_t next_block_index(const uint8_t block_index) { return BLOCK_MOD(block_index + 1); } static constexpr uint8_t prev_block_index(const uint8_t block_index) { return BLOCK_MOD(block_index - 1); } - /** - * Calculate the distance (not time) it takes to accelerate - * from initial_rate to target_rate using the given acceleration: - */ - static float estimate_acceleration_distance(const_float_t initial_rate, const_float_t target_rate, const_float_t accel) { - if (accel == 0) return 0; // accel was 0, set acceleration distance to 0 - return (sq(target_rate) - sq(initial_rate)) / (accel * 2); - } - - /** - * Return the point at which you must start braking (at the rate of -'accel') if - * you start at 'initial_rate', accelerate (until reaching the point), and want to end at - * 'final_rate' after traveling 'distance'. - * - * This is used to compute the intersection point between acceleration and deceleration - * in cases where the "trapezoid" has no plateau (i.e., never reaches maximum speed) - */ - static float intersection_distance(const_float_t initial_rate, const_float_t final_rate, const_float_t accel, const_float_t distance) { - if (accel == 0) return 0; // accel was 0, set intersection distance to 0 - return (accel * 2 * distance - sq(initial_rate) + sq(final_rate)) / (accel * 4); - } - /** * Calculate the maximum allowable speed squared at this point, in order * to reach 'target_velocity_sqr' using 'acceleration' within a given From 96d3c66b646c89115be4a6c27d8908bedd8dbfb7 Mon Sep 17 00:00:00 2001 From: Nikolay-Po <54221205+Nikolay-Po@users.noreply.github.com> Date: Sat, 16 Jul 2022 03:56:15 +0300 Subject: [PATCH 02/54] =?UTF-8?q?=E2=9C=A8=20Steinhart-Hart=20C=20Coeff=20?= =?UTF-8?q?for=20Custom=20Thermistor=20(#24428)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 98 ++++++++++++++++++------------- Marlin/src/module/temperature.cpp | 28 ++++----- 2 files changed, 70 insertions(+), 56 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index bf305741dd..1a327e769a 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -54,87 +54,101 @@ // Custom Thermistor 1000 parameters // #if TEMP_SENSOR_0 == 1000 - #define HOTEND0_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND0_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND0_BETA 3950 // Beta value + #define HOTEND0_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND0_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND0_BETA 3950 // Beta value + #define HOTEND0_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_1 == 1000 - #define HOTEND1_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND1_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND1_BETA 3950 // Beta value + #define HOTEND1_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND1_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND1_BETA 3950 // Beta value + #define HOTEND1_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_2 == 1000 - #define HOTEND2_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND2_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND2_BETA 3950 // Beta value + #define HOTEND2_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND2_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND2_BETA 3950 // Beta value + #define HOTEND2_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_3 == 1000 - #define HOTEND3_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND3_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND3_BETA 3950 // Beta value + #define HOTEND3_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND3_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND3_BETA 3950 // Beta value + #define HOTEND3_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_4 == 1000 - #define HOTEND4_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND4_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND4_BETA 3950 // Beta value + #define HOTEND4_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND4_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND4_BETA 3950 // Beta value + #define HOTEND4_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_5 == 1000 - #define HOTEND5_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND5_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND5_BETA 3950 // Beta value + #define HOTEND5_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND5_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND5_BETA 3950 // Beta value + #define HOTEND5_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_6 == 1000 - #define HOTEND6_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND6_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND6_BETA 3950 // Beta value + #define HOTEND6_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND6_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND6_BETA 3950 // Beta value + #define HOTEND6_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_7 == 1000 - #define HOTEND7_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND7_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND7_BETA 3950 // Beta value + #define HOTEND7_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND7_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND7_BETA 3950 // Beta value + #define HOTEND7_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_BED == 1000 - #define BED_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define BED_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define BED_BETA 3950 // Beta value + #define BED_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define BED_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define BED_BETA 3950 // Beta value + #define BED_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_CHAMBER == 1000 - #define CHAMBER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define CHAMBER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define CHAMBER_BETA 3950 // Beta value + #define CHAMBER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define CHAMBER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define CHAMBER_BETA 3950 // Beta value + #define CHAMBER_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_COOLER == 1000 - #define COOLER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define COOLER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define COOLER_BETA 3950 // Beta value + #define COOLER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define COOLER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define COOLER_BETA 3950 // Beta value + #define COOLER_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_PROBE == 1000 - #define PROBE_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define PROBE_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define PROBE_BETA 3950 // Beta value + #define PROBE_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define PROBE_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define PROBE_BETA 3950 // Beta value + #define PROBE_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_BOARD == 1000 - #define BOARD_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define BOARD_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define BOARD_BETA 3950 // Beta value + #define BOARD_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define BOARD_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define BOARD_BETA 3950 // Beta value + #define BOARD_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_REDUNDANT == 1000 - #define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define REDUNDANT_BETA 3950 // Beta value + #define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define REDUNDANT_BETA 3950 // Beta value + #define REDUNDANT_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif /** diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 97d248864e..e15e843051 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1947,46 +1947,46 @@ void Temperature::task() { void Temperature::reset_user_thermistors() { user_thermistor_t default_user_thermistor[USER_THERMISTORS] = { #if TEMP_SENSOR_0_IS_CUSTOM - { true, 0, 0, HOTEND0_PULLUP_RESISTOR_OHMS, HOTEND0_RESISTANCE_25C_OHMS, 0, 0, HOTEND0_BETA, 0 }, + { true, HOTEND0_SH_C_COEFF, 0, HOTEND0_PULLUP_RESISTOR_OHMS, HOTEND0_RESISTANCE_25C_OHMS, 0, 0, HOTEND0_BETA, 0 }, #endif #if TEMP_SENSOR_1_IS_CUSTOM - { true, 0, 0, HOTEND1_PULLUP_RESISTOR_OHMS, HOTEND1_RESISTANCE_25C_OHMS, 0, 0, HOTEND1_BETA, 0 }, + { true, HOTEND1_SH_C_COEFF, 0, HOTEND1_PULLUP_RESISTOR_OHMS, HOTEND1_RESISTANCE_25C_OHMS, 0, 0, HOTEND1_BETA, 0 }, #endif #if TEMP_SENSOR_2_IS_CUSTOM - { true, 0, 0, HOTEND2_PULLUP_RESISTOR_OHMS, HOTEND2_RESISTANCE_25C_OHMS, 0, 0, HOTEND2_BETA, 0 }, + { true, HOTEND2_SH_C_COEFF, 0, HOTEND2_PULLUP_RESISTOR_OHMS, HOTEND2_RESISTANCE_25C_OHMS, 0, 0, HOTEND2_BETA, 0 }, #endif #if TEMP_SENSOR_3_IS_CUSTOM - { true, 0, 0, HOTEND3_PULLUP_RESISTOR_OHMS, HOTEND3_RESISTANCE_25C_OHMS, 0, 0, HOTEND3_BETA, 0 }, + { true, HOTEND3_SH_C_COEFF, 0, HOTEND3_PULLUP_RESISTOR_OHMS, HOTEND3_RESISTANCE_25C_OHMS, 0, 0, HOTEND3_BETA, 0 }, #endif #if TEMP_SENSOR_4_IS_CUSTOM - { true, 0, 0, HOTEND4_PULLUP_RESISTOR_OHMS, HOTEND4_RESISTANCE_25C_OHMS, 0, 0, HOTEND4_BETA, 0 }, + { true, HOTEND4_SH_C_COEFF, 0, HOTEND4_PULLUP_RESISTOR_OHMS, HOTEND4_RESISTANCE_25C_OHMS, 0, 0, HOTEND4_BETA, 0 }, #endif #if TEMP_SENSOR_5_IS_CUSTOM - { true, 0, 0, HOTEND5_PULLUP_RESISTOR_OHMS, HOTEND5_RESISTANCE_25C_OHMS, 0, 0, HOTEND5_BETA, 0 }, + { true, HOTEND5_SH_C_COEFF, 0, HOTEND5_PULLUP_RESISTOR_OHMS, HOTEND5_RESISTANCE_25C_OHMS, 0, 0, HOTEND5_BETA, 0 }, #endif #if TEMP_SENSOR_6_IS_CUSTOM - { true, 0, 0, HOTEND6_PULLUP_RESISTOR_OHMS, HOTEND6_RESISTANCE_25C_OHMS, 0, 0, HOTEND6_BETA, 0 }, + { true, HOTEND6_SH_C_COEFF, 0, HOTEND6_PULLUP_RESISTOR_OHMS, HOTEND6_RESISTANCE_25C_OHMS, 0, 0, HOTEND6_BETA, 0 }, #endif #if TEMP_SENSOR_7_IS_CUSTOM - { true, 0, 0, HOTEND7_PULLUP_RESISTOR_OHMS, HOTEND7_RESISTANCE_25C_OHMS, 0, 0, HOTEND7_BETA, 0 }, + { true, HOTEND7_SH_C_COEFF, 0, HOTEND7_PULLUP_RESISTOR_OHMS, HOTEND7_RESISTANCE_25C_OHMS, 0, 0, HOTEND7_BETA, 0 }, #endif #if TEMP_SENSOR_BED_IS_CUSTOM - { true, 0, 0, BED_PULLUP_RESISTOR_OHMS, BED_RESISTANCE_25C_OHMS, 0, 0, BED_BETA, 0 }, + { true, BED_SH_C_COEFF, 0, BED_PULLUP_RESISTOR_OHMS, BED_RESISTANCE_25C_OHMS, 0, 0, BED_BETA, 0 }, #endif #if TEMP_SENSOR_CHAMBER_IS_CUSTOM - { true, 0, 0, CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS, 0, 0, CHAMBER_BETA, 0 }, + { true, CHAMBER_SH_C_COEFF, 0, CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS, 0, 0, CHAMBER_BETA, 0 }, #endif #if TEMP_SENSOR_COOLER_IS_CUSTOM - { true, 0, 0, COOLER_PULLUP_RESISTOR_OHMS, COOLER_RESISTANCE_25C_OHMS, 0, 0, COOLER_BETA, 0 }, + { true, COOLER_SH_C_COEFF, 0, COOLER_PULLUP_RESISTOR_OHMS, COOLER_RESISTANCE_25C_OHMS, 0, 0, COOLER_BETA, 0 }, #endif #if TEMP_SENSOR_PROBE_IS_CUSTOM - { true, 0, 0, PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS, 0, 0, PROBE_BETA, 0 }, + { true, PROBE_SH_C_COEFF, 0, PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS, 0, 0, PROBE_BETA, 0 }, #endif #if TEMP_SENSOR_BOARD_IS_CUSTOM - { true, 0, 0, BOARD_PULLUP_RESISTOR_OHMS, BOARD_RESISTANCE_25C_OHMS, 0, 0, BOARD_BETA, 0 }, + { true, BOARD_SH_C_COEFF, 0, BOARD_PULLUP_RESISTOR_OHMS, BOARD_RESISTANCE_25C_OHMS, 0, 0, BOARD_BETA, 0 }, #endif #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM - { true, 0, 0, REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS, 0, 0, REDUNDANT_BETA, 0 }, + { true, REDUNDANT_SH_C_COEFF, 0, REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS, 0, 0, REDUNDANT_BETA, 0 }, #endif }; COPY(user_thermistor, default_user_thermistor); From 173eb3ff715535e1144de9961700363dc5780884 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 16 Jul 2022 16:26:36 -0500 Subject: [PATCH 03/54] =?UTF-8?q?=F0=9F=9A=B8=20Renumber=20EXP=20pins=20to?= =?UTF-8?q?=20match=20schematics/RRF/Klipper?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 86 +++---- Marlin/src/pins/esp32/pins_PANDA_common.h | 60 ++--- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 82 +++---- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 212 ++++++++-------- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 210 ++++++++-------- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 54 ++-- Marlin/src/pins/lpc1768/pins_EMOTRONIC.h | 68 +++--- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 142 +++++------ .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 84 +++---- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 138 +++++------ Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 70 +++--- Marlin/src/pins/ramps/pins_MKS_GEN_13.h | 42 ++-- Marlin/src/pins/ramps/pins_RAMPS.h | 230 +++++++++--------- Marlin/src/pins/ramps/pins_RAMPS_PLUS.h | 42 ++-- Marlin/src/pins/ramps/pins_ZRIB_V53.h | 58 ++--- Marlin/src/pins/sam/pins_RAMPS_FD_V1.h | 98 ++++---- Marlin/src/pins/sam/pins_RAMPS_SMART.h | 42 ++-- Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 94 +++---- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 98 ++++---- .../src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h | 170 ++++++------- Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h | 174 ++++++------- .../src/pins/sanguino/pins_MELZI_CREALITY.h | 10 +- Marlin/src/pins/sanguino/pins_ZMIB_V2.h | 48 ++-- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 30 +-- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 60 ++--- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 112 ++++----- .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 42 ++-- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 20 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h | 66 ++--- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 80 +++--- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 60 ++--- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 142 +++++------ .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 110 ++++----- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h | 64 ++--- Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h | 48 ++-- Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h | 114 ++++----- Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h | 86 +++---- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 116 ++++----- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 40 +-- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 126 +++++----- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 166 ++++++------- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 180 +++++++------- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 182 +++++++------- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 80 +++--- .../pins/stm32f4/pins_FYSETC_CHEETAH_V20.h | 112 ++++----- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 122 +++++----- .../pins/stm32f4/pins_MKS_MONSTER8_common.h | 116 ++++----- .../stm32f4/pins_MKS_ROBIN_NANO_V3_common.h | 116 ++++----- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 112 ++++----- .../src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h | 68 +++--- Marlin/src/pins/stm32f4/pins_VAKE403D.h | 66 ++--- .../pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h | 78 +++--- .../pins/stm32h7/pins_BTT_SKR_V3_0_common.h | 184 +++++++------- 53 files changed, 2604 insertions(+), 2606 deletions(-) diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index 110c6f83ef..3762f64033 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -119,72 +119,72 @@ /** * ------ ------ - * (BEEPER) 149 |10 9 | 13 (BTN_ENC) (SPI MISO) 19 |10 9 | 18 (SPI SCK) - * (LCD_EN) 21 | 8 7 | 4 (LCD_RS) (BTN_EN1) 14 | 8 7 | 5 (SPI CS) - * (LCD_D4) 0 6 5 | 16 (LCD_D5) (BTN_EN2) 12 6 5 | 23 (SPI MOSI) - * (LCD_D6) 15 | 4 3 | 17 (LCD_D7) (SPI_DET) 34 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | 3.3V + * (BEEPER) 149 | 1 2 | 13 (BTN_ENC) (SPI MISO) 19 | 1 2 | 18 (SPI SCK) + * (LCD_EN) 21 | 3 4 | 4 (LCD_RS) (BTN_EN1) 14 | 3 4 | 5 (SPI CS) + * (LCD_D4) 0 5 6 | 16 (LCD_D5) (BTN_EN2) 12 5 6 | 23 (SPI MOSI) + * (LCD_D6) 15 | 7 8 | 17 (LCD_D7) (SPI_DET) 34 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 3.3V * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN 17 -#define EXP1_04_PIN 15 -#define EXP1_05_PIN 16 -#define EXP1_06_PIN 0 -#define EXP1_07_PIN 4 -#define EXP1_08_PIN 21 -#define EXP1_09_PIN 13 -#define EXP1_10_PIN 149 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN 34 -#define EXP2_05_PIN 23 -#define EXP2_06_PIN 12 -#define EXP2_07_PIN 5 -#define EXP2_08_PIN 14 -#define EXP2_09_PIN 18 -#define EXP2_10_PIN 19 +#define EXP1_08_PIN 17 +#define EXP1_07_PIN 15 +#define EXP1_06_PIN 16 +#define EXP1_05_PIN 0 +#define EXP1_04_PIN 4 +#define EXP1_03_PIN 21 +#define EXP1_02_PIN 13 +#define EXP1_01_PIN 149 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN 34 +#define EXP2_06_PIN 23 +#define EXP2_05_PIN 12 +#define EXP2_04_PIN 5 +#define EXP2_03_PIN 14 +#define EXP2_02_PIN 18 +#define EXP2_01_PIN 19 // // MicroSD card // -//#define SD_MOSI_PIN EXP2_05_PIN // uses esp32 default 23 -//#define SD_MISO_PIN EXP2_10_PIN // uses esp32 default 19 -//#define SD_SCK_PIN EXP2_09_PIN // uses esp32 default 18 -#define SDSS EXP2_07_PIN -#define SD_DETECT_PIN EXP2_04_PIN // IO34 default is SD_DET signal (Jump to SDDET) +//#define SD_MOSI_PIN EXP2_06_PIN // uses esp32 default 23 +//#define SD_MISO_PIN EXP2_01_PIN // uses esp32 default 19 +//#define SD_SCK_PIN EXP2_02_PIN // uses esp32 default 18 +#define SDSS EXP2_04_PIN +#define SD_DETECT_PIN EXP2_07_PIN // IO34 default is SD_DET signal (Jump to SDDET) #define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers #if HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_RS EXP1_07_PIN - #define BTN_ENC EXP1_09_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BEEPER_PIN EXP1_01_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #define LCD_BACKLIGHT_PIN -1 #if ENABLED(MKS_MINI_12864) // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) - #define DOGLCD_CS EXP1_05_PIN - #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN #define LCD_RESET_PIN -1 #elif ENABLED(FYSETC_MINI_12864_2_1) // MKS_MINI_12864_V3, BTT_MINI_12864_V1, FYSETC_MINI_12864_2_1 - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN - #define LCD_RESET_PIN EXP1_06_PIN - #define NEOPIXEL_PIN EXP1_05_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define LCD_RESET_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif #else - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #endif #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 diff --git a/Marlin/src/pins/esp32/pins_PANDA_common.h b/Marlin/src/pins/esp32/pins_PANDA_common.h index 7deeca3f62..dfd0525521 100644 --- a/Marlin/src/pins/esp32/pins_PANDA_common.h +++ b/Marlin/src/pins/esp32/pins_PANDA_common.h @@ -82,47 +82,47 @@ #endif /** ------ ------ - * (MISO 19?) |10 9 | (18 SCK?) (BEEPER) 129 |10 9 | 12 (^ENC) - * (EN1) 33 | 8 7 | (5 SDSS?) (EN) 26 | 8 7 | 27 (RS) - * (EN2) 32 6 5 | (23 MOSI?) (D4) 14 | 6 5 -- - * (SDDET 2?) | 4 3 | (RESET) -- | 4 3 | -- - * -- | 2 1 | -- (GND) | 2 1 | (5V) + * (MISO 19?) | 1 2 | (18 SCK?) (BEEPER) 129 | 1 2 | 12 (^ENC) + * (EN1) 33 | 3 4 | (5 SDSS?) (EN) 26 | 3 4 | 27 (RS) + * (EN2) 32 5 6 | (23 MOSI?) (D4) 14 | 5 6 -- + * (SDDET 2?) | 7 8 | (RESET) -- | 7 8 | -- + * -- | 9 10 | -- (GND) | 9 10 | (5V) * ------ ------ * EXP2 EXP1 */ -#define EXP1_06_PIN 14 -#define EXP1_07_PIN 27 -#define EXP1_08_PIN 26 -#define EXP1_09_PIN 12 -#define EXP1_10_PIN 129 - -#define EXP2_04_PIN 2 // ? -#define EXP2_05_PIN 23 // ? -#define EXP2_06_PIN 32 -#define EXP2_07_PIN 5 // ? -#define EXP2_08_PIN 33 -#define EXP2_09_PIN 18 // ? -#define EXP2_10_PIN 19 // ? +#define EXP1_05_PIN 14 +#define EXP1_04_PIN 27 +#define EXP1_03_PIN 26 +#define EXP1_02_PIN 12 +#define EXP1_01_PIN 129 + +#define EXP2_07_PIN 2 // ? +#define EXP2_06_PIN 23 // ? +#define EXP2_05_PIN 32 +#define EXP2_04_PIN 5 // ? +#define EXP2_03_PIN 33 +#define EXP2_02_PIN 18 // ? +#define EXP2_01_PIN 19 // ? // // SD Card // #if ENABLED(SDSUPPORT) - #define SD_MOSI_PIN EXP2_05_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SDSS EXP2_07_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SDSS EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif #if HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN - #define BTN_ENC EXP1_09_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #endif diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index f0f57c63ee..ba042e3bf5 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -58,31 +58,31 @@ /** ------ ------ - * 1.30 |10 9 | 2.11 0.17 |10 9 | 0.15 - * 0.18 | 8 7 | 0.16 3.26 | 8 7 | 1.23 - * 0.15 6 5 | -- 3.25 6 5 | 0.18 - * -- | 4 3 | -- 1.31 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * 1.30 | 1 2 | 2.11 0.17 | 1 2 | 0.15 + * 0.18 | 3 4 | 0.16 3.26 | 3 4 | 1.23 + * 0.15 5 6 | -- 3.25 5 6 | 0.18 + * -- | 7 8 | -- 1.31 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN -1 // NC -#define EXP1_04_PIN -1 // NC -#define EXP1_05_PIN -1 // NC -#define EXP1_06_PIN P0_15 -#define EXP1_07_PIN P0_16 -#define EXP1_08_PIN P0_18 -#define EXP1_09_PIN P2_11 -#define EXP1_10_PIN P1_30 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN P1_31 -#define EXP2_05_PIN P0_18 -#define EXP2_06_PIN P3_25 -#define EXP2_07_PIN P1_23 -#define EXP2_08_PIN P3_26 -#define EXP2_09_PIN P0_15 -#define EXP2_10_PIN P0_17 +#define EXP1_08_PIN -1 // NC +#define EXP1_07_PIN -1 // NC +#define EXP1_06_PIN -1 // NC +#define EXP1_05_PIN P0_15 +#define EXP1_04_PIN P0_16 +#define EXP1_03_PIN P0_18 +#define EXP1_02_PIN P2_11 +#define EXP1_01_PIN P1_30 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN P1_31 +#define EXP2_06_PIN P0_18 +#define EXP2_05_PIN P3_25 +#define EXP2_04_PIN P1_23 +#define EXP2_03_PIN P3_26 +#define EXP2_02_PIN P0_15 +#define EXP2_01_PIN P0_17 /** * LCD / Controller @@ -100,23 +100,23 @@ #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif #elif HAS_WIRED_LCD - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN - #define LCD_SDSS EXP2_07_PIN - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP2_05_PIN - #define LCD_PINS_D4 EXP2_09_PIN + #define LCD_SDSS EXP2_04_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP2_06_PIN + #define LCD_PINS_D4 EXP2_02_PIN #if ENABLED(MKS_MINI_12864) #define DOGLCD_CS P2_06 - #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_A0 EXP1_04_PIN #endif #endif // HAS_WIRED_LCD @@ -165,10 +165,10 @@ // When using any TMC SPI-based drivers, software SPI is used // because pins may be shared with the display or SD card. #define TMC_USE_SW_SPI - #define TMC_SW_MOSI EXP2_05_PIN - #define TMC_SW_MISO EXP2_10_PIN + #define TMC_SW_MOSI EXP2_06_PIN + #define TMC_SW_MISO EXP2_01_PIN // To minimize pin usage use the same clock pin as the display/SD card reader. (May generate LCD noise.) - #define TMC_SW_SCK EXP2_09_PIN + #define TMC_SW_SCK EXP2_02_PIN // If pin 2_06 is unused, it can be used for the clock to avoid the LCD noise. //#define TMC_SW_SCK P2_06 @@ -211,11 +211,11 @@ // SDCARD_CONNECTION must not be 'LCD'. Nothing should be connected to EXP1/EXP2. //#define SKR_USE_LCD_PINS_FOR_CS #if ENABLED(SKR_USE_LCD_PINS_FOR_CS) - #define X_CS_PIN EXP2_07_PIN - #define Y_CS_PIN EXP2_08_PIN - #define Z_CS_PIN EXP1_09_PIN - #define E0_CS_PIN EXP2_06_PIN - #define E1_CS_PIN EXP2_04_PIN + #define X_CS_PIN EXP2_04_PIN + #define Y_CS_PIN EXP2_03_PIN + #define Z_CS_PIN EXP1_02_PIN + #define E0_CS_PIN EXP2_05_PIN + #define E1_CS_PIN EXP2_07_PIN #endif // Example 2: A REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER @@ -228,11 +228,11 @@ #define Z_CS_PIN P2_06 // We use SD_DETECT_PIN for E0 #undef SD_DETECT_PIN - #define E0_CS_PIN EXP2_04_PIN + #define E0_CS_PIN EXP2_07_PIN // We use LCD_SDSS pin for E1 #undef LCD_SDSS #define LCD_SDSS -1 - #define E1_CS_PIN EXP2_07_PIN + #define E1_CS_PIN EXP2_04_PIN #endif // Example 3: Use the driver enable pins for chip-select. diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 4ab5b10937..4ea4687507 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -191,31 +191,31 @@ /** * ------ ------ - * (BEEPER) 1.30 |10 9 | 0.28 (BTN_ENC) (MISO) 0.17 |10 9 | 0.15 (SCK) - * (LCD_EN) 1.18 | 8 7 | 1.19 (LCD_RS) (BTN_EN1) 3.26 | 8 7 | 0.16 (SD_SS) - * (LCD_D4) 1.20 6 5 | 1.21 (LCD_D5) (BTN_EN2) 3.25 6 5 | 0.18 (MOSI) - * (LCD_D6) 1.22 | 4 3 | 1.23 (LCD_D7) (SD_DETECT) 1.31 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) 1.30 | 1 2 | 0.28 (BTN_ENC) (MISO) 0.17 | 1 2 | 0.15 (SCK) + * (LCD_EN) 1.18 | 3 4 | 1.19 (LCD_RS) (BTN_EN1) 3.26 | 3 4 | 0.16 (SD_SS) + * (LCD_D4) 1.20 5 6 | 1.21 (LCD_D5) (BTN_EN2) 3.25 5 6 | 0.18 (MOSI) + * (LCD_D6) 1.22 | 7 8 | 1.23 (LCD_D7) (SD_DETECT) 1.31 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN P1_23 -#define EXP1_04_PIN P1_22 -#define EXP1_05_PIN P1_21 -#define EXP1_06_PIN P1_20 -#define EXP1_07_PIN P1_19 -#define EXP1_08_PIN P1_18 -#define EXP1_09_PIN P0_28 -#define EXP1_10_PIN P1_30 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN P1_31 -#define EXP2_05_PIN P0_18 -#define EXP2_06_PIN P3_25 -#define EXP2_07_PIN P0_16 -#define EXP2_08_PIN P3_26 -#define EXP2_09_PIN P0_15 -#define EXP2_10_PIN P0_17 +#define EXP1_08_PIN P1_23 +#define EXP1_07_PIN P1_22 +#define EXP1_06_PIN P1_21 +#define EXP1_05_PIN P1_20 +#define EXP1_04_PIN P1_19 +#define EXP1_03_PIN P1_18 +#define EXP1_02_PIN P0_28 +#define EXP1_01_PIN P1_30 + +#define EXP2_08_PIN -1 +#define EXP2_07_PIN P1_31 +#define EXP2_06_PIN P0_18 +#define EXP2_05_PIN P3_25 +#define EXP2_04_PIN P0_16 +#define EXP2_03_PIN P3_26 +#define EXP2_02_PIN P0_15 +#define EXP2_01_PIN P0_17 #if HAS_WIRED_LCD #if ENABLED(ANET_FULL_GRAPHICS_LCD_ALT_WIRING) @@ -239,23 +239,23 @@ * * BEFORE AFTER * ------ ------ - * (CLK) |10 9 | (BEEPER) (BEEPER) |10 9 | -- - * -- | 8 7 | (BTN_ENC) (BTN_ENC) | 8 7 | (CLK) - * (SID) 6 5 | (BTN_EN1) (BTN_EN1) 6 5 | (SID) - * (CS) | 4 3 | (BTN_EN2) (BTN_EN2) | 4 3 | (CS) - * GND | 2 1 | 5V GND | 2 1 | 5V + * (CLK) | 1 2 | (BEEPER) (BEEPER) | 1 2 | -- + * -- | 3 4 | (BTN_ENC) (BTN_ENC) | 3 4 | (CLK) + * (SID) 5 6 | (BTN_EN1) (BTN_EN1) 5 6 | (SID) + * (CS) | 7 8 | (BTN_EN2) (BTN_EN2) | 7 8 | (CS) + * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ * LCD LCD */ - #define LCD_PINS_RS EXP1_03_PIN + #define LCD_PINS_RS EXP1_08_PIN - #define BTN_EN1 EXP1_06_PIN - #define BTN_EN2 EXP1_04_PIN - #define BTN_ENC EXP1_08_PIN + #define BTN_EN1 EXP1_05_PIN + #define BTN_EN2 EXP1_07_PIN + #define BTN_ENC EXP1_03_PIN - #define LCD_PINS_ENABLE EXP1_05_PIN - #define LCD_PINS_D4 EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_06_PIN + #define LCD_PINS_D4 EXP1_04_PIN #elif ENABLED(WYH_L12864) @@ -274,33 +274,33 @@ * * BEFORE AFTER * ______ ______ - * |10 9 | (MOSI) (MOSI) |10 9 | -- - * (BTN_ENC) | 8 7 | (SCK) (BTN_ENC) | 8 7 | (SCK) - * (BTN_EN1) 6 5 | (SID) (BTN_EN1) 6 5 | (SID) - * (BTN_EN2) | 4 3 | (CS) (BTN_EN2) | 4 3 | (CS) - * 5V | 2 1 | GND GND | 2 1 | 5V + * | 1 2 | (MOSI) (MOSI) | 1 2 | -- + * (BTN_ENC) | 3 4 | (SCK) (BTN_ENC) | 3 4 | (SCK) + * (BTN_EN1) 5 6 | (SID) (BTN_EN1) 5 6 | (SID) + * (BTN_EN2) | 7 8 | (CS) (BTN_EN2) | 7 8 | (CS) + * 5V | 9 10 | GND GND | 9 10 | 5V * ------ ------ * LCD LCD */ - #define BTN_EN1 EXP1_06_PIN - #define BTN_EN2 EXP1_04_PIN - #define BTN_ENC EXP1_08_PIN - #define DOGLCD_CS EXP1_03_PIN - #define DOGLCD_A0 EXP1_05_PIN - #define DOGLCD_SCK EXP1_07_PIN - #define DOGLCD_MOSI EXP1_10_PIN + #define BTN_EN1 EXP1_05_PIN + #define BTN_EN2 EXP1_07_PIN + #define BTN_ENC EXP1_03_PIN + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_06_PIN + #define DOGLCD_SCK EXP1_04_PIN + #define DOGLCD_MOSI EXP1_01_PIN #define LCD_BACKLIGHT_PIN -1 #elif ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN // (58) open-drain + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_02_PIN // (58) open-drain - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif HAS_ADC_BUTTONS @@ -308,20 +308,20 @@ #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_A0_PIN EXP1_03_PIN - #define TFT_DC_PIN EXP1_03_PIN - #define TFT_CS_PIN EXP1_04_PIN - #define TFT_RESET_PIN EXP1_07_PIN - #define TFT_BACKLIGHT_PIN EXP1_08_PIN + #define TFT_A0_PIN EXP1_08_PIN + #define TFT_DC_PIN EXP1_08_PIN + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_RESET_PIN EXP1_04_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN - //#define TFT_RST_PIN EXP2_04_PIN - #define TFT_MOSI_PIN EXP2_05_PIN - #define TFT_SCK_PIN EXP2_09_PIN - #define TFT_MISO_PIN EXP2_10_PIN + //#define TFT_RST_PIN EXP2_07_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_ENC EXP1_02_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 @@ -369,90 +369,90 @@ #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #else // !CR10_STOCKDISPLAY - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN // (31) J3-2 & AUX-4 - #define BTN_EN2 EXP2_06_PIN // (33) J3-4 & AUX-4 - #define BTN_ENC EXP1_09_PIN // (58) open-drain + #define BTN_EN1 EXP2_03_PIN // (31) J3-2 & AUX-4 + #define BTN_EN2 EXP2_05_PIN // (33) J3-4 & AUX-4 + #define BTN_ENC EXP1_02_PIN // (58) open-drain - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN - #define LCD_SDSS EXP2_07_PIN // (16) J3-7 & AUX-4 - #define SD_DETECT_PIN EXP2_04_PIN // (49) (NOT 5V tolerant) + #define LCD_SDSS EXP2_04_PIN // (16) J3-7 & AUX-4 + #define SD_DETECT_PIN EXP2_07_PIN // (49) (NOT 5V tolerant) #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #define LCD_BACKLIGHT_PIN -1 #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS EXP1_05_PIN - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #elif ENABLED(ENDER2_STOCKDISPLAY) /** * Creality Ender-2 display pinout * ------ - * (SCK) P1_30 |10 9 | P0_28 (BTN_ENC) - * (BTN_EN1) P1_18 | 8 7 | P1_19 (RESET) - * (BTN_EN2) P1_20 6 5 | P1_21 (LCD_A0) - * (LCD_CS) P1_22 | 4 3 | P1_23 (MOSI) - * GND | 2 1 | 5V + * (SCK) P1_30 | 1 2 | P0_28 (BTN_ENC) + * (BTN_EN1) P1_18 | 3 4 | P1_19 (RESET) + * (BTN_EN2) P1_20 5 6 | P1_21 (LCD_A0) + * (LCD_CS) P1_22 | 7 8 | P1_23 (MOSI) + * GND | 9 10 | 5V * ------ * EXP1 */ - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN - #define DOGLCD_CS EXP1_04_PIN - #define DOGLCD_A0 EXP1_05_PIN - #define DOGLCD_SCK EXP1_10_PIN - #define DOGLCD_MOSI EXP1_03_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_02_PIN + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_A0 EXP1_06_PIN + #define DOGLCD_SCK EXP1_01_PIN + #define DOGLCD_MOSI EXP1_08_PIN #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 #endif #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -467,11 +467,11 @@ #endif // HAS_WIRED_LCD #if NEED_TOUCH_PINS - #define TOUCH_CS_PIN EXP1_06_PIN - #define TOUCH_SCK_PIN EXP2_09_PIN - #define TOUCH_MOSI_PIN EXP2_05_PIN - #define TOUCH_MISO_PIN EXP2_10_PIN - #define TOUCH_INT_PIN EXP1_05_PIN + #define TOUCH_CS_PIN EXP1_05_PIN + #define TOUCH_SCK_PIN EXP2_02_PIN + #define TOUCH_MOSI_PIN EXP2_06_PIN + #define TOUCH_MISO_PIN EXP2_01_PIN + #define TOUCH_INT_PIN EXP1_06_PIN #endif /** diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index b50e8e5780..8f0f46ad85 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -246,41 +246,41 @@ #endif /** ------ ------ - * 1.30 |10 9 | 0.28 0.17 |10 9 | 0.15 - * 1.18 | 8 7 | 1.19 3.26 | 8 7 | 0.16 - * 1.20 6 5 | 1.21 3.25 6 5 | 0.18 - * 1.22 | 4 3 | 1.23 1.31 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * 1.30 | 1 2 | 0.28 0.17 | 1 2 | 0.15 + * 1.18 | 3 4 | 1.19 3.26 | 3 4 | 0.16 + * 1.20 5 6 | 1.21 3.25 5 6 | 0.18 + * 1.22 | 7 8 | 1.23 1.31 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN P1_23 -#define EXP1_04_PIN P1_22 -#define EXP1_05_PIN P1_21 -#define EXP1_06_PIN P1_20 -#define EXP1_07_PIN P1_19 -#define EXP1_08_PIN P1_18 -#define EXP1_09_PIN P0_28 -#define EXP1_10_PIN P1_30 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN P1_31 -#define EXP2_05_PIN P0_18 -#define EXP2_06_PIN P3_25 -#define EXP2_07_PIN P0_16 -#define EXP2_08_PIN P3_26 -#define EXP2_09_PIN P0_15 -#define EXP2_10_PIN P0_17 +#define EXP1_08_PIN P1_23 +#define EXP1_07_PIN P1_22 +#define EXP1_06_PIN P1_21 +#define EXP1_05_PIN P1_20 +#define EXP1_04_PIN P1_19 +#define EXP1_03_PIN P1_18 +#define EXP1_02_PIN P0_28 +#define EXP1_01_PIN P1_30 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN P1_31 +#define EXP2_06_PIN P0_18 +#define EXP2_05_PIN P3_25 +#define EXP2_04_PIN P0_16 +#define EXP2_03_PIN P3_26 +#define EXP2_02_PIN P0_15 +#define EXP2_01_PIN P0_17 #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI // RET6 DWIN ENCODER LCD - #define BTN_ENC EXP1_06_PIN - #define BTN_EN1 EXP1_03_PIN - #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_05_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_07_PIN #ifndef BEEPER_PIN - #define BEEPER_PIN EXP1_05_PIN + #define BEEPER_PIN EXP1_06_PIN #endif #elif HAS_WIRED_LCD @@ -300,24 +300,24 @@ * * BEFORE AFTER * ------ ------ - * (BEEPER) | 10 9 | (CLK) (BEEPER) | 10 9 | (CLK) - * (BTN_ENC) | 8 7 | -- (BTN_ENC) | 8 7 | -- - * (BTN_EN1) 6 5 | (SID) (BTN_EN1) 6 5 | (SID) - * (BTN_EN2) | 4 3 | (CS) (BTN_EN2) | 4 3 | (CS) - * 5V | 2 1 | GND GND | 2 1 | 5V + * (BEEPER) | 1 2 | (CLK) (BEEPER) | 1 2 | (CLK) + * (BTN_ENC) | 3 4 | -- (BTN_ENC) | 3 4 | -- + * (BTN_EN1) 5 6 | (SID) (BTN_EN1) 5 6 | (SID) + * (BTN_EN2) | 7 8 | (CS) (BTN_EN2) | 7 8 | (CS) + * 5V | 9 10 | GND GND | 9 10 | 5V * ------ ------ * LCD LCD */ - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP1_05_PIN - #define BTN_EN2 EXP1_04_PIN - #define BTN_ENC EXP1_10_PIN + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_07_PIN + #define BTN_ENC EXP1_01_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define BEEPER_PIN EXP1_03_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define BEEPER_PIN EXP1_08_PIN #elif ENABLED(ANET_FULL_GRAPHICS_LCD) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING @@ -336,147 +336,147 @@ * * BEFORE AFTER * ------ ------ - * (BEEPER) |10 9 | (CLK) (BEEPER) |10 9 | -- - * (BTN_ENC) | 8 7 | -- (BTN_ENC) | 8 7 | (CLK) - * (BTN_EN1) 6 5 | (SID) (BTN_EN1) 6 5 | (SID) - * (BTN_EN2) | 4 3 | (CS) (BTN_EN2) | 4 3 | (CS) - * 5V | 2 1 | GND GND | 2 1 | 5V + * (BEEPER) | 1 2 | (CLK) (BEEPER) | 1 2 | -- + * (BTN_ENC) | 3 4 | -- (BTN_ENC) | 3 4 | (CLK) + * (BTN_EN1) 5 6 | (SID) (BTN_EN1) 5 6 | (SID) + * (BTN_EN2) | 7 8 | (CS) (BTN_EN2) | 7 8 | (CS) + * 5V | 9 10 | GND GND | 9 10 | 5V * ------ ------ * LCD LCD */ - #define LCD_PINS_RS EXP1_03_PIN + #define LCD_PINS_RS EXP1_08_PIN - #define BTN_EN1 EXP1_06_PIN - #define BTN_EN2 EXP1_04_PIN - #define BTN_ENC EXP1_08_PIN + #define BTN_EN1 EXP1_05_PIN + #define BTN_EN2 EXP1_07_PIN + #define BTN_ENC EXP1_03_PIN - #define LCD_PINS_ENABLE EXP1_05_PIN - #define LCD_PINS_D4 EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_06_PIN + #define LCD_PINS_D4 EXP1_04_PIN - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #elif ENABLED(CR10_STOCKDISPLAY) - #define BTN_ENC EXP1_09_PIN // (58) open-drain - #define LCD_PINS_RS EXP1_04_PIN + #define BTN_ENC EXP1_02_PIN // (58) open-drain + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(ENDER2_STOCKDISPLAY) /** Creality Ender-2 display pinout * ------ - * (SCK) 1.30 |10 9 | 0.28 (BTN_ENC) - * (BTN_EN1) 1.18 | 8 7 | 1.19 (RESET) - * (BTN_EN2) 1.20 6 5 | 1.21 (LCD_A0) - * (LCD_RS) 1.22 | 4 3 | 1.23 (MOSI) - * GND | 2 1 | 5V + * (SCK) 1.30 | 1 2 | 0.28 (BTN_ENC) + * (BTN_EN1) 1.18 | 3 4 | 1.19 (RESET) + * (BTN_EN2) 1.20 5 6 | 1.21 (LCD_A0) + * (LCD_RS) 1.22 | 7 8 | 1.23 (MOSI) + * GND | 9 10 | 5V * ------ * EXP1 */ - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_02_PIN - #define DOGLCD_CS EXP1_04_PIN - #define DOGLCD_A0 EXP1_05_PIN - #define DOGLCD_SCK EXP1_10_PIN - #define DOGLCD_MOSI EXP1_03_PIN + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_A0 EXP1_06_PIN + #define DOGLCD_SCK EXP1_01_PIN + #define DOGLCD_MOSI EXP1_08_PIN #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_CS_PIN EXP1_04_PIN - #define TFT_A0_PIN EXP1_03_PIN - #define TFT_DC_PIN EXP1_03_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_BACKLIGHT_PIN EXP1_08_PIN - #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_A0_PIN EXP1_08_PIN + #define TFT_DC_PIN EXP1_08_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_RESET_PIN EXP1_04_PIN #define LCD_USE_DMA_SPI - #define TOUCH_INT_PIN EXP1_05_PIN - #define TOUCH_CS_PIN EXP1_06_PIN + #define TOUCH_INT_PIN EXP1_06_PIN + #define TOUCH_CS_PIN EXP1_05_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 // SPI 1 - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN #define TFT_BUFFER_SIZE 2400 #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #else - #define BTN_ENC EXP1_09_PIN // (58) open-drain - #define LCD_PINS_RS EXP1_07_PIN + #define BTN_ENC EXP1_02_PIN // (58) open-drain + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN // (31) J3-2 & AUX-4 - #define BTN_EN2 EXP2_06_PIN // (33) J3-4 & AUX-4 + #define BTN_EN1 EXP2_03_PIN // (31) J3-2 & AUX-4 + #define BTN_EN2 EXP2_05_PIN // (33) J3-4 & AUX-4 - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN - #define LCD_SDSS EXP2_07_PIN // (16) J3-7 & AUX-4 + #define LCD_SDSS EXP2_04_PIN // (16) J3-7 & AUX-4 #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #define LCD_BACKLIGHT_PIN -1 #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS EXP1_05_PIN - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #define FORCE_SOFT_SPI #endif #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN EXP1_03_PIN // Detect the presence of the encoder + #define BTN_ENC_EN EXP1_08_PIN // Detect the presence of the encoder #endif #endif diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 37d0cb7fb1..ec74cc640e 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -134,8 +134,8 @@ #define SD_SCK_PIN P0_15 #define SD_MISO_PIN P0_17 #define SD_MOSI_PIN P0_18 - #define SD_SS_PIN EXP2_07_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_SS_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN @@ -152,11 +152,11 @@ #if ENABLED(BTT_MOTOR_EXPANSION) /** * ------ ------ - * (M3STP) |10 9 | (M3DIR) (M3DIAG) |10 9 | (M3RX) - * (M2STP) | 8 7 | (M2DIR) (M2DIAG) | 8 7 | (M2RX) - * (M1DIR) 6 5 | (M1STP) (M1DIAG) 6 5 | (M1RX) - * (M1EN) | 4 3 | -- (M3EN) | 4 3 | (M2EN) - * GND | 2 1 | -- GND | 2 1 | -- + * (M3STP) | 1 2 | (M3DIR) (M3DIAG) | 1 2 | (M3RX) + * (M2STP) | 3 4 | (M2DIR) (M2DIAG) | 3 4 | (M2RX) + * (M1DIR) 5 6 | (M1STP) (M1DIAG) 5 6 | (M1RX) + * (M1EN) | 7 8 | -- (M3EN) | 7 8 | (M2EN) + * GND | 9 10 | -- GND | 9 10 | -- * ------ ------ * EXP2 EXP1 * @@ -164,46 +164,46 @@ */ // M1 on Driver Expansion Module - #define E2_STEP_PIN EXP2_05_PIN - #define E2_DIR_PIN EXP2_06_PIN - #define E2_ENABLE_PIN EXP2_04_PIN + #define E2_STEP_PIN EXP2_06_PIN + #define E2_DIR_PIN EXP2_05_PIN + #define E2_ENABLE_PIN EXP2_07_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E2_DIAG_PIN EXP1_06_PIN - #define E2_CS_PIN EXP1_05_PIN + #define E2_DIAG_PIN EXP1_05_PIN + #define E2_CS_PIN EXP1_06_PIN #if HAS_TMC_UART - #define E2_SERIAL_TX_PIN EXP1_05_PIN + #define E2_SERIAL_TX_PIN EXP1_06_PIN #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN #endif #endif // M2 on Driver Expansion Module - #define E3_STEP_PIN EXP2_08_PIN - #define E3_DIR_PIN EXP2_07_PIN + #define E3_STEP_PIN EXP2_03_PIN + #define E3_DIR_PIN EXP2_04_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E3_ENABLE_PIN EXP1_03_PIN - #define E3_DIAG_PIN EXP1_08_PIN - #define E3_CS_PIN EXP1_07_PIN + #define E3_ENABLE_PIN EXP1_08_PIN + #define E3_DIAG_PIN EXP1_03_PIN + #define E3_CS_PIN EXP1_04_PIN #if HAS_TMC_UART - #define E3_SERIAL_TX_PIN EXP1_07_PIN + #define E3_SERIAL_TX_PIN EXP1_04_PIN #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN #endif #else - #define E3_ENABLE_PIN EXP2_04_PIN + #define E3_ENABLE_PIN EXP2_07_PIN #endif // M3 on Driver Expansion Module - #define E4_STEP_PIN EXP2_10_PIN - #define E4_DIR_PIN EXP2_09_PIN + #define E4_STEP_PIN EXP2_01_PIN + #define E4_DIR_PIN EXP2_02_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E4_ENABLE_PIN EXP1_04_PIN - #define E4_DIAG_PIN EXP1_10_PIN - #define E4_CS_PIN EXP1_09_PIN + #define E4_ENABLE_PIN EXP1_07_PIN + #define E4_DIAG_PIN EXP1_01_PIN + #define E4_CS_PIN EXP1_02_PIN #if HAS_TMC_UART - #define E4_SERIAL_TX_PIN EXP1_09_PIN + #define E4_SERIAL_TX_PIN EXP1_02_PIN #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN #endif #else - #define E4_ENABLE_PIN EXP2_04_PIN + #define E4_ENABLE_PIN EXP2_07_PIN #endif #endif // BTT_MOTOR_EXPANSION diff --git a/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h b/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h index 1cda5db669..59b5068eeb 100644 --- a/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h +++ b/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h @@ -91,27 +91,25 @@ // // Extension ports // -// warning: pins are backward numbered w.r.t. to the -// schematics, e.g. EXP1_01 / EXP1_02 are X1-10 / X1-9. -#define EXP1_01_PIN P0_28 // SCL0 -#define EXP1_02_PIN P0_27 // SDA0 -#define EXP1_03_PIN P0_16 // SSEL0 -#define EXP1_04_PIN P0_15 // SCK0 -#define EXP1_05_PIN P0_18 // MOSI0 -#define EXP1_06_PIN P0_17 // MISO0 -#define EXP1_07_PIN P1_31 -#define EXP1_08_PIN P1_30 -#define EXP1_09_PIN P0_02 // TX0 -#define EXP1_10_PIN P0_03 // RX0 - -#define EXP2_03_PIN P1_27 -#define EXP2_04_PIN P1_26 -#define EXP2_05_PIN P1_29 -#define EXP2_06_PIN P1_28 -#define EXP2_07_PIN P0_01 // SCL1 -#define EXP2_08_PIN P0_00 // SDA1 -#define EXP2_09_PIN P0_11 -#define EXP2_10_PIN P0_10 +#define EXP1_10_PIN P0_28 // SCL0 +#define EXP1_09_PIN P0_27 // SDA0 +#define EXP1_08_PIN P0_16 // SSEL0 +#define EXP1_07_PIN P0_15 // SCK0 +#define EXP1_06_PIN P0_18 // MOSI0 +#define EXP1_05_PIN P0_17 // MISO0 +#define EXP1_04_PIN P1_31 +#define EXP1_03_PIN P1_30 +#define EXP1_02_PIN P0_02 // TX0 +#define EXP1_01_PIN P0_03 // RX0 + +#define EXP2_08_PIN P1_27 +#define EXP2_07_PIN P1_26 +#define EXP2_06_PIN P1_29 +#define EXP2_05_PIN P1_28 +#define EXP2_04_PIN P0_01 // SCL1 +#define EXP2_03_PIN P0_00 // SDA1 +#define EXP2_02_PIN P0_11 +#define EXP2_01_PIN P0_10 // // SD Support @@ -126,11 +124,11 @@ #define SD_MOSI_PIN P0_09 #define SD_SS_PIN P0_06 #elif SD_CONNECTION_IS(LCD) - #define SD_SCK_PIN EXP1_04_PIN - #define SD_MISO_PIN EXP1_06_PIN - #define SD_MOSI_PIN EXP1_05_PIN - #define SD_SS_PIN EXP1_03_PIN - #define SD_DETECT_PIN EXP1_07_PIN + #define SD_SCK_PIN EXP1_07_PIN + #define SD_MISO_PIN EXP1_05_PIN + #define SD_MOSI_PIN EXP1_06_PIN + #define SD_SS_PIN EXP1_08_PIN + #define SD_DETECT_PIN EXP1_04_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif @@ -139,13 +137,13 @@ // LCD / Controller // #if ENABLED(EMOTION_TECH_LCD) - #define BEEPER_PIN EXP2_10_PIN - #define DOGLCD_A0 EXP2_05_PIN - #define DOGLCD_CS EXP2_07_PIN - #define DOGLCD_SCK EXP1_04_PIN - #define DOGLCD_MOSI EXP1_05_PIN - - #define BTN_EN1 EXP2_04_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP2_09_PIN + #define BEEPER_PIN EXP2_01_PIN + #define DOGLCD_A0 EXP2_06_PIN + #define DOGLCD_CS EXP2_04_PIN + #define DOGLCD_SCK EXP1_07_PIN + #define DOGLCD_MOSI EXP1_06_PIN + + #define BTN_EN1 EXP2_07_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP2_02_PIN #endif diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 95bbe17b9b..2ffaef949c 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -231,46 +231,46 @@ #define LED4_PIN P1_21 /** ------ ------ - * (BEEPER) 1.31 |10 9 | 1.30 (BTN_ENC) (MISO) 0.8 |10 9 | 0.7 (SD_SCK) - * (LCD_EN) 0.18 | 8 7 | 0.16 (LCD_RS) (BTN_EN1) 3.25 | 8 7 | 0.28 (SD_CS2) - * (LCD_D4) 0.15 6 5 | 0.17 (LCD_D5) (BTN_EN2) 3.26 6 5 | 0.9 (SD_MOSI) - * (LCD_D6) 1.0 | 4 3 | 1.22 (LCD_D7) (SD_DETECT) 0.27 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) 1.31 | 1 2 | 1.30 (BTN_ENC) (MISO) 0.8 | 1 2 | 0.7 (SD_SCK) + * (LCD_EN) 0.18 | 3 4 | 0.16 (LCD_RS) (BTN_EN1) 3.25 | 3 4 | 0.28 (SD_CS2) + * (LCD_D4) 0.15 5 6 | 0.17 (LCD_D5) (BTN_EN2) 3.26 5 6 | 0.9 (SD_MOSI) + * (LCD_D6) 1.0 | 7 8 | 1.22 (LCD_D7) (SD_DETECT) 0.27 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN P1_22 -#define EXP1_04_PIN P1_00 -#define EXP1_05_PIN P0_17 -#define EXP1_06_PIN P0_15 -#define EXP1_07_PIN P0_16 -#define EXP1_08_PIN P0_18 -#define EXP1_09_PIN P1_30 -#define EXP1_10_PIN P1_31 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN P0_27 -#define EXP2_05_PIN P0_09 -#define EXP2_06_PIN P3_26 -#define EXP2_07_PIN P0_28 -#define EXP2_08_PIN P3_25 -#define EXP2_09_PIN P0_07 -#define EXP2_10_PIN P0_08 +#define EXP1_08_PIN P1_22 +#define EXP1_07_PIN P1_00 +#define EXP1_06_PIN P0_17 +#define EXP1_05_PIN P0_15 +#define EXP1_04_PIN P0_16 +#define EXP1_03_PIN P0_18 +#define EXP1_02_PIN P1_30 +#define EXP1_01_PIN P1_31 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN P0_27 +#define EXP2_06_PIN P0_09 +#define EXP2_05_PIN P3_26 +#define EXP2_04_PIN P0_28 +#define EXP2_03_PIN P3_25 +#define EXP2_02_PIN P0_07 +#define EXP2_01_PIN P0_08 #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) - #define SD_DETECT_PIN EXP2_04_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN #if SD_CONNECTION_IS(ONBOARD) #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #else - #define SD_SS_PIN EXP2_07_PIN + #define SD_SS_PIN EXP2_04_PIN #endif #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." @@ -278,30 +278,30 @@ #if HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_CS_PIN EXP1_04_PIN - #define TFT_A0_PIN EXP1_03_PIN - #define TFT_DC_PIN EXP1_03_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_BACKLIGHT_PIN EXP1_08_PIN - #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_A0_PIN EXP1_08_PIN + #define TFT_DC_PIN EXP1_08_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_RESET_PIN EXP1_04_PIN #define LCD_USE_DMA_SPI - #define TOUCH_INT_PIN EXP1_05_PIN - #define TOUCH_CS_PIN EXP1_06_PIN + #define TOUCH_INT_PIN EXP1_06_PIN + #define TOUCH_CS_PIN EXP1_05_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 @@ -316,8 +316,8 @@ #define TFT_QUEUE_SIZE 6144 #endif - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #elif IS_TFTGLCD_PANEL @@ -325,74 +325,74 @@ #undef BTN_ENC #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif #else - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_SDSS EXP2_07_PIN + #define LCD_SDSS EXP2_04_PIN #if ENABLED(MKS_12864OLED_SSD1306) - #define LCD_PINS_DC EXP1_05_PIN - #define DOGLCD_CS EXP1_07_PIN + #define LCD_PINS_DC EXP1_06_PIN + #define DOGLCD_CS EXP1_04_PIN #define DOGLCD_A0 LCD_PINS_DC - #define DOGLCD_SCK EXP1_06_PIN - #define DOGLCD_MOSI EXP1_08_PIN + #define DOGLCD_SCK EXP1_05_PIN + #define DOGLCD_MOSI EXP1_03_PIN - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #define KILL_PIN -1 // NC #else // !MKS_12864OLED_SSD1306 - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #define LCD_BACKLIGHT_PIN -1 #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS EXP1_05_PIN - #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN #endif #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 090a2e4051..d8dae61d94 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -186,22 +186,22 @@ /** * ------ - * (BEEPER) P2_08 |10 9 | P0_16 (BTN_ENC) - * (BTN_EN1) P0_19 | 8 7 | RESET - * (BTN_EN2) P0_20 6 5 | P0_15 (LCD_D4) - * (LCD_RS) P0_17 | 4 3 | P0_18 (LCD_EN) - * GND | 2 1 | 5V + * (BEEPER) P2_08 | 1 2 | P0_16 (BTN_ENC) + * (BTN_EN1) P0_19 | 3 4 | RESET + * (BTN_EN2) P0_20 5 6 | P0_15 (LCD_D4) + * (LCD_RS) P0_17 | 7 8 | P0_18 (LCD_EN) + * GND | 9 10 | 5V * ------ * EXP */ -#define EXP1_03_PIN P0_18 -#define EXP1_04_PIN P0_17 -#define EXP1_05_PIN P0_15 -#define EXP1_06_PIN P0_20 -#define EXP1_07_PIN -1 -#define EXP1_08_PIN P0_19 -#define EXP1_09_PIN P0_16 -#define EXP1_10_PIN P2_08 +#define EXP1_08_PIN P0_18 +#define EXP1_07_PIN P0_17 +#define EXP1_06_PIN P0_15 +#define EXP1_05_PIN P0_20 +#define EXP1_04_PIN -1 +#define EXP1_03_PIN P0_19 +#define EXP1_02_PIN P0_16 +#define EXP1_01_PIN P2_08 #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING @@ -211,32 +211,32 @@ /** * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo * ------ ------ RX 8 --> 5 P0_15 - * -- |10 9 | -- (BEEPER) P2_08 |10 9 | P0_16 (BTN_ENC) TX 7 --> 9 P0_16 - * (SKR_TX1) RX | 8 7 | TX (SKR_RX1) (BTN_EN1) P0_19 | 8 7 | RESET BEEPER 5 --> 10 P2_08 - * (BTN_ENC) ENT 6 5 | BEEPER (BTN_EN2) P0_20 6 5 | P0_15 (LCD_D4) - * (BTN_E2) B | 4 3 | A (BTN_E1) (LCD_RS) P0_17 | 4 3 | P0_18 (LCD_EN) - * GND | 2 1 | 5V GND | 2 1 | 5V + * -- | 1 2 | -- (BEEPER) P2_08 | 1 2 | P0_16 (BTN_ENC) TX 7 --> 9 P0_16 + * (SKR_TX1) RX | 3 4 | TX (SKR_RX1) (BTN_EN1) P0_19 | 3 4 | RESET BEEPER 5 --> 10 P2_08 + * (BTN_ENC) ENT 5 6 | BEEPER (BTN_EN2) P0_20 5 6 | P0_15 (LCD_D4) + * (BTN_E2) B | 7 8 | A (BTN_E1) (LCD_RS) P0_17 | 7 8 | P0_18 (LCD_EN) + * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ */ - #define BEEPER_PIN EXP1_10_PIN - #define BTN_EN1 EXP1_03_PIN - #define BTN_EN2 EXP1_04_PIN - #define BTN_ENC EXP1_06_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_07_PIN + #define BTN_ENC EXP1_05_PIN #elif HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -244,24 +244,24 @@ #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_E3_TURBO.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" #endif - #define LCD_PINS_RS EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_09_PIN - #define LCD_PINS_D4 EXP1_04_PIN - #define LCD_PINS_D5 EXP1_06_PIN - #define LCD_PINS_D6 EXP1_08_PIN - #define LCD_PINS_D7 EXP1_10_PIN + #define LCD_PINS_RS EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_02_PIN + #define LCD_PINS_D4 EXP1_07_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN P1_23 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_02_PIN - #define DOGLCD_CS EXP1_04_PIN - #define DOGLCD_A0 EXP1_05_PIN - #define DOGLCD_SCK EXP1_10_PIN - #define DOGLCD_MOSI EXP1_03_PIN + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_A0 EXP1_06_PIN + #define DOGLCD_SCK EXP1_01_PIN + #define DOGLCD_MOSI EXP1_08_PIN #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index 4cff5d59e1..d137bdae91 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -270,87 +270,87 @@ #endif /** ------ ------ - * (BEEPER) 1.31 |10 9 | 1.30 (BTN_ENC) (MISO) 0.8 |10 9 | 0.7 (SD_SCK) - * (LCD_EN) 0.18 | 8 7 | 0.16 (LCD_RS) (BTN_EN1) 3.25 | 8 7 | 0.28 (SD_CS2) - * (LCD_D4) 0.15 6 5 | 0.17 (LCD_D5) (BTN_EN2) 3.26 6 5 | 0.9 (SD_MOSI) - * (LCD_D6) 1.0 | 4 3 | 1.22 (LCD_D7) (SD_DETECT) 0.27 | 4 3 | RST - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) 1.31 | 1 2 | 1.30 (BTN_ENC) (MISO) 0.8 | 1 2 | 0.7 (SD_SCK) + * (LCD_EN) 0.18 | 3 4 | 0.16 (LCD_RS) (BTN_EN1) 3.25 | 3 4 | 0.28 (SD_CS2) + * (LCD_D4) 0.15 5 6 | 0.17 (LCD_D5) (BTN_EN2) 3.26 5 6 | 0.9 (SD_MOSI) + * (LCD_D6) 1.0 | 7 8 | 1.22 (LCD_D7) (SD_DETECT) 0.27 | 7 8 | RST + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN P1_22 -#define EXP1_04_PIN P1_00 -#define EXP1_05_PIN P0_17 -#define EXP1_06_PIN P0_15 -#define EXP1_07_PIN P0_16 -#define EXP1_08_PIN P0_18 -#define EXP1_09_PIN P1_30 -#define EXP1_10_PIN P1_31 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN P0_27 -#define EXP2_05_PIN P0_09 -#define EXP2_06_PIN P3_26 -#define EXP2_07_PIN P0_28 -#define EXP2_08_PIN P3_25 -#define EXP2_09_PIN P0_07 -#define EXP2_10_PIN P0_08 +#define EXP1_08_PIN P1_22 +#define EXP1_07_PIN P1_00 +#define EXP1_06_PIN P0_17 +#define EXP1_05_PIN P0_15 +#define EXP1_04_PIN P0_16 +#define EXP1_03_PIN P0_18 +#define EXP1_02_PIN P1_30 +#define EXP1_01_PIN P1_31 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN P0_27 +#define EXP2_06_PIN P0_09 +#define EXP2_05_PIN P3_26 +#define EXP2_04_PIN P0_28 +#define EXP2_03_PIN P3_25 +#define EXP2_02_PIN P0_07 +#define EXP2_01_PIN P0_08 #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #elif HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #else - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_SDSS EXP2_07_PIN + #define LCD_SDSS EXP2_04_PIN #if ENABLED(MKS_12864OLED_SSD1306) - #define LCD_PINS_DC EXP1_05_PIN - #define DOGLCD_CS EXP1_07_PIN + #define LCD_PINS_DC EXP1_06_PIN + #define DOGLCD_CS EXP1_04_PIN #define DOGLCD_A0 LCD_PINS_DC - #define DOGLCD_SCK EXP1_06_PIN - #define DOGLCD_MOSI EXP1_08_PIN + #define DOGLCD_SCK EXP1_05_PIN + #define DOGLCD_MOSI EXP1_03_PIN - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #define KILL_PIN -1 // NC #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_CS_PIN EXP1_04_PIN - #define TFT_DC_PIN EXP1_03_PIN + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_DC_PIN EXP1_08_PIN #define TFT_A0_PIN TFT_DC_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_BACKLIGHT_PIN EXP1_08_PIN - #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_RESET_PIN EXP1_04_PIN #define LCD_USE_DMA_SPI - #define TOUCH_INT_PIN EXP1_05_PIN - #define TOUCH_CS_PIN EXP1_06_PIN + #define TOUCH_INT_PIN EXP1_06_PIN + #define TOUCH_CS_PIN EXP1_05_PIN #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 @@ -367,50 +367,50 @@ #else // !MKS_12864OLED_SSD1306 - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #define LCD_BACKLIGHT_PIN -1 #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS EXP1_05_PIN - #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN #endif #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -431,15 +431,15 @@ #endif #if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) - #define SD_DETECT_PIN EXP2_04_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN #if SD_CONNECTION_IS(ONBOARD) #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card #define SD_SS_PIN ONBOARD_SD_CS_PIN #else - #define SD_SS_PIN EXP2_07_PIN + #define SD_SS_PIN EXP2_04_PIN #endif #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index 81c7dc9403..f6d8e40844 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -157,11 +157,11 @@ /** * ------ - * P1_31 |10 9 | P1_30 - * P3_26 | 8 7 | P2_11 - * P3_25 6 5 | P0_15 - * P0_16 | 4 3 | P0_18 - * GND | 2 1 | 5V + * P1_31 | 1 2 | P1_30 + * P3_26 | 3 4 | P2_11 + * P3_25 5 6 | P0_15 + * P0_16 | 7 8 | P0_18 + * GND | 9 10 | 5V * ------ * EXP1 * @@ -171,43 +171,43 @@ * A remote SD card is currently not supported because the pins routed to the EXP2 * connector are shared with the onboard SD card. */ -#define EXP1_03_PIN P0_18 -#define EXP1_04_PIN P0_16 -#define EXP1_05_PIN P0_15 -#define EXP1_06_PIN P3_25 -#define EXP1_07_PIN P2_11 -#define EXP1_08_PIN P3_26 -#define EXP1_09_PIN P1_30 -#define EXP1_10_PIN P1_31 +#define EXP1_08_PIN P0_18 +#define EXP1_07_PIN P0_16 +#define EXP1_06_PIN P0_15 +#define EXP1_05_PIN P3_25 +#define EXP1_04_PIN P2_11 +#define EXP1_03_PIN P3_26 +#define EXP1_02_PIN P1_30 +#define EXP1_01_PIN P1_31 #if ENABLED(CR10_STOCKDISPLAY) /** ------ - * BEEPER |10 9 | ENC - * EN1 | 8 7 | KILL - * EN2 6 5 | LCD_D4 - * LCD_RS | 4 3 | LCD_EN - * GND | 2 1 | 5V + * BEEPER | 1 2 | ENC + * EN1 | 3 4 | KILL + * EN2 5 6 | LCD_D4 + * LCD_RS | 7 8 | LCD_EN + * GND | 9 10 | 5V * ------ */ - #define BEEPER_PIN EXP1_10_PIN - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN - #define KILL_PIN EXP1_07_PIN + #define BEEPER_PIN EXP1_01_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define KILL_PIN EXP1_04_PIN #elif ENABLED(MKS_MINI_12864) /** ------ - * SCK |10 9 | ENC - * EN1 | 8 7 | -- - * EN2 6 5 | A0 - * CS | 4 3 | MOSI - * GND | 2 1 | 5V + * SCK | 1 2 | ENC + * EN1 | 3 4 | -- + * EN2 5 6 | A0 + * CS | 7 8 | MOSI + * GND | 9 10 | 5V * ------ */ - #define DOGLCD_CS EXP1_04_PIN - #define DOGLCD_A0 EXP1_05_PIN - #define DOGLCD_SCK EXP1_10_PIN - #define DOGLCD_MOSI EXP1_03_PIN + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_A0 EXP1_06_PIN + #define DOGLCD_SCK EXP1_01_PIN + #define DOGLCD_MOSI EXP1_08_PIN #define LCD_CONTRAST_INIT 160 #define LCD_CONTRAST_MIN 120 #define LCD_CONTRAST_MAX 180 @@ -221,7 +221,7 @@ #endif #if EITHER(CR10_STOCKDISPLAY, MKS_MINI_12864) - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_02_PIN #endif diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index 1ba58629c1..7a8c99e3af 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -54,8 +54,8 @@ #include "pins_RAMPS.h" -#undef EXP2_03_PIN -#define EXP2_03_PIN -1 // RESET +#undef EXP2_08_PIN +#define EXP2_08_PIN -1 // RESET // // LCD / Controller @@ -85,11 +85,11 @@ * This configuration uses the following arrangement: * * ------ ------ - * ENCB |10 9 | ENCA MISO |10 9 | SCK - * BLUE_LED | 8 7 | RED_LED ENCBTN | 8 7 | SDCS - * KILL 6 5 | BEEPER 6 5 | MOSI - * A0 | 4 3 | LCD_CS SDCD | 4 3 | - * GND | 2 1 | 5V GND | 2 1 | -- + * ENCB | 1 2 | ENCA MISO | 1 2 | SCK + * BLUE_LED | 3 4 | RED_LED ENCBTN | 3 4 | SDCS + * KILL 5 6 | BEEPER 5 6 | MOSI + * A0 | 7 8 | LCD_CS SDCD | 7 8 | + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ @@ -107,24 +107,24 @@ // // VIKI2 12-wire lead // - #define SD_DETECT_PIN EXP2_04_PIN // SDCD orange/white - #define BTN_EN1 EXP1_09_PIN // ENCA white - #define BTN_EN2 EXP1_10_PIN // ENCB green - #define BTN_ENC EXP2_08_PIN // ENCBTN purple - #define DOGLCD_A0 EXP1_04_PIN // A0 brown - #define DOGLCD_CS EXP1_03_PIN // LCS green/white + #define SD_DETECT_PIN EXP2_07_PIN // SDCD orange/white + #define BTN_EN1 EXP1_02_PIN // ENCA white + #define BTN_EN2 EXP1_01_PIN // ENCB green + #define BTN_ENC EXP2_03_PIN // ENCBTN purple + #define DOGLCD_A0 EXP1_07_PIN // A0 brown + #define DOGLCD_CS EXP1_08_PIN // LCS green/white - // EXP2_10_PIN gray MISO - // EXP2_05_PIN yellow MOSI - // EXP2_09_PIN orange SCK + // EXP2_01_PIN gray MISO + // EXP2_06_PIN yellow MOSI + // EXP2_02_PIN orange SCK - //#define SDSS EXP2_07_PIN // SDCS blue + //#define SDSS EXP2_04_PIN // SDCS blue // // VIKI2 4-wire lead // - #define KILL_PIN EXP1_06_PIN // BTN blue - #define BEEPER_PIN EXP1_05_PIN // BUZZER green - #define STAT_LED_RED_PIN EXP1_07_PIN // RED-LED yellow - #define STAT_LED_BLUE_PIN EXP1_08_PIN // BLUE-LED white + #define KILL_PIN EXP1_05_PIN // BTN blue + #define BEEPER_PIN EXP1_06_PIN // BUZZER green + #define STAT_LED_RED_PIN EXP1_04_PIN // RED-LED yellow + #define STAT_LED_BLUE_PIN EXP1_03_PIN // BLUE-LED white #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 5672915b7c..a9824fbb8d 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -513,62 +513,62 @@ * LCD adapters come in different variants. The socket keys can be * on either side, and may be backwards on some boards / displays. */ -#ifndef EXP1_03_PIN +#ifndef EXP1_08_PIN - #define EXP1_03_PIN AUX4_13_PIN - #define EXP1_04_PIN AUX4_14_PIN - #define EXP1_05_PIN AUX4_15_PIN - #define EXP1_06_PIN AUX4_16_PIN - #define EXP1_07_PIN AUX4_18_PIN - #define EXP1_08_PIN AUX4_17_PIN + #define EXP1_08_PIN AUX4_13_PIN + #define EXP1_07_PIN AUX4_14_PIN + #define EXP1_06_PIN AUX4_15_PIN + #define EXP1_05_PIN AUX4_16_PIN + #define EXP1_04_PIN AUX4_18_PIN + #define EXP1_03_PIN AUX4_17_PIN - #define EXP2_04_PIN AUX3_02_PIN - #define EXP2_05_PIN AUX3_04_PIN - #define EXP2_07_PIN AUX3_06_PIN - #define EXP2_09_PIN AUX3_05_PIN - #define EXP2_10_PIN AUX3_03_PIN + #define EXP2_07_PIN AUX3_02_PIN + #define EXP2_06_PIN AUX3_04_PIN + #define EXP2_04_PIN AUX3_06_PIN + #define EXP2_02_PIN AUX3_05_PIN + #define EXP2_01_PIN AUX3_03_PIN #if ENABLED(G3D_PANEL) /** Gadgets3D Smart Adapter * ------ ------ - * 4-11 |10 9 | 4-12 (MISO) 3-03 |10 9 | 3-05 (SCK) - * 4-17 | 8 7 | 4-18 4-10 | 8 7 | 3-06 - * 4-16 6 5 | 4-15 4-09 6 5 | 3-04 (MOSI) - * 4-14 | 4 3 | 4-13 3-02 | 4 3 | 4-07 - * (GND) 4-02 | 2 1 | 4-01 (5V) -- | 2 1 | -- + * 4-11 | 1 2 | 4-12 (MISO) 3-03 | 1 2 | 3-05 (SCK) + * 4-17 | 3 4 | 4-18 4-10 | 3 4 | 3-06 + * 4-16 5 6 | 4-15 4-09 5 6 | 3-04 (MOSI) + * 4-14 | 7 8 | 4-13 3-02 | 7 8 | 4-07 + * (GND) 4-02 | 9 10 | 4-01 (5V) -- | 9 10 | -- * ------ ------ * EXP1 EXP2 */ - #define EXP1_09_PIN AUX4_12_PIN - #define EXP1_10_PIN AUX4_11_PIN + #define EXP1_02_PIN AUX4_12_PIN + #define EXP1_01_PIN AUX4_11_PIN - #define EXP2_03_PIN AUX4_07_PIN - #define EXP2_06_PIN AUX4_09_PIN - #define EXP2_08_PIN AUX4_10_PIN + #define EXP2_08_PIN AUX4_07_PIN + #define EXP2_05_PIN AUX4_09_PIN + #define EXP2_03_PIN AUX4_10_PIN #else /** Smart Adapter (c) RRD * ------ ------ - * 4-09 |10 9 | 4-10 (MISO) 3-03 |10 9 | 3-05 (SCK) - * 4-17 | 8 7 | 4-18 4-12 | 8 7 | 3-06 - * 4-16 6 5 | 4-15 4-11 6 5 | 3-04 (MOSI) - * 4-14 | 4 3 | 4-13 3-02 | 4 3 | 4-07 - * (GND) 3-07 | 2 1 | 3-01 (5V) (GND) 3-07 | 2 1 | -- + * 4-09 | 1 2 | 4-10 (MISO) 3-03 | 1 2 | 3-05 (SCK) + * 4-17 | 3 4 | 4-18 4-12 | 3 4 | 3-06 + * 4-16 5 6 | 4-15 4-11 5 6 | 3-04 (MOSI) + * 4-14 | 7 8 | 4-13 3-02 | 7 8 | 4-07 + * (GND) 3-07 | 9 10 | 3-01 (5V) (GND) 3-07 | 9 10 | -- * ------ ------ * EXP1 EXP2 */ - #define EXP1_09_PIN AUX4_10_PIN - #define EXP1_10_PIN AUX4_09_PIN + #define EXP1_02_PIN AUX4_10_PIN + #define EXP1_01_PIN AUX4_09_PIN #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) - #define EXP2_03_PIN -1 // RESET - #define EXP2_06_PIN AUX4_12_PIN - #define EXP2_08_PIN AUX4_11_PIN + #define EXP2_08_PIN -1 // RESET + #define EXP2_05_PIN AUX4_12_PIN + #define EXP2_03_PIN AUX4_11_PIN #else - #define EXP2_03_PIN AUX4_07_PIN - #define EXP2_06_PIN AUX4_11_PIN - #define EXP2_08_PIN AUX4_12_PIN + #define EXP2_08_PIN AUX4_07_PIN + #define EXP2_05_PIN AUX4_11_PIN + #define EXP2_03_PIN AUX4_12_PIN #endif #endif @@ -588,9 +588,9 @@ // #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS EXP2_04_PIN // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE EXP2_05_PIN // SID (MOSI) - #define LCD_PINS_D4 EXP2_09_PIN // SCK (CLK) clock + #define LCD_PINS_RS EXP2_07_PIN // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE EXP2_06_PIN // SID (MOSI) + #define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock #elif BOTH(IS_NEWPANEL, PANEL_ONE) @@ -603,18 +603,18 @@ #elif ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_06_PIN + #define TFTGLCD_CS EXP2_05_PIN #else #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #if !IS_NEWPANEL - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #endif #elif ENABLED(ZONESTAR_LCD) @@ -637,25 +637,25 @@ #else #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - #define LCD_PINS_DC EXP1_05_PIN // Set as output on init - #define LCD_PINS_RS EXP1_04_PIN // Pull low for 1s to init + #define LCD_PINS_DC EXP1_06_PIN // Set as output on init + #define LCD_PINS_RS EXP1_07_PIN // Pull low for 1s to init // DOGM SPI LCD Support #define DOGLCD_A0 LCD_PINS_DC - #define DOGLCD_CS EXP1_07_PIN - #define DOGLCD_MOSI EXP1_08_PIN - #define DOGLCD_SCK EXP1_06_PIN + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_MOSI EXP1_03_PIN + #define DOGLCD_SCK EXP1_05_PIN #else - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN #endif - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if !IS_NEWPANEL - #define BEEPER_PIN EXP2_06_PIN + #define BEEPER_PIN EXP2_05_PIN #endif #endif @@ -666,7 +666,7 @@ //#define SHIFT_CLK_PIN 38 //#define SHIFT_LD_PIN AUX2_08_PIN //#define SHIFT_OUT_PIN AUX2_06_PIN - //#define SHIFT_EN_PIN EXP1_08_PIN + //#define SHIFT_EN_PIN EXP1_03_PIN #endif #endif @@ -682,22 +682,22 @@ #if IS_RRD_SC - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN #else - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #endif - #define BTN_ENC EXP1_09_PIN + #define BTN_ENC EXP1_02_PIN #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif #ifndef KILL_PIN - #define KILL_PIN EXP2_03_PIN + #define KILL_PIN EXP2_08_PIN #endif #if ENABLED(BQ_LCD_SMART_CONTROLLER) @@ -717,7 +717,7 @@ #define BTN_EN2 AUX4_06_PIN #define BTN_ENC AUX4_03_PIN #define LCD_SDSS SDSS - #define KILL_PIN EXP2_03_PIN + #define KILL_PIN EXP2_08_PIN #elif ENABLED(LCD_I2C_VIKI) @@ -726,7 +726,7 @@ #define BTN_ENC -1 #define LCD_SDSS SDSS - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #elif EITHER(VIKI2, miniVIKI) @@ -734,83 +734,83 @@ #define DOGLCD_A0 AUX2_07_PIN #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #define BEEPER_PIN EXP2_06_PIN + #define BEEPER_PIN EXP2_05_PIN #define STAT_LED_RED_PIN AUX4_03_PIN - #define STAT_LED_BLUE_PIN EXP1_09_PIN + #define STAT_LED_BLUE_PIN EXP1_02_PIN #define BTN_EN1 22 #define BTN_EN2 7 #define BTN_ENC AUX4_08_PIN #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board - #define KILL_PIN EXP2_08_PIN + #define KILL_PIN EXP2_03_PIN #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define DOGLCD_CS EXP1_03_PIN - #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN - #define BEEPER_PIN EXP1_06_PIN - #define LCD_BACKLIGHT_PIN EXP2_06_PIN + #define BEEPER_PIN EXP1_05_PIN + #define LCD_BACKLIGHT_PIN EXP2_05_PIN - #define BTN_EN1 EXP1_09_PIN - #define BTN_EN2 EXP1_10_PIN - #define BTN_ENC EXP2_08_PIN + #define BTN_EN1 EXP1_02_PIN + #define BTN_EN2 EXP1_01_PIN + #define BTN_ENC EXP2_03_PIN #define LCD_SDSS SDSS - #define SD_DETECT_PIN EXP2_04_PIN - #define KILL_PIN EXP2_03_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #define KILL_PIN EXP2_08_PIN #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif #ifndef KILL_PIN - #define KILL_PIN EXP2_03_PIN + #define KILL_PIN EXP2_08_PIN #endif #if ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN // not connected to a pin #define LCD_BACKLIGHT_PIN -1 // 65 (MKS mini12864 can't adjust backlight by software!) - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #elif ENABLED(FYSETC_MINI_12864) // From https://wiki.fysetc.com/Mini12864_Panel/ - #define DOGLCD_A0 EXP1_07_PIN - #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN - #define BTN_EN1 EXP2_06_PIN - #define BTN_EN2 EXP2_08_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif @@ -840,31 +840,31 @@ #elif ENABLED(G3D_PANEL) - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN - #define SD_DETECT_PIN EXP2_04_PIN - #define KILL_PIN EXP2_03_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #define KILL_PIN EXP2_08_PIN - #define BTN_EN1 EXP2_06_PIN - #define BTN_EN2 EXP2_08_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN + #define BTN_ENC EXP1_02_PIN #elif IS_TFTGLCD_PANEL - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #else - #define BEEPER_PIN EXP2_06_PIN + #define BEEPER_PIN EXP2_05_PIN #if ENABLED(PANEL_ONE) // Buttons connect directly to AUX-2 #define BTN_EN1 AUX2_03_PIN #define BTN_EN2 AUX2_04_PIN #define BTN_ENC AUX3_02_PIN #else - #define BTN_EN1 EXP1_10_PIN - #define BTN_EN2 EXP1_09_PIN - #define BTN_ENC EXP2_08_PIN + #define BTN_EN1 EXP1_01_PIN + #define BTN_EN2 EXP1_02_PIN + #define BTN_ENC EXP2_03_PIN #endif #endif @@ -898,11 +898,11 @@ * * Board Display * ------ ------ - * (MISO) 50 |10 9 | 52 (SCK) 5V |10 9 | GND - * (BTN_EN2) 33 | 8 7 | 53 (SD_CS) RESET | 8 7 | (SD_DET) - * (BTN_EN1) 31 6 5 | 51 (MOSI) (MOSI) 6 5 | (LCD_CS) - * (SD_DET) 49 | 4 3 | RESET (SD_CS) | 4 3 | (MOD_RESET) - * GND | 2 1 | -- (SCK) | 2 1 | (MISO) + * (MISO) 50 | 1 2 | 52 (SCK) 5V | 1 2 | GND + * (BTN_EN2) 33 | 3 4 | 53 (SD_CS) RESET | 3 4 | (SD_DET) + * (BTN_EN1) 31 5 6 | 51 (MOSI) (MOSI) 5 6 | (LCD_CS) + * (SD_DET) 49 | 7 8 | RESET (SD_CS) | 7 8 | (MOD_RESET) + * GND | 9 10 | -- (SCK) | 9 10 | (MISO) * ------ ------ * EXP2 * @@ -925,11 +925,11 @@ * To fix, insert a 1N4148 diode in the MISO line. */ - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN - #define CLCD_MOD_RESET EXP2_06_PIN - #define CLCD_SPI_CS EXP2_08_PIN + #define CLCD_MOD_RESET EXP2_05_PIN + #define CLCD_SPI_CS EXP2_03_PIN #endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 diff --git a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h index 0c554c353f..f4e811b8e6 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h @@ -65,30 +65,30 @@ /** 3DYMY Expansion Headers * ------ ------ - * 37 |10 9 | 35 (MISO) 50 |10 9 | 52 (SCK) - * 31 | 8 7 | 41 29 | 8 7 | 53 - * 33 6 5 | 23 25 6 5 | 51 (MOSI) - * 42 | 4 3 | 44 49 | 4 3 | 27 - * GND | 2 1 | 5V GND | 2 1 | -- + * 37 | 1 2 | 35 (MISO) 50 | 1 2 | 52 (SCK) + * 31 | 3 4 | 41 29 | 3 4 | 53 + * 33 5 6 | 23 25 5 6 | 51 (MOSI) + * 42 | 7 8 | 44 49 | 7 8 | 27 + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN 44 -#define EXP1_04_PIN 42 -#define EXP1_05_PIN 23 -#define EXP1_06_PIN 33 -#define EXP1_07_PIN 41 -#define EXP1_08_PIN 31 -#define EXP1_09_PIN 35 -#define EXP1_10_PIN 37 +#define EXP1_08_PIN 44 +#define EXP1_07_PIN 42 +#define EXP1_06_PIN 23 +#define EXP1_05_PIN 33 +#define EXP1_04_PIN 41 +#define EXP1_03_PIN 31 +#define EXP1_02_PIN 35 +#define EXP1_01_PIN 37 -#define EXP2_03_PIN 27 -#define EXP2_04_PIN 49 -#define EXP2_05_PIN 51 -#define EXP2_06_PIN 25 -#define EXP2_07_PIN 53 -#define EXP2_08_PIN 29 -#define EXP2_09_PIN 52 -#define EXP2_10_PIN 50 +#define EXP2_08_PIN 27 +#define EXP2_07_PIN 49 +#define EXP2_06_PIN 51 +#define EXP2_05_PIN 25 +#define EXP2_04_PIN 53 +#define EXP2_03_PIN 29 +#define EXP2_02_PIN 52 +#define EXP2_01_PIN 50 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V53.h b/Marlin/src/pins/ramps/pins_ZRIB_V53.h index 48808d9601..38b8e09b03 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V53.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V53.h @@ -299,33 +299,33 @@ * LCD adapter. NOTE: These come in two variants. The socket keys can be * on either side, and may be backwards on some displays. * ------ ------ - * D37 |10 9 | D35 (MISO) D50 |10 9 | D52 (SCK) - * D17 | 8 7 | D16 D31 | 8 7 | D53 + * D37 | 1 2 | D35 (MISO) D50 | 1 2 | D52 (SCK) + * D17 | 3 4 | D16 D31 | 3 4 | D53 * D23 6 5 D25 D33 6 5 D51 (MOSI) - * D27 | 4 3 | D29 D49 | 4 3 | D41 - * GND | 2 1 | 5V GND | 2 1 | -- + * D27 | 7 8 | D29 D49 | 7 8 | D41 + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#ifndef EXP1_03_PIN - #define EXP1_03_PIN 29 - #define EXP1_04_PIN 27 - #define EXP1_05_PIN 25 - #define EXP1_06_PIN 23 - #define EXP1_07_PIN 16 - #define EXP1_08_PIN 17 - #define EXP1_09_PIN 35 - #define EXP1_10_PIN 37 - - #define EXP2_03_PIN 41 - #define EXP2_04_PIN 49 - #define EXP2_05_PIN XS6_05_PIN - #define EXP2_06_PIN 33 - #define EXP2_07_PIN 53 - #define EXP2_08_PIN 31 - #define EXP2_09_PIN XS6_03_PIN - #define EXP2_10_PIN XS6_07_PIN +#ifndef EXP1_08_PIN + #define EXP1_08_PIN 29 + #define EXP1_07_PIN 27 + #define EXP1_06_PIN 25 + #define EXP1_05_PIN 23 + #define EXP1_04_PIN 16 + #define EXP1_03_PIN 17 + #define EXP1_02_PIN 35 + #define EXP1_01_PIN 37 + + #define EXP2_08_PIN 41 + #define EXP2_07_PIN 49 + #define EXP2_06_PIN XS6_05_PIN + #define EXP2_05_PIN 33 + #define EXP2_04_PIN 53 + #define EXP2_03_PIN 31 + #define EXP2_02_PIN XS6_03_PIN + #define EXP2_01_PIN XS6_07_PIN #endif ////////////////////////// @@ -386,14 +386,14 @@ #if ENABLED(ZONESTAR_LCD) #define LCDSCREEN_NAME "LCD2004 ADCKEY" - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #define ADC_KEYPAD_PIN 10 // A10 for ADCKEY - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #endif /** diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index 4cb0f60328..e734a08943 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -135,31 +135,31 @@ #define LED_PIN 13 /** ------ ------ - * 37 |10 9 | 35 (MISO) 50 |10 9 | 76 (SCK) - * 29 | 8 7 | 27 (EN2) 31 | 8 7 | 4 (SD_SS) - * 25 6 5 | 23 (EN1) 33 6 5 | 75 (MOSI) - * 16 | 4 3 | 17 (SDD) 49 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * 37 | 1 2 | 35 (MISO) 50 | 1 2 | 76 (SCK) + * 29 | 3 4 | 27 (EN2) 31 | 3 4 | 4 (SD_SS) + * 25 5 6 | 23 (EN1) 33 5 6 | 75 (MOSI) + * 16 | 7 8 | 17 (SDD) 49 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN 17 -#define EXP1_04_PIN 16 -#define EXP1_05_PIN 23 -#define EXP1_06_PIN 25 -#define EXP1_07_PIN 27 -#define EXP1_08_PIN 29 -#define EXP1_09_PIN 35 -#define EXP1_10_PIN 37 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN 49 -#define EXP2_05_PIN 75 -#define EXP2_06_PIN 33 -#define EXP2_07_PIN 4 -#define EXP2_08_PIN 31 -#define EXP2_09_PIN 76 -#define EXP2_10_PIN 74 +#define EXP1_08_PIN 17 +#define EXP1_07_PIN 16 +#define EXP1_06_PIN 23 +#define EXP1_05_PIN 25 +#define EXP1_04_PIN 27 +#define EXP1_03_PIN 29 +#define EXP1_02_PIN 35 +#define EXP1_01_PIN 37 + +#define EXP2_08_PIN -1 +#define EXP2_07_PIN 49 +#define EXP2_06_PIN 75 +#define EXP2_05_PIN 33 +#define EXP2_04_PIN 4 +#define EXP2_03_PIN 31 +#define EXP2_02_PIN 76 +#define EXP2_01_PIN 74 // // LCD / Controller @@ -167,65 +167,65 @@ #if HAS_WIRED_LCD // ramps-fd lcd adaptor - #define BEEPER_PIN EXP1_10_PIN - #define BTN_EN1 EXP2_06_PIN - #define BTN_EN2 EXP2_08_PIN - #define BTN_ENC EXP1_09_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN + #define BTN_ENC EXP1_02_PIN + #define SD_DETECT_PIN EXP2_07_PIN #if IS_NEWPANEL - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN #endif #if ENABLED(FYSETC_MINI_12864) #define DOGLCD_CS LCD_PINS_ENABLE #define DOGLCD_A0 LCD_PINS_RS - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_06_PIN + #define RGB_LED_R_PIN EXP1_05_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_07_PIN + #define RGB_LED_G_PIN EXP1_04_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_08_PIN + #define RGB_LED_B_PIN EXP1_03_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_06_PIN + #define NEOPIXEL_PIN EXP1_05_PIN #endif #elif IS_NEWPANEL - #define LCD_PINS_D4 EXP1_05_PIN - #define LCD_PINS_D5 EXP1_06_PIN - #define LCD_PINS_D6 EXP1_07_PIN - #define LCD_PINS_D7 EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN #if ENABLED(MINIPANEL) - #define DOGLCD_CS EXP1_06_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_A0 EXP1_04_PIN #endif #endif #if EITHER(VIKI2, miniVIKI) - #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_A0 EXP1_07_PIN #define KILL_PIN 51 - #define STAT_LED_BLUE_PIN EXP1_08_PIN - #define STAT_LED_RED_PIN EXP1_05_PIN - #define DOGLCD_CS EXP1_03_PIN - #define DOGLCD_SCK EXP2_09_PIN // SCK_PIN - Required for DUE Hardware SPI - #define DOGLCD_MOSI EXP2_05_PIN // MOSI_PIN - #define DOGLCD_MISO EXP2_10_PIN // MISO_PIN + #define STAT_LED_BLUE_PIN EXP1_03_PIN + #define STAT_LED_RED_PIN EXP1_06_PIN + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_SCK EXP2_02_PIN // SCK_PIN - Required for DUE Hardware SPI + #define DOGLCD_MOSI EXP2_06_PIN // MOSI_PIN + #define DOGLCD_MISO EXP2_01_PIN // MISO_PIN #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index 2b8942c6ad..47bc8bbaa6 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -110,31 +110,31 @@ #else /** ------ ------ - * 37 |10 9 | 35 (MISO) 50 |10 9 | 52 (SCK) - * 31 | 8 7 | 41 29 | 8 7 | 53 - * 33 6 5 | 23 25 6 5 | 51 (MOSI) - * 42 | 4 3 | 44 49 | 4 3 | 27 - * GND | 2 1 | 5V GND | 2 1 | -- + * 37 | 1 2 | 35 (MISO) 50 | 1 2 | 52 (SCK) + * 31 | 3 4 | 41 29 | 3 4 | 53 + * 33 5 6 | 23 25 5 6 | 51 (MOSI) + * 42 | 7 8 | 44 49 | 7 8 | 27 + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ - #define EXP1_03_PIN 44 - #define EXP1_04_PIN 42 - #define EXP1_05_PIN 23 - #define EXP1_06_PIN 33 - #define EXP1_07_PIN 41 - #define EXP1_08_PIN 31 - #define EXP1_09_PIN 35 - #define EXP1_10_PIN 37 + #define EXP1_08_PIN 44 + #define EXP1_07_PIN 42 + #define EXP1_06_PIN 23 + #define EXP1_05_PIN 33 + #define EXP1_04_PIN 41 + #define EXP1_03_PIN 31 + #define EXP1_02_PIN 35 + #define EXP1_01_PIN 37 - #define EXP2_03_PIN 27 - #define EXP2_04_PIN 49 - #define EXP2_05_PIN 51 - #define EXP2_06_PIN 25 - #define EXP2_07_PIN 53 - #define EXP2_08_PIN 29 - #define EXP2_09_PIN 52 - #define EXP2_10_PIN 50 + #define EXP2_08_PIN 27 + #define EXP2_07_PIN 49 + #define EXP2_06_PIN 51 + #define EXP2_05_PIN 25 + #define EXP2_04_PIN 53 + #define EXP2_03_PIN 29 + #define EXP2_02_PIN 52 + #define EXP2_01_PIN 50 #endif diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 064ce2751a..4f990a0aed 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -146,7 +146,7 @@ // SPI for MAX Thermocouple /* #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN EXP1_03_PIN + #define TEMP_0_CS_PIN EXP1_08_PIN #else #define TEMP_0_CS_PIN 49 #endif @@ -185,31 +185,31 @@ /** * ------ ------ - * (BEEPER) 62 |10 9 | 40 (BTN_ENC) (MISO) 74 |10 9 | 76 (SCK) - * (LCD_EN) 64 | 8 7 | 63 (LCD_RS) (BTN_EN1) 44 | 8 7 | 10 (SD_SS) - * (LCD_D4) 48 | 6 5 50 (LCD_D5) (BTN_EN2) 42 | 6 5 75 (MOSI) - * (LCD_D6) 52 | 4 3 | 53 (LCD_D7) (SD_DETECT) 51 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) 62 | 1 2 | 40 (BTN_ENC) (MISO) 74 | 1 2 | 76 (SCK) + * (LCD_EN) 64 | 3 4 | 63 (LCD_RS) (BTN_EN1) 44 | 3 4 | 10 (SD_SS) + * (LCD_D4) 48 | 5 6 50 (LCD_D5) (BTN_EN2) 42 | 5 6 75 (MOSI) + * (LCD_D6) 52 | 7 8 | 53 (LCD_D7) (SD_DETECT) 51 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN 53 -#define EXP1_04_PIN 52 -#define EXP1_05_PIN 50 -#define EXP1_06_PIN 48 -#define EXP1_07_PIN 63 -#define EXP1_08_PIN 64 -#define EXP1_09_PIN 40 -#define EXP1_10_PIN 62 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN 51 -#define EXP2_05_PIN 75 // MOSI -#define EXP2_06_PIN 42 -#define EXP2_07_PIN 10 -#define EXP2_08_PIN 44 -#define EXP2_09_PIN 76 // SCK -#define EXP2_10_PIN 74 // MISO +#define EXP1_08_PIN 53 +#define EXP1_07_PIN 52 +#define EXP1_06_PIN 50 +#define EXP1_05_PIN 48 +#define EXP1_04_PIN 63 +#define EXP1_03_PIN 64 +#define EXP1_02_PIN 40 +#define EXP1_01_PIN 62 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN 51 +#define EXP2_06_PIN 75 // MOSI +#define EXP2_05_PIN 42 +#define EXP2_04_PIN 10 +#define EXP2_03_PIN 44 +#define EXP2_02_PIN 76 // SCK +#define EXP2_01_PIN 74 // MISO // // LCD / Controller @@ -217,53 +217,53 @@ #if HAS_WIRED_LCD #if ANY(RADDS_DISPLAY, IS_RRD_SC, IS_RRD_FG_SC) - #define BEEPER_PIN EXP1_10_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define BEEPER_PIN EXP1_01_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif #if EITHER(RADDS_DISPLAY, IS_RRD_SC) - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN #elif IS_RRD_FG_SC - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN #elif HAS_U8GLIB_I2C_OLED - #define BEEPER_PIN EXP1_10_PIN - #define LCD_SDSS EXP2_07_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define BEEPER_PIN EXP1_01_PIN + #define LCD_SDSS EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #elif ENABLED(FYSETC_MINI_12864) - #define BEEPER_PIN EXP1_10_PIN - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define BEEPER_PIN EXP1_01_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN // D5 + #define RGB_LED_R_PIN EXP1_06_PIN // D5 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN // D6 + #define RGB_LED_G_PIN EXP1_07_PIN // D6 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN // D7 + #define RGB_LED_B_PIN EXP1_08_PIN // D7 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN // D5 + #define NEOPIXEL_PIN EXP1_06_PIN // D5 #endif #elif ENABLED(SPARK_FULL_GRAPHICS) @@ -280,9 +280,9 @@ #endif // SPARK_FULL_GRAPHICS #if IS_NEWPANEL - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index cc919d0a4f..37e7f20976 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -175,31 +175,31 @@ /** * ------ ------ - * (BEEPER) 62 |10 9 | 40 (BTN_ENC) (MISO) 74 |10 9 | 76 (SCK) - * (LCD_EN) 64 | 8 7 | 63 (LCD_RS) (BTN_EN1) 44 | 8 7 | 10 (SD_SS) - * (LCD_D4) 48 | 6 5 50 (LCD_D5) (BTN_EN2) 42 | 6 5 75 (MOSI) - * (LCD_D6) 52 | 4 3 | 53 (LCD_D7) (SD_DETECT) 51 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) 62 | 1 2 | 40 (BTN_ENC) (MISO) 74 | 1 2 | 76 (SCK) + * (LCD_EN) 64 | 3 4 | 63 (LCD_RS) (BTN_EN1) 44 | 3 4 | 10 (SD_SS) + * (LCD_D4) 48 | 5 6 50 (LCD_D5) (BTN_EN2) 42 | 5 6 75 (MOSI) + * (LCD_D6) 52 | 7 8 | 53 (LCD_D7) (SD_DETECT) 51 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN 53 -#define EXP1_04_PIN 52 -#define EXP1_05_PIN 50 -#define EXP1_06_PIN 48 -#define EXP1_07_PIN 63 -#define EXP1_08_PIN 64 -#define EXP1_09_PIN 40 -#define EXP1_10_PIN 62 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN 51 -#define EXP2_05_PIN 75 // MOSI -#define EXP2_06_PIN 42 -#define EXP2_07_PIN 10 -#define EXP2_08_PIN 44 -#define EXP2_09_PIN 76 // SCK -#define EXP2_10_PIN 74 // MISO +#define EXP1_08_PIN 53 +#define EXP1_07_PIN 52 +#define EXP1_06_PIN 50 +#define EXP1_05_PIN 48 +#define EXP1_04_PIN 63 +#define EXP1_03_PIN 64 +#define EXP1_02_PIN 40 +#define EXP1_01_PIN 62 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN 51 +#define EXP2_06_PIN 75 // MOSI +#define EXP2_05_PIN 42 +#define EXP2_04_PIN 10 +#define EXP2_03_PIN 44 +#define EXP2_02_PIN 76 // SCK +#define EXP2_01_PIN 74 // MISO // // LCD / Controller @@ -207,67 +207,67 @@ #if HAS_WIRED_LCD #if ANY(RADDS_DISPLAY, IS_RRD_SC, IS_RRD_FG_SC) - #define BEEPER_PIN EXP1_10_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define BEEPER_PIN EXP1_01_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif #if EITHER(RADDS_DISPLAY, IS_RRD_SC) - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN #elif IS_RRD_FG_SC - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN #elif HAS_U8GLIB_I2C_OLED - #define BEEPER_PIN EXP1_10_PIN - #define LCD_SDSS EXP2_07_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define BEEPER_PIN EXP1_01_PIN + #define LCD_SDSS EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #elif ENABLED(FYSETC_MINI_12864) - #define BEEPER_PIN EXP1_10_PIN - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define BEEPER_PIN EXP1_01_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN // D5 + #define RGB_LED_R_PIN EXP1_06_PIN // D5 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN // D6 + #define RGB_LED_G_PIN EXP1_07_PIN // D6 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN // D7 + #define RGB_LED_B_PIN EXP1_08_PIN // D7 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN // D5 + #define NEOPIXEL_PIN EXP1_06_PIN // D5 #endif #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif #if IS_NEWPANEL - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h index 264b2e80c6..a9199ba84c 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h @@ -166,33 +166,33 @@ * BTN_ENCODER 40 KILL_PIN 49 */ -#define EXP1_03_PIN 39 -#define EXP1_04_PIN 38 -#define EXP1_05_PIN 37 -#define EXP1_06_PIN 36 -#define EXP1_07_PIN 34 -#define EXP1_08_PIN 35 -#define EXP1_09_PIN 40 -#define EXP1_10_PIN 41 - -#define EXP2_01_PIN 49 -#define EXP2_04_PIN 44 -#define EXP2_05_PIN 51 -#define EXP2_06_PIN 42 -#define EXP2_07_PIN 53 -#define EXP2_08_PIN 43 -#define EXP2_09_PIN 52 -#define EXP2_10_PIN 50 +#define EXP1_08_PIN 39 +#define EXP1_07_PIN 38 +#define EXP1_06_PIN 37 +#define EXP1_05_PIN 36 +#define EXP1_04_PIN 34 +#define EXP1_03_PIN 35 +#define EXP1_02_PIN 40 +#define EXP1_01_PIN 41 + +#define EXP2_10_PIN 49 +#define EXP2_07_PIN 44 +#define EXP2_06_PIN 51 +#define EXP2_05_PIN 42 +#define EXP2_04_PIN 53 +#define EXP2_03_PIN 43 +#define EXP2_02_PIN 52 +#define EXP2_01_PIN 50 #if ENABLED(CR10_STOCKDISPLAY) - #define EXP3_03_PIN EXP1_03_PIN - #define EXP3_04_PIN EXP1_04_PIN - #define EXP3_05_PIN EXP1_05_PIN - #define EXP3_06_PIN EXP1_06_PIN - #define EXP3_07_PIN EXP1_07_PIN - #define EXP3_08_PIN EXP1_08_PIN - #define EXP3_09_PIN EXP1_09_PIN - #define EXP3_10_PIN EXP1_10_PIN + #define EXP3_03_PIN EXP1_08_PIN + #define EXP3_04_PIN EXP1_07_PIN + #define EXP3_05_PIN EXP1_06_PIN + #define EXP3_06_PIN EXP1_05_PIN + #define EXP3_07_PIN EXP1_04_PIN + #define EXP3_08_PIN EXP1_03_PIN + #define EXP3_09_PIN EXP1_02_PIN + #define EXP3_10_PIN EXP1_01_PIN #endif /************************************/ @@ -222,30 +222,30 @@ #endif // DWIN Encoder - #define BTN_ENC EXP1_09_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_07_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_04_PIN #ifndef BEEPER_PIN - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #undef SPEAKER #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) // TO TEST - //#define LCD_PINS_RS EXP2_01_PIN // CS chip select /SS chip slave select - //#define LCD_PINS_ENABLE EXP2_05_PIN // SID (MOSI) - //#define LCD_PINS_D4 EXP2_09_PIN // SCK (CLK) clock + //#define LCD_PINS_RS EXP2_10_PIN // CS chip select /SS chip slave select + //#define LCD_PINS_ENABLE EXP2_06_PIN // SID (MOSI) + //#define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock #elif BOTH(IS_NEWPANEL, PANEL_ONE) // TO TEST - //#define LCD_PINS_RS EXP1_09_PIN - //#define LCD_PINS_ENABLE EXP2_06_PIN + //#define LCD_PINS_RS EXP1_02_PIN + //#define LCD_PINS_ENABLE EXP2_05_PIN //#define LCD_PINS_D4 57 // Mega/Due:65 - AGCM4:57 //#define LCD_PINS_D5 58 // Mega/Due:66 - AGCM4:58 - //#define LCD_PINS_D6 EXP2_04_PIN + //#define LCD_PINS_D6 EXP2_07_PIN //#define LCD_PINS_D7 56 // Mega/Due:64 - AGCM4:56 #else @@ -266,10 +266,10 @@ // TO TEST //#define LCD_PINS_RS 56 // Mega/Due:64 - AGCM4:56 - //#define LCD_PINS_ENABLE EXP2_04_PIN + //#define LCD_PINS_ENABLE EXP2_07_PIN //#define LCD_PINS_D4 55 // Mega/Due:63 - AGCM4:55 - //#define LCD_PINS_D5 EXP1_09_PIN - //#define LCD_PINS_D6 EXP2_06_PIN + //#define LCD_PINS_D5 EXP1_02_PIN + //#define LCD_PINS_D6 EXP2_05_PIN //#define LCD_PINS_D7 57 // Mega/Due:65 - AGCM4:57 #else @@ -287,17 +287,17 @@ #else // Definitions for any standard Display - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN #endif - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if !IS_NEWPANEL - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #endif #endif @@ -305,9 +305,9 @@ #if !IS_NEWPANEL // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK_PIN EXP1_04_PIN - //#define SHIFT_LD_PIN EXP2_06_PIN - //#define SHIFT_OUT_PIN EXP1_09_PIN + //#define SHIFT_CLK_PIN EXP1_07_PIN + //#define SHIFT_LD_PIN EXP2_05_PIN + //#define SHIFT_OUT_PIN EXP1_02_PIN //#define SHIFT_EN_PIN 17 #endif @@ -320,7 +320,7 @@ #if IS_RRD_SC - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #if ENABLED(CR10_STOCKDISPLAY) // TO TEST @@ -329,21 +329,21 @@ #else // Definitions for any standard Display - #define BTN_EN1 EXP2_06_PIN - #define BTN_EN2 EXP2_08_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif #endif - #define BTN_ENC EXP1_09_PIN + #define BTN_ENC EXP1_02_PIN #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif - #define KILL_PIN EXP2_01_PIN + #define KILL_PIN EXP2_10_PIN #if ENABLED(BQ_LCD_SMART_CONTROLLER) - //#define LCD_BACKLIGHT_PIN EXP1_03_PIN // TO TEST + //#define LCD_BACKLIGHT_PIN EXP1_08_PIN // TO TEST #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) @@ -352,41 +352,41 @@ //#define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 //#define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 //#define BTN_ENC 55 - //#define SD_DETECT_PIN EXP2_06_PIN + //#define SD_DETECT_PIN EXP2_05_PIN #elif ENABLED(LCD_I2C_PANELOLU2) // TO TEST //#define BTN_EN1 47 - //#define BTN_EN2 EXP2_08_PIN + //#define BTN_EN2 EXP2_03_PIN //#define BTN_ENC 32 //#define LCD_SDSS SDSS - //#define KILL_PIN EXP1_10_PIN + //#define KILL_PIN EXP1_01_PIN #elif ENABLED(LCD_I2C_VIKI) // TO TEST - //#define BTN_EN1 EXP1_09_PIN // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - //#define BTN_EN2 EXP2_06_PIN + //#define BTN_EN1 EXP1_02_PIN // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + //#define BTN_EN2 EXP2_05_PIN //#define BTN_ENC -1 //#define LCD_SDSS SDSS - //#define SD_DETECT_PIN EXP2_01_PIN + //#define SD_DETECT_PIN EXP2_10_PIN #elif EITHER(VIKI2, miniVIKI) // TO TEST //#define DOGLCD_CS 45 - //#define DOGLCD_A0 EXP2_04_PIN + //#define DOGLCD_A0 EXP2_07_PIN //#define LCD_SCREEN_ROT_180 //#define BEEPER_PIN 33 //#define STAT_LED_RED_PIN 32 - //#define STAT_LED_BLUE_PIN EXP1_08_PIN + //#define STAT_LED_BLUE_PIN EXP1_03_PIN //#define BTN_EN1 22 //#define BTN_EN2 7 - //#define BTN_ENC EXP1_03_PIN + //#define BTN_ENC EXP1_08_PIN //#define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board //#define KILL_PIN 31 @@ -400,23 +400,23 @@ //#define BEEPER_PIN 23 //#define LCD_BACKLIGHT_PIN 33 - //#define BTN_EN1 EXP1_08_PIN - //#define BTN_EN2 EXP1_05_PIN + //#define BTN_EN1 EXP1_03_PIN + //#define BTN_EN2 EXP1_06_PIN //#define BTN_ENC 31 //#define LCD_SDSS SDSS - //#define SD_DETECT_PIN EXP2_01_PIN - //#define KILL_PIN EXP1_10_PIN + //#define SD_DETECT_PIN EXP2_10_PIN + //#define KILL_PIN EXP1_01_PIN #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST - //#define BEEPER_PIN EXP1_05_PIN - //#define BTN_ENC EXP1_08_PIN - //#define SD_DETECT_PIN EXP2_01_PIN + //#define BEEPER_PIN EXP1_06_PIN + //#define BTN_ENC EXP1_03_PIN + //#define SD_DETECT_PIN EXP2_10_PIN //#ifndef KILL_PIN - // #define KILL_PIN EXP1_10_PIN + // #define KILL_PIN EXP1_01_PIN //#endif #if ENABLED(MKS_MINI_12864) @@ -476,11 +476,11 @@ #elif ENABLED(MINIPANEL) // TO TEST - //#define BEEPER_PIN EXP2_06_PIN + //#define BEEPER_PIN EXP2_05_PIN // not connected to a pin //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) - //#define DOGLCD_A0 EXP2_04_PIN + //#define DOGLCD_A0 EXP2_07_PIN //#define DOGLCD_CS 58 // Mega/Due:66 - AGCM4:58 // GLCD features @@ -489,11 +489,11 @@ //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - //#define BTN_EN1 EXP1_09_PIN + //#define BTN_EN1 EXP1_02_PIN //#define BTN_EN2 55 // Mega/Due:63 - AGCM4:55 //#define BTN_ENC 72 // Mega/Due:59 - AGCM4:72 - //#define SD_DETECT_PIN EXP2_01_PIN + //#define SD_DETECT_PIN EXP2_10_PIN //#define KILL_PIN 56 // Mega/Due:64 - AGCM4:56 #elif ENABLED(ZONESTAR_LCD) @@ -513,9 +513,9 @@ // Buttons are directly attached to AUX-2 #if IS_RRW_KEYPAD // TO TEST - //#define SHIFT_OUT_PIN EXP1_09_PIN - //#define SHIFT_CLK_PIN EXP2_04_PIN - //#define SHIFT_LD_PIN EXP2_06_PIN + //#define SHIFT_OUT_PIN EXP1_02_PIN + //#define SHIFT_CLK_PIN EXP2_07_PIN + //#define SHIFT_LD_PIN EXP2_05_PIN //#define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 //#define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 //#define BTN_ENC 55 // Mega/Due:63 - AGCM4:55 @@ -523,18 +523,18 @@ // TO TEST //#define BTN_EN1 72 // AUX2 PIN 3 (Mega/Due:59 - AGCM4:72) //#define BTN_EN2 55 // AUX2 PIN 4 (Mega/Due:63 - AGCM4:55) - //#define BTN_ENC EXP2_01_PIN // AUX3 PIN 7 + //#define BTN_ENC EXP2_10_PIN // AUX3 PIN 7 #else // TO TEST - //#define BTN_EN1 EXP1_05_PIN - //#define BTN_EN2 EXP1_08_PIN + //#define BTN_EN1 EXP1_06_PIN + //#define BTN_EN2 EXP1_03_PIN //#define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) // TO TEST - //#define SD_DETECT_PIN EXP2_01_PIN - //#define KILL_PIN EXP1_10_PIN + //#define SD_DETECT_PIN EXP2_10_PIN + //#define KILL_PIN EXP1_01_PIN #endif #endif @@ -565,7 +565,7 @@ #undef SD_DETECT_PIN #define SD_DETECT_PIN 95 #else - #define SDSS EXP2_07_PIN + #define SDSS EXP2_04_PIN #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h index e90be4eda1..991b4e1ad8 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h @@ -218,33 +218,33 @@ * BTN_ENCODER 40 */ -#define EXP1_03_PIN 39 -#define EXP1_04_PIN 38 -#define EXP1_05_PIN 37 -#define EXP1_06_PIN 36 -#define EXP1_07_PIN 34 -#define EXP1_08_PIN 35 -#define EXP1_09_PIN 40 -#define EXP1_10_PIN 41 - -#define EXP2_01_PIN 49 -#define EXP2_04_PIN 44 -#define EXP2_05_PIN 51 -#define EXP2_06_PIN 42 -#define EXP2_07_PIN 53 -#define EXP2_08_PIN 43 -#define EXP2_09_PIN 52 -#define EXP2_10_PIN 50 +#define EXP1_08_PIN 39 +#define EXP1_07_PIN 38 +#define EXP1_06_PIN 37 +#define EXP1_05_PIN 36 +#define EXP1_04_PIN 34 +#define EXP1_03_PIN 35 +#define EXP1_02_PIN 40 +#define EXP1_01_PIN 41 + +#define EXP2_10_PIN 49 +#define EXP2_07_PIN 44 +#define EXP2_06_PIN 51 +#define EXP2_05_PIN 42 +#define EXP2_04_PIN 53 +#define EXP2_03_PIN 43 +#define EXP2_02_PIN 52 +#define EXP2_01_PIN 50 #if ENABLED(CR10_STOCKDISPLAY) - #define EXP3_03_PIN EXP1_03_PIN - #define EXP3_04_PIN EXP1_04_PIN - #define EXP3_05_PIN EXP1_05_PIN - #define EXP3_06_PIN EXP1_06_PIN - #define EXP3_07_PIN EXP1_07_PIN - #define EXP3_08_PIN EXP1_08_PIN - #define EXP3_09_PIN EXP1_09_PIN - #define EXP3_10_PIN EXP1_10_PIN + #define EXP3_03_PIN EXP1_08_PIN + #define EXP3_04_PIN EXP1_07_PIN + #define EXP3_05_PIN EXP1_06_PIN + #define EXP3_06_PIN EXP1_05_PIN + #define EXP3_07_PIN EXP1_04_PIN + #define EXP3_08_PIN EXP1_03_PIN + #define EXP3_09_PIN EXP1_02_PIN + #define EXP3_10_PIN EXP1_01_PIN #endif /************************************/ @@ -275,30 +275,30 @@ #endif // DWIN Encoder - #define BTN_ENC EXP1_09_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_07_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_04_PIN #ifndef BEEPER_PIN - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #undef SPEAKER #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) // TO TEST - //#define LCD_PINS_RS EXP2_01_PIN // CS chip select /SS chip slave select - //#define LCD_PINS_ENABLE EXP2_05_PIN // SID (MOSI) - //#define LCD_PINS_D4 EXP2_09_PIN // SCK (CLK) clock + //#define LCD_PINS_RS EXP2_10_PIN // CS chip select /SS chip slave select + //#define LCD_PINS_ENABLE EXP2_06_PIN // SID (MOSI) + //#define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock #elif BOTH(IS_NEWPANEL, PANEL_ONE) // TO TEST - //#define LCD_PINS_RS EXP1_09_PIN - //#define LCD_PINS_ENABLE EXP2_06_PIN + //#define LCD_PINS_RS EXP1_02_PIN + //#define LCD_PINS_ENABLE EXP2_05_PIN //#define LCD_PINS_D4 57 // Mega/Due:65 - AGCM4:57 //#define LCD_PINS_D5 58 // Mega/Due:66 - AGCM4:58 - //#define LCD_PINS_D6 EXP2_04_PIN + //#define LCD_PINS_D6 EXP2_07_PIN //#define LCD_PINS_D7 56 // Mega/Due:64 - AGCM4:56 #else @@ -319,10 +319,10 @@ // TO TEST //#define LCD_PINS_RS 56 // Mega/Due:64 - AGCM4:56 - //#define LCD_PINS_ENABLE EXP2_04_PIN + //#define LCD_PINS_ENABLE EXP2_07_PIN //#define LCD_PINS_D4 55 // Mega/Due:63 - AGCM4:55 - //#define LCD_PINS_D5 EXP1_09_PIN - //#define LCD_PINS_D6 EXP2_06_PIN + //#define LCD_PINS_D5 EXP1_02_PIN + //#define LCD_PINS_D6 EXP2_05_PIN //#define LCD_PINS_D7 57 // Mega/Due:65 - AGCM4:57 #else @@ -339,17 +339,17 @@ #else // Definitions for any standard Display - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN #endif - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if !IS_NEWPANEL - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #endif #endif @@ -357,9 +357,9 @@ #if !IS_NEWPANEL // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK_PIN EXP1_04_PIN - //#define SHIFT_LD_PIN EXP2_06_PIN - //#define SHIFT_OUT_PIN EXP1_09_PIN + //#define SHIFT_CLK_PIN EXP1_07_PIN + //#define SHIFT_LD_PIN EXP2_05_PIN + //#define SHIFT_OUT_PIN EXP1_02_PIN //#define SHIFT_EN_PIN 17 #endif @@ -372,29 +372,29 @@ #if IS_RRD_SC - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #if ENABLED(CR10_STOCKDISPLAY) // TO TEST - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN #else // Definitions fpr any standard Display - #define BTN_EN1 EXP2_06_PIN - #define BTN_EN2 EXP2_08_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif #endif - #define BTN_ENC EXP1_09_PIN + #define BTN_ENC EXP1_02_PIN #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif - #define KILL_PIN EXP2_01_PIN + #define KILL_PIN EXP2_10_PIN #if ENABLED(BQ_LCD_SMART_CONTROLLER) - //#define LCD_BACKLIGHT_PIN EXP1_03_PIN // TO TEST + //#define LCD_BACKLIGHT_PIN EXP1_08_PIN // TO TEST #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) @@ -403,41 +403,41 @@ //#define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 //#define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 //#define BTN_ENC 55 - //#define SD_DETECT_PIN EXP2_06_PIN + //#define SD_DETECT_PIN EXP2_05_PIN #elif ENABLED(LCD_I2C_PANELOLU2) // TO TEST //#define BTN_EN1 47 - //#define BTN_EN2 EXP2_08_PIN + //#define BTN_EN2 EXP2_03_PIN //#define BTN_ENC 32 //#define LCD_SDSS SDSS - //#define KILL_PIN EXP1_10_PIN + //#define KILL_PIN EXP1_01_PIN #elif ENABLED(LCD_I2C_VIKI) // TO TEST - //#define BTN_EN1 EXP1_09_PIN // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - //#define BTN_EN2 EXP2_06_PIN + //#define BTN_EN1 EXP1_02_PIN // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + //#define BTN_EN2 EXP2_05_PIN //#define BTN_ENC -1 //#define LCD_SDSS SDSS - //#define SD_DETECT_PIN EXP2_01_PIN + //#define SD_DETECT_PIN EXP2_10_PIN #elif EITHER(VIKI2, miniVIKI) // TO TEST //#define DOGLCD_CS 45 - //#define DOGLCD_A0 EXP2_04_PIN + //#define DOGLCD_A0 EXP2_07_PIN //#define LCD_SCREEN_ROT_180 //#define BEEPER_PIN 33 //#define STAT_LED_RED_PIN 32 - //#define STAT_LED_BLUE_PIN EXP1_08_PIN + //#define STAT_LED_BLUE_PIN EXP1_03_PIN //#define BTN_EN1 22 //#define BTN_EN2 7 - //#define BTN_ENC EXP1_03_PIN + //#define BTN_ENC EXP1_08_PIN //#define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board //#define KILL_PIN 31 @@ -451,23 +451,23 @@ //#define BEEPER_PIN 23 //#define LCD_BACKLIGHT_PIN 33 - //#define BTN_EN1 EXP1_08_PIN - //#define BTN_EN2 EXP1_05_PIN + //#define BTN_EN1 EXP1_03_PIN + //#define BTN_EN2 EXP1_06_PIN //#define BTN_ENC 31 //#define LCD_SDSS SDSS - //#define SD_DETECT_PIN EXP2_01_PIN - //#define KILL_PIN EXP1_10_PIN + //#define SD_DETECT_PIN EXP2_10_PIN + //#define KILL_PIN EXP1_01_PIN #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST - //#define BEEPER_PIN EXP1_05_PIN - //#define BTN_ENC EXP1_08_PIN - //#define SD_DETECT_PIN EXP2_01_PIN + //#define BEEPER_PIN EXP1_06_PIN + //#define BTN_ENC EXP1_03_PIN + //#define SD_DETECT_PIN EXP2_10_PIN //#ifndef KILL_PIN - // #define KILL_PIN EXP1_10_PIN + // #define KILL_PIN EXP1_01_PIN //#endif #if ENABLED(MKS_MINI_12864) @@ -527,11 +527,11 @@ #elif ENABLED(MINIPANEL) // TO TEST - //#define BEEPER_PIN EXP2_06_PIN + //#define BEEPER_PIN EXP2_05_PIN // not connected to a pin //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) - //#define DOGLCD_A0 EXP2_04_PIN + //#define DOGLCD_A0 EXP2_07_PIN //#define DOGLCD_CS 58 // Mega/Due:66 - AGCM4:58 // GLCD features @@ -540,11 +540,11 @@ //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - //#define BTN_EN1 EXP1_09_PIN + //#define BTN_EN1 EXP1_02_PIN //#define BTN_EN2 55 // Mega/Due:63 - AGCM4:55 //#define BTN_ENC 72 // Mega/Due:59 - AGCM4:72 - //#define SD_DETECT_PIN EXP2_01_PIN + //#define SD_DETECT_PIN EXP2_10_PIN //#define KILL_PIN 56 // Mega/Due:64 - AGCM4:56 #elif ENABLED(ZONESTAR_LCD) @@ -564,9 +564,9 @@ // Buttons are directly attached to AUX-2 #if IS_RRW_KEYPAD // TO TEST - //#define SHIFT_OUT_PIN EXP1_09_PIN - //#define SHIFT_CLK_PIN EXP2_04_PIN - //#define SHIFT_LD_PIN EXP2_06_PIN + //#define SHIFT_OUT_PIN EXP1_02_PIN + //#define SHIFT_CLK_PIN EXP2_07_PIN + //#define SHIFT_LD_PIN EXP2_05_PIN //#define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 //#define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 //#define BTN_ENC 55 // Mega/Due:63 - AGCM4:55 @@ -574,18 +574,18 @@ // TO TEST //#define BTN_EN1 72 // AUX2 PIN 3 (Mega/Due:59 - AGCM4:72) //#define BTN_EN2 55 // AUX2 PIN 4 (Mega/Due:63 - AGCM4:55) - //#define BTN_ENC EXP2_01_PIN // AUX3 PIN 7 + //#define BTN_ENC EXP2_10_PIN // AUX3 PIN 7 #else // TO TEST - //#define BTN_EN1 EXP1_05_PIN - //#define BTN_EN2 EXP1_08_PIN + //#define BTN_EN1 EXP1_06_PIN + //#define BTN_EN2 EXP1_03_PIN //#define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) // TO TEST - //#define SD_DETECT_PIN EXP2_01_PIN - //#define KILL_PIN EXP1_10_PIN + //#define SD_DETECT_PIN EXP2_10_PIN + //#define KILL_PIN EXP1_01_PIN #endif #endif @@ -616,7 +616,7 @@ #undef SD_DETECT_PIN #define SD_DETECT_PIN 95 #else - #define SDSS EXP2_07_PIN + #define SDSS EXP2_04_PIN #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index a450515a79..83aa5317f9 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -132,10 +132,10 @@ /** * EXP1 Connector EXP1 as CR10 STOCKDISPLAY * ------ ------ - * PA4 |10 9 | PC0 BEEPER_PIN |10 9 | BTN_ENC - * PD3 | 8 7 | RESET BTN_EN1 | 8 7 | RESET - * PD2 6 5 | PA1 BTN_EN2 6 5 | LCD_PINS_D4 (ST9720 CLK) - * PA3 | 4 3 | PC1 (ST9720 CS) LCD_PINS_RS | 4 3 | LCD_PINS_ENABLE (ST9720 DAT) - * GND | 2 1 | 5V GND | 2 1 | 5V + * PA4 | 1 2 | PC0 BEEPER_PIN | 1 2 | BTN_ENC + * PD3 | 3 4 | RESET BTN_EN1 | 3 4 | RESET + * PD2 5 6 | PA1 BTN_EN2 5 6 | LCD_PINS_D4 (ST9720 CLK) + * PA3 | 7 8 | PC1 (ST9720 CS) LCD_PINS_RS | 7 8 | LCD_PINS_ENABLE (ST9720 DAT) + * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ */ diff --git a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h index 0a8143c376..f61f7dc6bb 100644 --- a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h +++ b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h @@ -164,25 +164,25 @@ /** EXP1 * ------ - * (MOSI) D5 |10 9 | D7 (SCK) - * (CS) D11 | 8 7 | D10 (DC/D4) - * (EN2) D12 6 5 | D4 or D3 (EN/RS) - * (ENC) D29 | 4 3 | D2 (EN1) - * (GND) | 2 1 | (5V) + * (MOSI) D5 | 1 2 | D7 (SCK) + * (CS) D11 | 3 4 | D10 (DC/D4) + * (EN2) D12 5 6 | D4 or D3 (EN/RS) + * (ENC) D29 | 7 8 | D2 (EN1) + * (GND) | 9 10 | (5V) * ------ */ -#define EXP1_03_PIN 2 -#define EXP1_04_PIN 29 +#define EXP1_08_PIN 2 +#define EXP1_07_PIN 29 #ifndef IS_ZMIB_V2 - #define EXP1_05_PIN 4 // ZMIB V1 + #define EXP1_06_PIN 4 // ZMIB V1 #else - #define EXP1_05_PIN 3 // ZMIB V2 + #define EXP1_06_PIN 3 // ZMIB V2 #endif -#define EXP1_06_PIN 12 -#define EXP1_07_PIN 10 -#define EXP1_08_PIN 11 -#define EXP1_09_PIN 7 -#define EXP1_10_PIN 5 +#define EXP1_05_PIN 12 +#define EXP1_04_PIN 10 +#define EXP1_03_PIN 11 +#define EXP1_02_PIN 7 +#define EXP1_01_PIN 5 #if ENABLED(ZONESTAR_12864LCD) // @@ -190,10 +190,10 @@ // #define LCDSCREEN_NAME "ZONESTAR_12864LCD" #define FORCE_SOFT_SPI - //#define LCD_SDSS EXP1_08_PIN - #define LCD_PINS_RS EXP1_08_PIN // ST7920_CS_PIN (LCD module pin 4) - #define LCD_PINS_ENABLE EXP1_05_PIN // ST7920_DAT_PIN (LCD module pin 5) - #define LCD_PINS_D4 EXP1_07_PIN // ST7920_CLK_PIN (LCD module pin 6) + //#define LCD_SDSS EXP1_03_PIN + #define LCD_PINS_RS EXP1_03_PIN // ST7920_CS_PIN (LCD module pin 4) + #define LCD_PINS_ENABLE EXP1_06_PIN // ST7920_DAT_PIN (LCD module pin 5) + #define LCD_PINS_D4 EXP1_04_PIN // ST7920_CLK_PIN (LCD module pin 6) #define BOARD_ST7920_DELAY_1 DELAY_2_NOP #define BOARD_ST7920_DELAY_2 DELAY_2_NOP @@ -205,9 +205,9 @@ // #define LCDSCREEN_NAME "ZONESTAR 12864OLED" #define FORCE_SOFT_SPI - #define LCD_PINS_RS EXP1_05_PIN - #define LCD_PINS_DC EXP1_07_PIN - #define DOGLCD_CS EXP1_08_PIN + #define LCD_PINS_RS EXP1_06_PIN + #define LCD_PINS_DC EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN #if ENABLED(OLED_HW_IIC) #error "Oops! can't choose HW IIC for ZMIB board!!" @@ -224,9 +224,9 @@ // All the above are also RRDSC with rotary encoder // #if IS_RRD_SC - #define BTN_EN1 EXP1_03_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_04_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_07_PIN #define BEEPER_PIN -1 #define KILL_PIN -1 #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 06788139f0..4e4efc4f73 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -157,11 +157,11 @@ /** * ------ - * (BEEPER) PA15 |10 9 | PB6 (BTN_ENC) - * (BTN_EN1) PA9 | 8 7 | RESET - * (BTN_EN2) PA10 6 5 | PB9 (LCD_D4) - * (LCD_RS) PB8 | 4 3 | PB7 (LCD_EN) - * GND | 2 1 | 5V + * (BEEPER) PA15 | 1 2 | PB6 (BTN_ENC) + * (BTN_EN1) PA9 | 3 4 | RESET + * (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) + * (LCD_RS) PB8 | 7 8 | PB7 (LCD_EN) + * GND | 9 10 | 5V * ------ * EXP1 */ @@ -198,11 +198,11 @@ /** Creality Ender-2 display pinout * ------ - * (SCK) PA15 |10 9 | PB6 (BTN_ENC) - * (BTN_EN1) PA9 | 8 7 | RESET - * (BTN_EN2) PA10 6 5 | PB9 (LCD_A0) - * (LCD_RS) PB8 | 4 3 | PB7 (MOSI) - * GND | 2 1 | 5V + * (SCK) PA15 | 1 2 | PB6 (BTN_ENC) + * (BTN_EN1) PA9 | 3 4 | RESET + * (BTN_EN2) PA10 5 6 | PB9 (LCD_A0) + * (LCD_RS) PB8 | 7 8 | PB7 (MOSI) + * GND | 9 10 | 5V * ------ * EXP1 */ @@ -234,11 +234,11 @@ * * Board Display * ------ ------ - * (SD_DET) PA15 |10 9 | PB6 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PA9 | 8 7 | RESET (RESET) | 8 7 | (SD_DET) - * (SD_CS) PA10 6 5 | PB9 (MOSI) 6 5 | (LCD_CS) - * (LCD_CS) PB8 | 4 3 | PB7 (SD_CS) | 4 3 | (MOD_RESET) - * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * (SD_DET) PA15 | 1 2 | PB6 (BEEPER) 5V | 1 2 | GND + * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 3 4 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) 5 6 | (LCD_CS) + * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 7 8 | (MOD_RESET) + * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) * ------ ------ * EXP1 EXP1 * diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index fa7eb3dd11..a81f272f26 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -120,11 +120,11 @@ /** * SKR Mini E3 V1.0, V1.2 SKR Mini E3 V2.0 * ------ ------ - * (BEEPER) PB5 |10 9 | PB6 (BTN_ENC) (BEEPER) PB5 |10 9 | PA15 (BTN_ENC) - * (BTN_EN1) PA9 | 8 7 | RESET (BTN_EN1) PA9 | 8 7 | RESET - * (BTN_EN2) PA10 6 5 | PB9 (LCD_D4) (BTN_EN2) PA10 6 5 | PB9 (LCD_D4) - * (LCD_RS) PB8 | 4 3 | PB7 (LCD_EN) (LCD_RS) PB8 | 4 3 | PB15 (LCD_EN) - * GND | 2 1 | 5V GND | 2 1 | 5V + * (BEEPER) PB5 | 1 2 | PB6 (BTN_ENC) (BEEPER) PB5 | 1 2 | PA15 (BTN_ENC) + * (BTN_EN1) PA9 | 3 4 | RESET (BTN_EN1) PA9 | 3 4 | RESET + * (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) + * (LCD_RS) PB8 | 7 8 | PB7 (LCD_EN) (LCD_RS) PB8 | 7 8 | PB15 (LCD_EN) + * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ * EXP1 EXP1 */ @@ -139,11 +139,11 @@ #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI /** * ------ ------ ------ - * (ENT) |10 9 | (BEEP) |10 9 | |10 9 | - * (RX) | 8 7 | (RX) | 8 7 | (TX) RX | 8 7 | TX - * (TX) 6 5 | (ENT) 6 5 | (BEEP) ENT | 6 5 | BEEP - * (B) | 4 3 | (A) (B) | 4 3 | (A) B | 4 3 | A - * GND | 2 1 | (VCC) GND | 2 1 | VCC GND | 2 1 | VCC + * (ENT) | 1 2 | (BEEP) | 1 2 | | 1 2 | + * (RX) | 3 4 | (RX) | 3 4 | (TX) RX | 3 4 | TX + * (TX) 5 6 | (ENT) 5 6 | (BEEP) ENT | 5 6 | BEEP + * (B) | 7 8 | (A) (B) | 7 8 | (A) B | 7 8 | A + * GND | 9 10 | (VCC) GND | 9 10 | VCC GND | 9 10 | VCC * ------ ------ ------ * EXP1 DWIN DWIN (plug) * @@ -214,11 +214,11 @@ * * Board Display * ------ ------ - * (SD_DET) PB5 |10 9 | PB6 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PA9 | 8 7 | RESET -- | 8 7 | (SD_DET) - * (SD_CS) PA10 6 5 | PB9 (MOSI) | 6 5 | -- - * (LCD_CS) PB8 | 4 3 | PB7 (SD_CS) | 4 3 | (LCD_CS) - * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V | 1 2 | GND + * (MOD_RESET) PA9 | 3 4 | RESET -- | 3 4 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) | 5 6 | -- + * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 7 8 | (LCD_CS) + * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) * ------ ------ * EXP1 EXP1 * @@ -253,20 +253,20 @@ * * Board Display * ------ ------ - * PB5 |10 9 | PA15 (BEEP) |10 9 | BTN_ENC - * PA9 | 8 7 | RESET LCD_CS | 8 7 | LCD A0 - * PA10 | 6 5 | PB9 LCD_RST | 6 5 | RED - * PB8 | 4 3 | PB15 (GREEN) | 4 3 | (BLUE) - * GND | 2 1 | 5V GND | 2 1 | 5V + * PB5 | 1 2 | PA15 (BEEP) | 1 2 | BTN_ENC + * PA9 | 3 4 | RESET LCD_CS | 3 4 | LCD A0 + * PA10 | 5 6 | PB9 LCD_RST | 5 6 | RED + * PB8 | 7 8 | PB15 (GREEN) | 7 8 | (BLUE) + * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ * EXP1 EXP1 * * --- ------ - * RST | 1 | (MISO) |10 9 | SCK - * (RX2) PA2 | 2 | BTN_EN1 | 8 7 | (SS) - * (TX2) PA3 | 3 | BTN_EN2 | 6 5 | MOSI - * GND | 4 | (CD) | 4 3 | (RST) - * 5V | 5 | (GND) | 2 1 | (KILL) + * RST | 1 | (MISO) | 1 2 | SCK + * (RX2) PA2 | 2 | BTN_EN1 | 3 4 | (SS) + * (TX2) PA3 | 3 | BTN_EN2 | 5 6 | MOSI + * GND | 4 | (CD) | 7 8 | (RST) + * 5V | 5 | (GND) | 9 10 | (KILL) * --- ------ * TFT EXP2 * @@ -325,11 +325,11 @@ * * Board Display * ------ ------ - * (SD_DET) PB5 |10 9 | PB6 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PA9 | 8 7 | RESET (RESET) | 8 7 | (SD_DET) - * (SD_CS) PA10 6 5 | PB9 (MOSI) | 6 5 | (LCD_CS) - * (LCD_CS) PB8 | 4 3 | PB7 (SD_CS) | 4 3 | (MOD_RESET) - * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V | 1 2 | GND + * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 3 4 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) | 5 6 | (LCD_CS) + * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 7 8 | (MOD_RESET) + * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) * ------ ------ * EXP1 EXP1 * diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 1ea947ffdf..16ea8de2f0 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -111,47 +111,47 @@ #define TEMP_0_PIN PA0 // Analog Input /** ------ ------ - * (BEEPER) PC10 |10 9 | PC11 (BTN_ENC) (MISO) PB4 |10 9 | PB3 (SCK) - * (LCD_EN) PB6 | 8 7 | PC12 (LCD_RS) (BTN_EN1) PD2 | 8 7 | PA15 (SD_SS) - * (LCD_D4) PC13 6 5 | PB7 (LCD_D5) (BTN_EN2) PB8 6 5 | PB5 (MOSI) - * (LCD_D6) PC15 | 4 3 | PC14 (LCD_D7) (SD_DETECT) PB9 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) PC10 | 1 2 | PC11 (BTN_ENC) (MISO) PB4 | 1 2 | PB3 (SCK) + * (LCD_EN) PB6 | 3 4 | PC12 (LCD_RS) (BTN_EN1) PD2 | 3 4 | PA15 (SD_SS) + * (LCD_D4) PC13 5 6 | PB7 (LCD_D5) (BTN_EN2) PB8 5 6 | PB5 (MOSI) + * (LCD_D6) PC15 | 7 8 | PC14 (LCD_D7) (SD_DETECT) PB9 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PC14 -#define EXP1_04_PIN PC15 -#define EXP1_05_PIN PB7 -#define EXP1_06_PIN PC13 -#define EXP1_07_PIN PC12 -#define EXP1_08_PIN PB6 -#define EXP1_09_PIN PC11 -#define EXP1_10_PIN PC10 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN PB9 -#define EXP2_05_PIN PB5 -#define EXP2_06_PIN PB8 -#define EXP2_07_PIN PA15 -#define EXP2_08_PIN PD2 -#define EXP2_09_PIN PB3 -#define EXP2_10_PIN PB4 +#define EXP1_08_PIN PC14 +#define EXP1_07_PIN PC15 +#define EXP1_06_PIN PB7 +#define EXP1_05_PIN PC13 +#define EXP1_04_PIN PC12 +#define EXP1_03_PIN PB6 +#define EXP1_02_PIN PC11 +#define EXP1_01_PIN PC10 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN PB9 +#define EXP2_06_PIN PB5 +#define EXP2_05_PIN PB8 +#define EXP2_04_PIN PA15 +#define EXP2_03_PIN PD2 +#define EXP2_02_PIN PB3 +#define EXP2_01_PIN PB4 // // LCD / Controller // #if HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif IS_TFTGLCD_PANEL @@ -159,56 +159,56 @@ #undef BTN_ENC #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #else - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN #if ENABLED(FYSETC_MINI_12864) #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN - #define DOGLCD_A0 EXP1_07_PIN - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define LCD_RESET_PIN EXP1_05_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #define FORCE_SOFT_SPI // SPI MODE3 - #define LED_PIN EXP1_05_PIN // red pwm - //#define LED_PIN EXP1_04_PIN // green - //#define LED_PIN EXP1_03_PIN // blue + #define LED_PIN EXP1_06_PIN // red pwm + //#define LED_PIN EXP1_07_PIN // green + //#define LED_PIN EXP1_08_PIN // blue //#if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) // #ifndef RGB_LED_R_PIN - // #define RGB_LED_R_PIN EXP1_05_PIN + // #define RGB_LED_R_PIN EXP1_06_PIN // #endif // #ifndef RGB_LED_G_PIN - // #define RGB_LED_G_PIN EXP1_04_PIN + // #define RGB_LED_G_PIN EXP1_07_PIN // #endif // #ifndef RGB_LED_B_PIN - // #define RGB_LED_B_PIN EXP1_03_PIN + // #define RGB_LED_B_PIN EXP1_08_PIN // #endif //#elif ENABLED(FYSETC_MINI_12864_2_1) - // #define NEOPIXEL_PIN EXP1_05_PIN + // #define NEOPIXEL_PIN EXP1_06_PIN //#endif #else // !FYSETC_MINI_12864 - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -241,11 +241,11 @@ #if SD_CONNECTION_IS(LCD) #define SPI_DEVICE 3 - #define SD_DETECT_PIN EXP2_04_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN - #define SD_SS_PIN EXP2_07_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_SS_PIN EXP2_04_PIN #elif SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PA3 #define SD_SCK_PIN PA5 diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 9dec1e1279..7f63cb1b24 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -123,35 +123,35 @@ /** * ------ - * PB5 |10 9 | PB6 - * PA2 | 8 7 | RESET - * PA3 6 5 | PB8 - * PB7 | 4 3 | PA4 - * GND | 2 1 | VCC5 + * PB5 | 1 2 | PB6 + * PA2 | 3 4 | RESET + * PA3 5 6 | PB8 + * PB7 | 7 8 | PA4 + * GND | 9 10 | VCC5 * ------ * EXP1 */ -#define EXP1_03_PIN PA4 -#define EXP1_04_PIN PB7 -#define EXP1_05_PIN PB8 -#define EXP1_06_PIN PA3 -#define EXP1_07_PIN -1 // RESET -#define EXP1_08_PIN PA2 -#define EXP1_09_PIN PB6 -#define EXP1_10_PIN PB5 +#define EXP1_08_PIN PA4 +#define EXP1_07_PIN PB7 +#define EXP1_06_PIN PB8 +#define EXP1_05_PIN PA3 +#define EXP1_04_PIN -1 // RESET +#define EXP1_03_PIN PA2 +#define EXP1_02_PIN PB6 +#define EXP1_01_PIN PB5 // // LCD / Controller // #if ENABLED(CR10_STOCKDISPLAY) - #define BEEPER_PIN EXP1_10_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN - - #define LCD_PINS_RS EXP1_04_PIN // CS -- SOFT SPI for ENDER3 LCD - #define LCD_PINS_D4 EXP1_05_PIN // SCLK - #define LCD_PINS_ENABLE EXP1_03_PIN // DATA MOSI + #define BEEPER_PIN EXP1_01_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_02_PIN + + #define LCD_PINS_RS EXP1_07_PIN // CS -- SOFT SPI for ENDER3 LCD + #define LCD_PINS_D4 EXP1_06_PIN // SCLK + #define LCD_PINS_ENABLE EXP1_08_PIN // DATA MOSI #endif // Alter timing for graphical display diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 7e3979b87e..3df8ad2a8e 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -168,11 +168,11 @@ /** * RET6 12864 LCD * ------ - * PC6 |10 9 | PB2 - * PB10 | 8 7 | PE8 - * PB14 6 5 | PB13 - * PB12 | 4 3 | PB15 - * GND | 2 1 | 5V + * PC6 | 1 2 | PB2 + * PB10 | 3 4 | PE8 + * PB14 5 6 | PB13 + * PB12 | 7 8 | PB15 + * GND | 9 10 | 5V * ------ * EXP1 */ @@ -194,11 +194,11 @@ /** * VET6 12864 LCD * ------ - * ? |10 9 | PC5 - * PB10 | 8 7 | ? - * PA6 6 5 | PA5 - * PA4 | 4 3 | PA7 - * GND | 2 1 | 5V + * ? | 1 2 | PC5 + * PB10 | 3 4 | ? + * PA6 5 6 | PA5 + * PA4 | 7 8 | PA7 + * GND | 9 10 | 5V * ------ * EXP1 */ diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index 484ff65442..699bfee563 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -150,58 +150,58 @@ /** * RET6 12864 LCD * ------ - * PC6 |10 9 | PB2 - * PB10 | 8 7 | PE8 - * PB14 6 5 | PB13 - * PB12 | 4 3 | PB15 - * GND | 2 1 | 5V + * PC6 | 1 2 | PB2 + * PB10 | 3 4 | PE8 + * PB14 5 6 | PB13 + * PB12 | 7 8 | PB15 + * GND | 9 10 | 5V * ------ * EXP1 */ - #define EXP1_03_PIN PB15 - #define EXP1_04_PIN PB12 - #define EXP1_05_PIN PB13 - #define EXP1_06_PIN PB14 - #define EXP1_07_PIN PE8 - #define EXP1_08_PIN PB10 - #define EXP1_09_PIN PB2 - #define EXP1_10_PIN PC6 + #define EXP1_08_PIN PB15 + #define EXP1_07_PIN PB12 + #define EXP1_06_PIN PB13 + #define EXP1_05_PIN PB14 + #define EXP1_04_PIN PE8 + #define EXP1_03_PIN PB10 + #define EXP1_02_PIN PB2 + #define EXP1_01_PIN PC6 - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #elif ENABLED(VET6_12864_LCD) /** * VET6 12864 LCD * ------ - * ? |10 9 | PC5 - * PB10 | 8 7 | ? - * PA6 6 5 | PA5 - * PA4 | 4 3 | PA7 - * GND | 2 1 | 5V + * ? | 1 2 | PC5 + * PB10 | 3 4 | ? + * PA6 5 6 | PA5 + * PA4 | 7 8 | PA7 + * GND | 9 10 | 5V * ------ * EXP1 */ - #define EXP1_03_PIN PA7 - #define EXP1_04_PIN PA4 - #define EXP1_05_PIN PA5 - #define EXP1_06_PIN PA6 - #define EXP1_07_PIN -1 - #define EXP1_08_PIN PB10 - #define EXP1_09_PIN PC5 - #define EXP1_10_PIN -1 + #define EXP1_08_PIN PA7 + #define EXP1_07_PIN PA4 + #define EXP1_06_PIN PA5 + #define EXP1_05_PIN PA6 + #define EXP1_04_PIN -1 + #define EXP1_03_PIN PB10 + #define EXP1_02_PIN PC5 + #define EXP1_01_PIN -1 #else #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." #endif - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN #elif HAS_DWIN_E3V2 || IS_DWIN_MARLINUI diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index 952b40c1de..5326611672 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -85,13 +85,13 @@ #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI EXP2_05_PIN + #define TMC_SW_MOSI EXP2_06_PIN #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO EXP2_10_PIN + #define TMC_SW_MISO EXP2_01_PIN #endif #ifndef TMC_SW_SCK - #define TMC_SW_SCK EXP2_09_PIN + #define TMC_SW_SCK EXP2_02_PIN #endif #endif @@ -123,31 +123,31 @@ #define TEMP_0_PIN PC1 // Analog Input /** ------ ------ - * (BEEPER) PC14 |10 9 | PC13 (BTN_ENC) (MISO) PB14 |10 9 | PB13 (SD_SCK) - * (LCD_EN) PB9 | 8 7 | PB8 (LCD_RS) (BTN_EN1) PB3 | 8 7 | PB12 (SD_CS2) - * (LCD_D4) PB7 6 5 | PB6 (LCD_D5) (BTN_EN2) PD2 6 5 | PB15 (SD_MOSI) - * (LCD_D6) PB5 | 4 3 | PB4 (LCD_D7) (SD_DETECT) PB11 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) PC14 | 1 2 | PC13 (BTN_ENC) (MISO) PB14 | 1 2 | PB13 (SD_SCK) + * (LCD_EN) PB9 | 3 4 | PB8 (LCD_RS) (BTN_EN1) PB3 | 3 4 | PB12 (SD_CS2) + * (LCD_D4) PB7 5 6 | PB6 (LCD_D5) (BTN_EN2) PD2 5 6 | PB15 (SD_MOSI) + * (LCD_D6) PB5 | 7 8 | PB4 (LCD_D7) (SD_DETECT) PB11 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PB4 -#define EXP1_04_PIN PB5 -#define EXP1_05_PIN PB6 -#define EXP1_06_PIN PB7 -#define EXP1_07_PIN PB8 -#define EXP1_08_PIN PB9 -#define EXP1_09_PIN PC13 -#define EXP1_10_PIN PC14 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN PB11 -#define EXP2_05_PIN PB15 -#define EXP2_06_PIN PD2 -#define EXP2_07_PIN PB12 -#define EXP2_08_PIN PB3 -#define EXP2_09_PIN PB13 -#define EXP2_10_PIN PB14 +#define EXP1_08_PIN PB4 +#define EXP1_07_PIN PB5 +#define EXP1_06_PIN PB6 +#define EXP1_05_PIN PB7 +#define EXP1_04_PIN PB8 +#define EXP1_03_PIN PB9 +#define EXP1_02_PIN PC13 +#define EXP1_01_PIN PC14 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN PB11 +#define EXP2_06_PIN PB15 +#define EXP2_05_PIN PD2 +#define EXP2_04_PIN PB12 +#define EXP2_03_PIN PB3 +#define EXP2_02_PIN PB13 +#define EXP2_01_PIN PB14 // // LCD / Controller @@ -155,26 +155,26 @@ #if HAS_WIRED_LCD #define SPI_DEVICE 2 - #define SD_SS_PIN EXP2_07_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN + #define SD_SS_PIN EXP2_04_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN #define SDSS SD_SS_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN - #define BTN_EN1 EXP2_06_PIN - #define BTN_EN2 EXP2_08_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index beda50d29b..7b790ef157 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -133,11 +133,11 @@ /** * EXP1 pinout for the LCD according to FYSETC's Cheetah board schematic * ------ - * (BEEPER) PC9 |10 9 | PC12 (BTN_ENC) - * (BTN_EN2) PC11 | 8 7 | PB14 (LCD_RS / MISO) - * (BTN_EN1) PC10 6 5 | PB13 (SCK) - * (LCD_EN) PB12 | 4 3 | PB15 (MOSI) - * GND | 2 1 | 5V + * (BEEPER) PC9 | 1 2 | PC12 (BTN_ENC) + * (BTN_EN2) PC11 | 3 4 | PB14 (LCD_RS / MISO) + * (BTN_EN1) PC10 5 6 | PB13 (SCK) + * (LCD_EN) PB12 | 7 8 | PB15 (MOSI) + * GND | 9 10 | 5V * ------ * EXP1 * @@ -146,23 +146,23 @@ * - Functionally the pins are assigned in the same order as on the Ender-3 board. * - Pin 4 on the Cheetah board is assigned to an I/O, it is assigned to RESET on the Ender-3 board. */ -#define EXP1_03_PIN PB15 -#define EXP1_04_PIN PB12 -#define EXP1_05_PIN PB13 -#define EXP1_06_PIN PC10 -#define EXP1_07_PIN PB14 -#define EXP1_08_PIN PC11 -#define EXP1_09_PIN PC12 -#define EXP1_10_PIN PC9 +#define EXP1_08_PIN PB15 +#define EXP1_07_PIN PB12 +#define EXP1_06_PIN PB13 +#define EXP1_05_PIN PC10 +#define EXP1_04_PIN PB14 +#define EXP1_03_PIN PC11 +#define EXP1_02_PIN PC12 +#define EXP1_01_PIN PC9 #if HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #if HAS_MARLINUI_U8GLIB - #define DOGLCD_A0 EXP1_07_PIN - #define DOGLCD_CS EXP1_04_PIN - #define DOGLCD_SCK EXP1_05_PIN - #define DOGLCD_MOSI EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_SCK EXP1_06_PIN + #define DOGLCD_MOSI EXP1_08_PIN #if EITHER(FYSETC_MINI_12864, U8GLIB_ST7920) #define FORCE_SOFT_SPI @@ -170,30 +170,30 @@ //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #endif - #define LCD_PINS_RS EXP1_04_PIN // CS -- SOFT SPI for ENDER3 LCD - #define LCD_PINS_D4 EXP1_05_PIN // SCLK - #define LCD_PINS_ENABLE EXP1_03_PIN // DATA MOSI + #define LCD_PINS_RS EXP1_07_PIN // CS -- SOFT SPI for ENDER3 LCD + #define LCD_PINS_D4 EXP1_06_PIN // SCLK + #define LCD_PINS_ENABLE EXP1_08_PIN // DATA MOSI //#define LCD_CONTRAST_INIT 190 #if IS_NEWPANEL - #define BTN_EN1 EXP1_06_PIN - #define BTN_EN2 EXP1_08_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP1_05_PIN + #define BTN_EN2 EXP1_03_PIN + #define BTN_ENC EXP1_02_PIN #endif #endif #if ENABLED(TOUCH_UI_FTDI_EVE) - #define BEEPER_PIN EXP1_10_PIN - #define CLCD_MOD_RESET EXP1_08_PIN - #define CLCD_SPI_CS EXP1_04_PIN + #define BEEPER_PIN EXP1_01_PIN + #define CLCD_MOD_RESET EXP1_03_PIN + #define CLCD_SPI_CS EXP1_07_PIN //#define CLCD_USE_SOFT_SPI // the Cheetah can use hardware-SPI so we do not really need this #if ENABLED(CLCD_USE_SOFT_SPI) - #define CLCD_SOFT_SPI_MOSI EXP1_03_PIN - #define CLCD_SOFT_SPI_MISO EXP1_07_PIN - #define CLCD_SOFT_SPI_SCLK EXP1_05_PIN + #define CLCD_SOFT_SPI_MOSI EXP1_08_PIN + #define CLCD_SOFT_SPI_MISO EXP1_04_PIN + #define CLCD_SOFT_SPI_SCLK EXP1_06_PIN #else #define CLCD_SPI_BUS 2 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 38f10f6713..b6f5dfa87e 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -207,31 +207,31 @@ /** * ------ ------ - * PC5 |10 9 | PE13 PA6 |10 9 | PA5 - * PD13 | 8 7 | PC6 PE8 | 8 7 | PE10 - * PE14 | 6 5 PE15 PE11 | 6 5 PA7 - * PD11 | 4 3 | PD10 PE12 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | 3.3V + * PC5 | 1 2 | PE13 PA6 | 1 2 | PA5 + * PD13 | 3 4 | PC6 PE8 | 3 4 | PE10 + * PE14 | 5 6 PE15 PE11 | 5 6 PA7 + * PD11 | 7 8 | PD10 PE12 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 3.3V * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PD10 -#define EXP1_04_PIN PD11 -#define EXP1_05_PIN PE15 -#define EXP1_06_PIN PE14 -#define EXP1_07_PIN PC6 -#define EXP1_08_PIN PD13 -#define EXP1_09_PIN PE13 -#define EXP1_10_PIN PC5 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PE12 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PE11 -#define EXP2_07_PIN PE10 -#define EXP2_08_PIN PE8 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PD10 +#define EXP1_07_PIN PD11 +#define EXP1_06_PIN PE15 +#define EXP1_05_PIN PE14 +#define EXP1_04_PIN PC6 +#define EXP1_03_PIN PD13 +#define EXP1_02_PIN PE13 +#define EXP1_01_PIN PC5 + +#define EXP2_08_PIN -1 +#define EXP2_07_PIN PE12 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PE11 +#define EXP2_04_PIN PE10 +#define EXP2_03_PIN PE8 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 // // SD Card @@ -247,11 +247,11 @@ #define ONBOARD_SD_CS_PIN PC11 #elif SD_CONNECTION_IS(LCD) #define ENABLE_SPI1 - #define SDSS EXP2_07_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SDSS EXP2_04_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif // @@ -268,25 +268,25 @@ // Shared SPI TFT - #define LCD_BACKLIGHT_PIN EXP1_08_PIN + #define LCD_BACKLIGHT_PIN EXP1_03_PIN - #define TOUCH_CS_PIN EXP1_06_PIN // SPI1_NSS - #define TOUCH_SCK_PIN EXP2_09_PIN // SPI1_SCK - #define TOUCH_MISO_PIN EXP2_10_PIN // SPI1_MISO - #define TOUCH_MOSI_PIN EXP2_05_PIN // SPI1_MOSI + #define TOUCH_CS_PIN EXP1_05_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_02_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_01_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_06_PIN // SPI1_MOSI - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN - #define TFT_CS_PIN EXP1_04_PIN - #define TFT_SCK_PIN EXP2_09_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_MOSI_PIN EXP2_05_PIN - #define TFT_DC_PIN EXP1_03_PIN + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + #define TFT_DC_PIN EXP1_08_PIN #define TFT_A0_PIN TFT_DC_PIN - #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_RESET_PIN EXP1_04_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI @@ -298,22 +298,22 @@ #if ENABLED(TFT_CLASSIC_UI) // Emulated DOGM SPI - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_RS EXP1_07_PIN - #define BTN_ENC EXP1_09_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #elif ENABLED(TFT_COLOR_UI) #define TFT_BUFFER_SIZE 14400 #endif #if HAS_WIRED_LCD && !HAS_SPI_TFT - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #define LCD_BACKLIGHT_PIN -1 #if ENABLED(MKS_MINI_12864) @@ -323,18 +323,18 @@ #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN -1 - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define PIN_SPI_SCK EXP2_09_PIN - #define PIN_TFT_MISO EXP2_10_PIN - #define PIN_TFT_MOSI EXP2_05_PIN - #define TFTGLCD_CS EXP2_08_PIN + #define PIN_SPI_SCK EXP2_02_PIN + #define PIN_TFT_MISO EXP2_01_PIN + #define PIN_TFT_MOSI EXP2_06_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif #ifndef BEEPER_PIN @@ -342,14 +342,14 @@ #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define LCD_PINS_DC EXP1_07_PIN - #define DOGLCD_CS EXP1_08_PIN + #define LCD_PINS_DC EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN #define DOGLCD_A0 DOGLCD_A0 #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN - #define NEOPIXEL_PIN EXP1_05_PIN - #define DOGLCD_MOSI EXP2_05_PIN - #define DOGLCD_SCK EXP2_09_PIN + #define LCD_RESET_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN + #define DOGLCD_MOSI EXP2_06_PIN + #define DOGLCD_SCK EXP2_02_PIN #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif @@ -357,11 +357,11 @@ #else // !MKS_MINI_12864 - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -387,7 +387,7 @@ #endif #ifndef BEEPER_PIN - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #endif #if ENABLED(SPEAKER) && BEEPER_PIN == PC5 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 4af88c1848..a25c8950cb 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -141,82 +141,82 @@ /** * ------ ------ ------ - * (BEEPER) PC1 |10 9 | PC3 (BTN_ENC) (MISO) PB14 |10 9 | PB13 (SD_SCK) (BEEPER) PC1 |10 9 | PC3 (BTN_ENC) - * (LCD_EN) PA4 | 8 7 | PA5 (LCD_RS) (BTN_EN1) PB11 | 8 7 | PA15 (SD_SS) (BTN_EN1) PB11 | 8 7 | RESET - * (LCD_D4) PA6 6 5 | PA7 (LCD_D5) (BTN_EN2) PB0 6 5 | PB15 (SD_MOSI) (BTN_EN2) PB0 6 5 | PA6 (LCD_D4) - * (LCD_D6) PC4 | 4 3 | PC5 (LCD_D7) (SD_DETECT) PC10 | 4 3 | RESET (LCD_RS) PA5 | 4 3 | PA4 (LCD_EN) - * GND | 2 1 | 5V GND | 2 1 | -- GND | 2 1 | 5V + * (BEEPER) PC1 | 1 2 | PC3 (BTN_ENC) (MISO) PB14 | 1 2 | PB13 (SD_SCK) (BEEPER) PC1 | 1 2 | PC3 (BTN_ENC) + * (LCD_EN) PA4 | 3 4 | PA5 (LCD_RS) (BTN_EN1) PB11 | 3 4 | PA15 (SD_SS) (BTN_EN1) PB11 | 3 4 | RESET + * (LCD_D4) PA6 5 6 | PA7 (LCD_D5) (BTN_EN2) PB0 5 6 | PB15 (SD_MOSI) (BTN_EN2) PB0 5 6 | PA6 (LCD_D4) + * (LCD_D6) PC4 | 7 8 | PC5 (LCD_D7) (SD_DETECT) PC10 | 7 8 | RESET (LCD_RS) PA5 | 7 8 | PA4 (LCD_EN) + * GND | 9 10 | 5V GND | 9 10 | -- GND | 9 10 | 5V * ------ ------ ------ * EXP1 EXP2 "Ender-3 EXP1" */ -#define EXP1_03_PIN PC5 -#define EXP1_04_PIN PC4 -#define EXP1_05_PIN PA7 -#define EXP1_06_PIN PA6 -#define EXP1_07_PIN PA5 -#define EXP1_08_PIN PA4 -#define EXP1_09_PIN PC3 -#define EXP1_10_PIN PC1 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN PC10 -#define EXP2_05_PIN PB15 -#define EXP2_06_PIN PB0 -#define EXP2_07_PIN PA15 -#define EXP2_08_PIN PB11 -#define EXP2_09_PIN PB13 -#define EXP2_10_PIN PB14 +#define EXP1_08_PIN PC5 +#define EXP1_07_PIN PC4 +#define EXP1_06_PIN PA7 +#define EXP1_05_PIN PA6 +#define EXP1_04_PIN PA5 +#define EXP1_03_PIN PA4 +#define EXP1_02_PIN PC3 +#define EXP1_01_PIN PC1 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN PC10 +#define EXP2_06_PIN PB15 +#define EXP2_05_PIN PB0 +#define EXP2_04_PIN PA15 +#define EXP2_03_PIN PB11 +#define EXP2_02_PIN PB13 +#define EXP2_01_PIN PB14 // "Ender-3 EXP1" -#define E3_EXP1_03_PIN PA4 -#define E3_EXP1_04_PIN PA5 -#define E3_EXP1_05_PIN PA6 -#define E3_EXP1_06_PIN PB0 -#define E3_EXP1_07_PIN -1 // RESET -#define E3_EXP1_08_PIN PB11 -#define E3_EXP1_09_PIN PC3 -#define E3_EXP1_10_PIN PC1 +#define EXP3_08_PIN PA4 +#define EXP3_07_PIN PA5 +#define EXP3_06_PIN PA6 +#define EXP3_05_PIN PB0 +#define EXP3_04_PIN -1 // RESET +#define EXP3_03_PIN PB11 +#define EXP3_02_PIN PC3 +#define EXP3_01_PIN PC1 #if HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN -1 - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #elif ENABLED(FYSETC_MINI_12864_2_1) - #define LCD_PINS_DC EXP1_07_PIN - #define DOGLCD_CS EXP1_08_PIN + #define LCD_PINS_DC EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN #define DOGLCD_A0 LCD_PINS_DC #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN - #define NEOPIXEL_PIN EXP1_05_PIN - #define DOGLCD_MOSI EXP2_05_PIN - #define DOGLCD_SCK EXP2_09_PIN + #define LCD_RESET_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN + #define DOGLCD_MOSI EXP2_06_PIN + #define DOGLCD_SCK EXP2_02_PIN #define FORCE_SOFT_SPI #define SOFTWARE_SPI //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #else - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if !defined(BTN_ENC_EN) && ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -254,12 +254,12 @@ #define ONBOARD_SPI_DEVICE 2 #define SDSS SD_SS_PIN #define ONBOARD_SD_CS_PIN SD_SS_PIN -#define SD_DETECT_PIN PC10 // EXP2_04_PIN +#define SD_DETECT_PIN PC10 // EXP2_07_PIN #define NO_SD_HOST_DRIVE // TODO: This is the only way to set SPI for SD on STM32 (for now) #define ENABLE_SPI2 -#define SD_SCK_PIN EXP2_09_PIN -#define SD_MISO_PIN EXP2_10_PIN -#define SD_MOSI_PIN EXP2_05_PIN -#define SD_SS_PIN EXP2_07_PIN +#define SD_SCK_PIN EXP2_02_PIN +#define SD_MISO_PIN EXP2_01_PIN +#define SD_MOSI_PIN EXP2_06_PIN +#define SD_SS_PIN EXP2_04_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index bc42bd02eb..227db4b15c 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -80,50 +80,50 @@ #define FIL_RUNOUT_PIN PB8 // MT_DET /** ------ - * (BEEPER) PD2 |10 9 | PB3 (BTN_ENC) - * (BTN_EN1) PB5 | 8 7 | PA11 (RESET?) - * (BTN_EN2) PB4 6 5 | PC1 (LCD_D4) - * (LCD_RS) PC3 | 4 3 | PC2 (LCD_EN) - * GND | 2 1 | 5V + * (BEEPER) PD2 | 1 2 | PB3 (BTN_ENC) + * (BTN_EN1) PB5 | 3 4 | PA11 (RESET?) + * (BTN_EN2) PB4 5 6 | PC1 (LCD_D4) + * (LCD_RS) PC3 | 7 8 | PC2 (LCD_EN) + * GND | 9 10 | 5V * ------ * "E3" EXP1 */ -#define E3_EXP1_01_PIN -1 // 5V -#define E3_EXP1_02_PIN -1 // GND -#define E3_EXP1_03_PIN PC2 -#define E3_EXP1_04_PIN PC3 -#define E3_EXP1_05_PIN PC1 -#define E3_EXP1_06_PIN PB4 -#define E3_EXP1_07_PIN PA11 // RESET? -#define E3_EXP1_08_PIN PB5 -#define E3_EXP1_09_PIN PB3 -#define E3_EXP1_10_PIN PD2 +#define EXP3_10_PIN -1 // 5V +#define EXP3_09_PIN -1 // GND +#define EXP3_08_PIN PC2 +#define EXP3_07_PIN PC3 +#define EXP3_06_PIN PC1 +#define EXP3_05_PIN PB4 +#define EXP3_04_PIN PA11 // RESET? +#define EXP3_03_PIN PB5 +#define EXP3_02_PIN PB3 +#define EXP3_01_PIN PD2 // // LCD Pins // #if HAS_WIRED_LCD - #define BEEPER_PIN E3_EXP1_10_PIN - #define BTN_ENC E3_EXP1_09_PIN - #define LCD_PINS_RS E3_EXP1_04_PIN + #define BEEPER_PIN EXP3_01_PIN + #define BTN_ENC EXP3_02_PIN + #define LCD_PINS_RS EXP3_07_PIN - #define BTN_EN1 E3_EXP1_08_PIN - #define BTN_EN2 E3_EXP1_06_PIN + #define BTN_EN1 EXP3_03_PIN + #define BTN_EN2 EXP3_05_PIN - #define LCD_PINS_ENABLE E3_EXP1_03_PIN + #define LCD_PINS_ENABLE EXP3_08_PIN #if ENABLED(MKS_MINI_12864) #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN -1 - #define DOGLCD_A0 E3_EXP1_05_PIN - #define DOGLCD_CS E3_EXP1_03_PIN + #define DOGLCD_A0 EXP3_06_PIN + #define DOGLCD_CS EXP3_08_PIN #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 #else // !MKS_MINI_12864 - #define LCD_PINS_D4 E3_EXP1_05_PIN + #define LCD_PINS_D4 EXP3_06_PIN #if IS_ULTIPANEL #define LCD_PINS_D5 -1 #define LCD_PINS_D6 -1 @@ -164,12 +164,12 @@ // EXP1 replace LCD with keys for EasyThreeD ET4000+ Mainboard #if ENABLED(EASYTHREED_UI) - #define BTN_HOME E3_EXP1_04_PIN // INPUT_PULLUP (unused) - #define BTN_FEED E3_EXP1_09_PIN // Run E Forward - #define BTN_RETRACT E3_EXP1_08_PIN // Run E Backward - #define BTN_PRINT E3_EXP1_07_PIN // Start File Print - #define BTN_HOME_GND E3_EXP1_03_PIN // OUTPUT (LOW) - #define BTN_FEED_GND E3_EXP1_06_PIN // OUTPUT (LOW) - #define BTN_RETRACT_GND E3_EXP1_05_PIN // OUTPUT (LOW) - #define EASYTHREED_LED_PIN E3_EXP1_10_PIN // Indicator LED + #define BTN_HOME EXP3_07_PIN // INPUT_PULLUP (unused) + #define BTN_FEED EXP3_02_PIN // Run E Forward + #define BTN_RETRACT EXP3_03_PIN // Run E Backward + #define BTN_PRINT EXP3_04_PIN // Start File Print + #define BTN_HOME_GND EXP3_08_PIN // OUTPUT (LOW) + #define BTN_FEED_GND EXP3_05_PIN // OUTPUT (LOW) + #define BTN_RETRACT_GND EXP3_06_PIN // OUTPUT (LOW) + #define EASYTHREED_LED_PIN EXP3_01_PIN // Indicator LED #endif diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h index f1f03a7dd7..ed0f00591f 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h @@ -72,14 +72,14 @@ // 2 +5V // 1 GND -#define EXP1_03_PIN PB11 -#define EXP1_04_PIN PB10 -#define EXP1_05_PIN PB2 -#define EXP1_06_PIN PC5 -#define EXP1_07_PIN PA10 -#define EXP1_08_PIN PA9 -#define EXP1_09_PIN PB0 -#define EXP1_10_PIN PB1 +#define EXP1_08_PIN PB11 +#define EXP1_07_PIN PB10 +#define EXP1_06_PIN PB2 +#define EXP1_05_PIN PC5 +#define EXP1_04_PIN PA10 +#define EXP1_03_PIN PA9 +#define EXP1_02_PIN PB0 +#define EXP1_01_PIN PB1 // AUX1 connector // 1 +5V @@ -193,14 +193,14 @@ // 1 GND #define LCDSCREEN_NAME "ZONESTAR LCD12864" - #define LCD_PINS_RS EXP1_08_PIN - #define LCD_PINS_ENABLE EXP1_05_PIN - #define LCD_PINS_D4 EXP1_07_PIN - //#define KILL_PIN EXP1_10_PIN - #define BEEPER_PIN EXP1_09_PIN - #define BTN_EN1 EXP1_03_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_04_PIN + #define LCD_PINS_RS EXP1_03_PIN + #define LCD_PINS_ENABLE EXP1_06_PIN + #define LCD_PINS_D4 EXP1_04_PIN + //#define KILL_PIN EXP1_01_PIN + #define BEEPER_PIN EXP1_02_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_07_PIN #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 200 #define BOARD_ST7920_DELAY_3 125 @@ -221,15 +221,15 @@ #define FORCE_SOFT_SPI #define LCDSCREEN_NAME "ZONESTAR 12864OLED" - #define LCD_PINS_RS EXP1_05_PIN // = LCD_RESET_PIN - #define LCD_PINS_DC EXP1_07_PIN // DC - #define DOGLCD_CS EXP1_08_PIN // CS + #define LCD_PINS_RS EXP1_06_PIN // = LCD_RESET_PIN + #define LCD_PINS_DC EXP1_04_PIN // DC + #define DOGLCD_CS EXP1_03_PIN // CS #define DOGLCD_A0 LCD_PINS_DC - #define DOGLCD_MOSI EXP1_10_PIN // SDA - #define DOGLCD_SCK EXP1_09_PIN // SCK + #define DOGLCD_MOSI EXP1_01_PIN // SDA + #define DOGLCD_SCK EXP1_02_PIN // SCK // Encoder - #define BTN_EN1 EXP1_03_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_04_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_07_PIN #endif diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h index 17e13bdc87..f59d61434e 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -89,14 +89,14 @@ // 2 +5V +5V // 1 GND GND -#define EXP1_03_PIN PE14 -#define EXP1_04_PIN PE15 -#define EXP1_05_PIN PE9 -#define EXP1_06_PIN PE8 -#define EXP1_07_PIN PE10 -#define EXP1_08_PIN PE12 -#define EXP1_09_PIN PE11 -#define EXP1_10_PIN PE13 +#define EXP1_08_PIN PE14 +#define EXP1_07_PIN PE15 +#define EXP1_06_PIN PE9 +#define EXP1_05_PIN PE8 +#define EXP1_04_PIN PE10 +#define EXP1_03_PIN PE12 +#define EXP1_02_PIN PE11 +#define EXP1_01_PIN PE13 // EXP2 connector // MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 @@ -111,12 +111,12 @@ // 2 +5V +5V // 1 GND GND -#define EXP2_03_PIN PB3 -#define EXP2_04_PIN PB5 -#define EXP2_05_PIN PB4 -#define EXP2_06_PIN PA15 -#define EXP2_07_PIN PA10 -#define EXP2_08_PIN PA9 +#define EXP2_08_PIN PB3 +#define EXP2_07_PIN PB5 +#define EXP2_06_PIN PB4 +#define EXP2_05_PIN PA15 +#define EXP2_04_PIN PA10 +#define EXP2_03_PIN PA9 // AUX1 connector // 1 +5V @@ -279,55 +279,55 @@ // #if ENABLED(ZONESTAR_12864LCD) #define LCDSCREEN_NAME "ZONESTAR LCD12864" - #define LCD_PINS_RS EXP1_08_PIN // 7 CS make sure for zonestar zm3e4! - #define LCD_PINS_ENABLE EXP1_05_PIN // 6 DATA make sure for zonestar zm3e4! - #define LCD_PINS_D4 EXP1_07_PIN // 8 SCK make sure for zonestar zm3e4! - #define BEEPER_PIN EXP1_09_PIN - #define KILL_PIN -1 // EXP1_10_PIN - #define BTN_EN1 EXP1_06_PIN - #define BTN_EN2 EXP1_03_PIN - #define BTN_ENC EXP1_04_PIN + #define LCD_PINS_RS EXP1_03_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP1_06_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP1_04_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP1_02_PIN + #define KILL_PIN -1 // EXP1_01_PIN + #define BTN_EN1 EXP1_05_PIN + #define BTN_EN2 EXP1_08_PIN + #define BTN_ENC EXP1_07_PIN #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define LCDSCREEN_NAME "REPRAPDISCOUNT LCD12864" - #define LCD_PINS_RS EXP1_08_PIN // 7 CS make sure for zonestar zm3e4! - #define LCD_PINS_ENABLE EXP1_07_PIN // 6 DATA make sure for zonestar zm3e4! - #define LCD_PINS_D4 EXP1_05_PIN // 8 SCK make sure for zonestar zm3e4! - #define BEEPER_PIN EXP1_09_PIN - #define KILL_PIN EXP2_04_PIN - #define BTN_EN1 EXP2_05_PIN - #define BTN_EN2 EXP2_07_PIN - #define BTN_ENC EXP1_10_PIN + #define LCD_PINS_RS EXP1_03_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP1_04_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP1_06_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP1_02_PIN + #define KILL_PIN EXP2_07_PIN + #define BTN_EN1 EXP2_06_PIN + #define BTN_EN2 EXP2_04_PIN + #define BTN_ENC EXP1_01_PIN #elif ENABLED(ZONESTAR_DWIN_LCD) // Connect to EXP2 connector #define LCDSCREEN_NAME "ZONESTAR DWIN LCD" - #define BEEPER_PIN EXP2_06_PIN + #define BEEPER_PIN EXP2_05_PIN #define KILL_PIN PC0 - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_04_PIN - #define BTN_ENC EXP2_05_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_07_PIN + #define BTN_ENC EXP2_06_PIN #endif #if ENABLED(ZONESTAR_LCD2004_KNOB) #define LCDSCREEN_NAME "LCD2004 KNOB" - #define LCD_PINS_RS EXP1_08_PIN - #define LCD_PINS_ENABLE EXP1_07_PIN - #define LCD_PINS_D4 EXP1_05_PIN - #define LCD_PINS_D5 EXP1_06_PIN - #define LCD_PINS_D6 EXP1_03_PIN - #define LCD_PINS_D7 EXP1_04_PIN - #define BTN_EN1 EXP2_07_PIN - #define BTN_EN2 EXP2_05_PIN - #define BTN_ENC EXP1_10_PIN - #define BEEPER_PIN EXP1_09_PIN - #define KILL_PIN EXP2_04_PIN + #define LCD_PINS_RS EXP1_03_PIN + #define LCD_PINS_ENABLE EXP1_04_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_08_PIN + #define LCD_PINS_D7 EXP1_07_PIN + #define BTN_EN1 EXP2_04_PIN + #define BTN_EN2 EXP2_06_PIN + #define BTN_ENC EXP1_01_PIN + #define BEEPER_PIN EXP1_02_PIN + #define KILL_PIN EXP2_07_PIN #elif ENABLED(ZONESTAR_LCD2004_ADCKEY) #define LCDSCREEN_NAME "LCD2004 5KEY" - #define LCD_PINS_RS EXP1_08_PIN - #define LCD_PINS_ENABLE EXP1_07_PIN - #define LCD_PINS_D4 EXP1_05_PIN - #define LCD_PINS_D5 EXP1_06_PIN - #define LCD_PINS_D6 EXP1_03_PIN - #define LCD_PINS_D7 EXP1_04_PIN + #define LCD_PINS_RS EXP1_03_PIN + #define LCD_PINS_ENABLE EXP1_04_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_08_PIN + #define LCD_PINS_D7 EXP1_07_PIN #define ADC_KEYPAD_PIN PC0 // PIN6 of AUX1 #endif @@ -341,16 +341,16 @@ // Remap SERVO0 PIN for BLTouch #if ENABLED(BLTOUCH_ON_EXP1) // BLTouch connected to EXP1 - #define BLTOUCH_PROBE_PIN EXP1_06_PIN - #define BLTOUCH_GND_PIN EXP1_04_PIN + #define BLTOUCH_PROBE_PIN EXP1_05_PIN + #define BLTOUCH_GND_PIN EXP1_07_PIN #undef SERVO0_PIN - #define SERVO0_PIN EXP1_03_PIN + #define SERVO0_PIN EXP1_08_PIN #elif ENABLED(BLTOUCH_ON_EXP2) // BLTouch connected to EXP2 - #define BLTOUCH_PROBE_PIN EXP2_03_PIN - #define BLTOUCH_GND_PIN EXP2_04_PIN + #define BLTOUCH_PROBE_PIN EXP2_08_PIN + #define BLTOUCH_GND_PIN EXP2_07_PIN #undef SERVO0_PIN - #define SERVO0_PIN EXP2_06_PIN + #define SERVO0_PIN EXP2_05_PIN #else #define BLTOUCH_PROBE_PIN PB13 #endif diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h index df0eb9c3d8..f83ce52fe9 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -90,14 +90,14 @@ // 2 +5V // 1 GND -#define EXP1_03_PIN PE14 -#define EXP1_04_PIN PE15 -#define EXP1_05_PIN PE9 -#define EXP1_06_PIN PE8 -#define EXP1_07_PIN PE10 -#define EXP1_08_PIN PE12 -#define EXP1_09_PIN PE11 -#define EXP1_10_PIN PE13 +#define EXP1_08_PIN PE14 +#define EXP1_07_PIN PE15 +#define EXP1_06_PIN PE9 +#define EXP1_05_PIN PE8 +#define EXP1_04_PIN PE10 +#define EXP1_03_PIN PE12 +#define EXP1_02_PIN PE11 +#define EXP1_01_PIN PE13 // EXP2 connector // MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 @@ -112,14 +112,14 @@ // 2 +5V // 1 GND -#define EXP2_03_PIN PB3 -#define EXP2_04_PIN PB5 -#define EXP2_05_PIN PB4 -#define EXP2_06_PIN PA15 -#define EXP2_07_PIN PA10 -#define EXP2_08_PIN PA9 -#define EXP2_09_PIN PE7 -#define EXP2_10_PIN PC0 +#define EXP2_08_PIN PB3 +#define EXP2_07_PIN PB5 +#define EXP2_06_PIN PB4 +#define EXP2_05_PIN PA15 +#define EXP2_04_PIN PA10 +#define EXP2_03_PIN PA9 +#define EXP2_02_PIN PE7 +#define EXP2_01_PIN PC0 // AUX1 connector // 1 +5V @@ -276,32 +276,32 @@ #if ENABLED(ZONESTAR_12864LCD) #define LCDSCREEN_NAME "ZONESTAR LCD12864" - #define LCD_PINS_RS EXP1_08_PIN // 7 CS make sure for zonestar zm3e4! - #define LCD_PINS_ENABLE EXP1_05_PIN // 6 DATA make sure for zonestar zm3e4! - #define LCD_PINS_D4 EXP1_07_PIN // 8 SCK make sure for zonestar zm3e4! - #define BEEPER_PIN EXP1_09_PIN - #define KILL_PIN -1 // EXP1_10_PIN - #define BTN_EN1 EXP1_06_PIN - #define BTN_EN2 EXP1_03_PIN - #define BTN_ENC EXP1_04_PIN + #define LCD_PINS_RS EXP1_03_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP1_06_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP1_04_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP1_02_PIN + #define KILL_PIN -1 // EXP1_01_PIN + #define BTN_EN1 EXP1_05_PIN + #define BTN_EN2 EXP1_08_PIN + #define BTN_ENC EXP1_07_PIN #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define LCDSCREEN_NAME "REPRAPDISCOUNT LCD12864" - #define LCD_PINS_RS EXP2_08_PIN // 7 CS make sure for zonestar zm3e4! - #define LCD_PINS_ENABLE EXP2_05_PIN // 6 DATA make sure for zonestar zm3e4! - #define LCD_PINS_D4 EXP2_07_PIN // 8 SCK make sure for zonestar zm3e4! - #define BEEPER_PIN EXP2_10_PIN - #define KILL_PIN EXP2_09_PIN - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP2_04_PIN + #define LCD_PINS_RS EXP2_03_PIN // 7 CS make sure for zonestar zm3e4! + #define LCD_PINS_ENABLE EXP2_06_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_D4 EXP2_04_PIN // 8 SCK make sure for zonestar zm3e4! + #define BEEPER_PIN EXP2_01_PIN + #define KILL_PIN EXP2_02_PIN + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP2_07_PIN #elif ENABLED(ZONESTAR_DWIN_LCD) // Connect to EXP2 connector #define LCDSCREEN_NAME "ZONESTAR DWIN LCD" - #define BEEPER_PIN EXP2_06_PIN // PE11 - #define KILL_PIN -1 // EXP1_10_PIN - #define BTN_EN2 EXP2_04_PIN // PE8 - #define BTN_EN1 EXP2_03_PIN // PE14 - #define BTN_ENC EXP2_05_PIN // PE15 + #define BEEPER_PIN EXP2_05_PIN // PE11 + #define KILL_PIN -1 // EXP1_01_PIN + #define BTN_EN2 EXP2_07_PIN // PE8 + #define BTN_EN1 EXP2_08_PIN // PE14 + #define BTN_ENC EXP2_06_PIN // PE15 #endif // Alter timing for graphical display @@ -314,16 +314,16 @@ // Remap SERVO0 PIN for BLTouch #if ENABLED(BLTOUCH_ON_EXP1) // BLTouch connected to EXP1 - #define BLTOUCH_PROBE_PIN EXP1_06_PIN - #define BLTOUCH_GND_PIN EXP1_04_PIN + #define BLTOUCH_PROBE_PIN EXP1_05_PIN + #define BLTOUCH_GND_PIN EXP1_07_PIN #undef SERVO0_PIN - #define SERVO0_PIN EXP1_03_PIN + #define SERVO0_PIN EXP1_08_PIN #elif ENABLED(BLTOUCH_ON_EXP2) // BLTouch connected to EXP2 - #define BLTOUCH_PROBE_PIN EXP2_03_PIN - #define BLTOUCH_GND_PIN EXP2_04_PIN + #define BLTOUCH_PROBE_PIN EXP2_08_PIN + #define BLTOUCH_GND_PIN EXP2_07_PIN #undef SERVO0_PIN - #define SERVO0_PIN EXP2_06_PIN + #define SERVO0_PIN EXP2_05_PIN #else #define BLTOUCH_PROBE_PIN PB13 // Z1_MAX #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 531ab7a958..aadce03c56 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -199,109 +199,109 @@ /** * ---------------------------------BTT002 V1.0--------------------------------- * ------ ------ | - * (BEEPER) PE7 |10 9 | PB1 (BTN_ENC) (MISO) PA6 |10 9 | PA5 (SCK) | - * (LCD_EN) PE9 | 8 7 | PE8 (LCD_RS) (BTN_EN1) PC5 | 8 7 | PA4 (SD_SS) | - * (LCD_D4) PE10 6 5 | PE11 (LCD_D5) (BTN_EN2) PB0 6 5 | PA7 (MOSI) | - * (LCD_D6) PE12 | 4 3 | PE13 (LCD_D7) (SD_DET) PC4 | 4 3 | RESET | - * GND | 2 1 | 5V GND | 2 1 | PA3 | + * (BEEPER) PE7 | 1 2 | PB1 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) | + * (LCD_EN) PE9 | 3 4 | PE8 (LCD_RS) (BTN_EN1) PC5 | 3 4 | PA4 (SD_SS) | + * (LCD_D4) PE10 5 6 | PE11 (LCD_D5) (BTN_EN2) PB0 5 6 | PA7 (MOSI) | + * (LCD_D6) PE12 | 7 8 | PE13 (LCD_D7) (SD_DET) PC4 | 7 8 | RESET | + * GND | 9 10 | 5V GND | 9 10 | PA3 | * ------ ------ | * EXP1 EXP2 | * ------------------------------------------------------------------------------ */ -#define EXP1_03_PIN PE13 -#define EXP1_04_PIN PE12 -#define EXP1_05_PIN PE11 -#define EXP1_06_PIN PE10 -#define EXP1_07_PIN PE8 -#define EXP1_08_PIN PE9 -#define EXP1_09_PIN PB1 -#define EXP1_10_PIN PE7 - -#define EXP2_01_PIN PA3 -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PC4 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PB0 -#define EXP2_07_PIN PA4 -#define EXP2_08_PIN PC5 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PE13 +#define EXP1_07_PIN PE12 +#define EXP1_06_PIN PE11 +#define EXP1_05_PIN PE10 +#define EXP1_04_PIN PE8 +#define EXP1_03_PIN PE9 +#define EXP1_02_PIN PB1 +#define EXP1_01_PIN PE7 + +#define EXP2_10_PIN PA3 +#define EXP2_08_PIN -1 +#define EXP2_07_PIN PC4 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PB0 +#define EXP2_04_PIN PA4 +#define EXP2_03_PIN PC5 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 // HAL SPI1 pins -#define SD_SCK_PIN EXP2_09_PIN // SPI1 SCLK -#define SD_SS_PIN EXP2_07_PIN // SPI1 SSEL -#define SD_MISO_PIN EXP2_10_PIN // SPI1 MISO -#define SD_MOSI_PIN EXP2_05_PIN // SPI1 MOSI +#define SD_SCK_PIN EXP2_02_PIN // SPI1 SCLK +#define SD_SS_PIN EXP2_04_PIN // SPI1 SSEL +#define SD_MISO_PIN EXP2_01_PIN // SPI1 MISO +#define SD_MOSI_PIN EXP2_06_PIN // SPI1 MOSI -#define SDSS EXP2_07_PIN +#define SDSS EXP2_04_PIN // // LCDs and Controllers // #if HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #else - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN - #define DOGLCD_MOSI EXP2_05_PIN - #define DOGLCD_MISO EXP2_10_PIN - #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_MOSI EXP2_06_PIN + #define DOGLCD_MISO EXP2_01_PIN + #define DOGLCD_SCK EXP2_02_PIN #define LCD_BACKLIGHT_PIN -1 #define FORCE_SOFT_SPI - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif // !FYSETC_MINI_12864 #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index c7cd35c7ad..ca257d257b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -186,11 +186,11 @@ /** * BTT E3 RRF * ------ - * (BEEPER) PE8 |10 9 | PE9 (BTN_ENC) - * (BTN_EN1) PE7 | 8 7 | RESET - * (BTN_EN2) PB2 6 5 | PE10 (LCD_D4) - * (LCD_RS) PB1 | 4 3 | PE11 (LCD_EN) - * GND | 2 1 | 5V + * (BEEPER) PE8 | 1 2 | PE9 (BTN_ENC) + * (BTN_EN1) PE7 | 3 4 | RESET + * (BTN_EN2) PB2 5 6 | PE10 (LCD_D4) + * (LCD_RS) PB1 | 7 8 | PE11 (LCD_EN) + * GND | 9 10 | 5V * ------ * EXP1 */ @@ -219,11 +219,11 @@ * * BTT E3 RRF Display Ribbon * ------ ------ - * (BEEPER) PE8 |10 9 | PE9 (BTN_ENC) GND |10 9 | 5V - * (BTN_EN1) PE7 | 8 7 | RESET BEEPER | 8 7 | ESTOP (RESET) - * (BTN_EN2) PB2 6 5 | PE10 (LCD_D4) (BTN_ENC) ENC_BTN | 6 5 | LCD_SCLK (LCD_D4) - * (LCD_RS) PB1 | 4 3 | PE11 (LCD_EN) (BTN_EN2) ENC_A | 4 3 | LCD_DATA (LCD_EN) - * GND | 2 1 | 5V (BTN_EN1) ENC_B | 2 1 | LCD_CS (LCD_RS) + * (BEEPER) PE8 | 1 2 | PE9 (BTN_ENC) GND | 1 2 | 5V + * (BTN_EN1) PE7 | 3 4 | RESET BEEPER | 3 4 | ESTOP (RESET) + * (BTN_EN2) PB2 5 6 | PE10 (LCD_D4) (BTN_ENC) ENC_BTN | 5 6 | LCD_SCLK (LCD_D4) + * (LCD_RS) PB1 | 7 8 | PE11 (LCD_EN) (BTN_EN2) ENC_A | 7 8 | LCD_DATA (LCD_EN) + * GND | 9 10 | 5V (BTN_EN1) ENC_B | 9 10 | LCD_CS (LCD_RS) * ------ ------ * EXP1 Ribbon * @@ -286,11 +286,11 @@ * * Board Display * ------ ------ - * (SD_DET) PE8 |10 9 | PE9 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PE7 | 8 7 | RESET -- | 8 7 | (SD_DET) - * (SD_CS) PB2 6 5 | PE10 (MOSI) 6 5 | -- - * (LCD_CS) PB1 | 4 3 | PE11 (SD_CS) | 4 3 | (LCD_CS) - * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * (SD_DET) PE8 | 1 2 | PE9 (BEEPER) 5V | 1 2 | GND + * (MOD_RESET) PE7 | 3 4 | RESET -- | 3 4 | (SD_DET) + * (SD_CS) PB2 5 6 | PE10 (MOSI) 5 6 | -- + * (LCD_CS) PB1 | 7 8 | PE11 (SD_CS) | 7 8 | (LCD_CS) + * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) * ------ ------ * EXP1 EXP1 * @@ -341,11 +341,11 @@ * * Board Display * ------ ------ - * (SD_DET) PE8 |10 9 | PE9 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PE7 | 8 7 | RESET RESET | 8 7 | (SD_DET) - * (SD_CS) PB2 6 5 | PE10 (MOSI) | 6 5 | (LCD_CS) - * (LCD_CS) PB1 | 4 3 | PE11 (SD_CS) | 4 3 | (MOD_RESET) - * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * (SD_DET) PE8 | 1 2 | PE9 (BEEPER) 5V | 1 2 | GND + * (MOD_RESET) PE7 | 3 4 | RESET RESET | 3 4 | (SD_DET) + * (SD_CS) PB2 5 6 | PE10 (MOSI) | 5 6 | (LCD_CS) + * (LCD_CS) PB1 | 7 8 | PE11 (SD_CS) | 7 8 | (MOD_RESET) + * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) * ------ ------ * EXP1 EXP1 * diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index b9525a9267..b341f3ae07 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -348,8 +348,8 @@ // #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN EXP2_04_PIN - #define SDSS EXP2_07_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #define SDSS EXP2_04_PIN #elif SD_CONNECTION_IS(ONBOARD) @@ -366,112 +366,112 @@ /** * ------ ------ - * (BEEPER) PC11 |10 9 | PA15 (BTN_ENC) (MISO) PB14 |10 9 | PB13 (SCK) - * (LCD_EN) PC10 | 8 7 | PA8 (LCD_RS) (BTN_EN1) PD10 | 8 7 | PB12 (SD_SS) - * (LCD_D4) PG8 6 5 | PG7 (LCD_D5) (BTN_EN2) PH10 6 5 | PB15 (MOSI) - * (LCD_D6) PG6 | 4 3 | PG5 (LCD_D7) (SD_DETECT) PB10 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) PC11 | 1 2 | PA15 (BTN_ENC) (MISO) PB14 | 1 2 | PB13 (SCK) + * (LCD_EN) PC10 | 3 4 | PA8 (LCD_RS) (BTN_EN1) PD10 | 3 4 | PB12 (SD_SS) + * (LCD_D4) PG8 5 6 | PG7 (LCD_D5) (BTN_EN2) PH10 5 6 | PB15 (MOSI) + * (LCD_D6) PG6 | 7 8 | PG5 (LCD_D7) (SD_DETECT) PB10 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PG5 -#define EXP1_04_PIN PG6 -#define EXP1_05_PIN PG7 -#define EXP1_06_PIN PG8 -#define EXP1_07_PIN PA8 -#define EXP1_08_PIN PC10 -#define EXP1_09_PIN PA15 -#define EXP1_10_PIN PC11 - -#define EXP2_04_PIN PB10 -#define EXP2_05_PIN PB15 -#define EXP2_06_PIN PH10 -#define EXP2_07_PIN PB12 -#define EXP2_08_PIN PD10 -#define EXP2_09_PIN PB13 -#define EXP2_10_PIN PB14 +#define EXP1_08_PIN PG5 +#define EXP1_07_PIN PG6 +#define EXP1_06_PIN PG7 +#define EXP1_05_PIN PG8 +#define EXP1_04_PIN PA8 +#define EXP1_03_PIN PC10 +#define EXP1_02_PIN PA15 +#define EXP1_01_PIN PC11 + +#define EXP2_07_PIN PB10 +#define EXP2_06_PIN PB15 +#define EXP2_05_PIN PH10 +#define EXP2_04_PIN PB12 +#define EXP2_03_PIN PD10 +#define EXP2_02_PIN PB13 +#define EXP2_01_PIN PB14 // // LCDs and Controllers // #if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) - #define TFT_CS_PIN EXP2_07_PIN - #define TFT_A0_PIN EXP2_04_PIN - #define TFT_SCK_PIN EXP2_09_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_MOSI_PIN EXP2_05_PIN - - #define TOUCH_INT_PIN EXP1_04_PIN - #define TOUCH_MISO_PIN EXP1_05_PIN - #define TOUCH_MOSI_PIN EXP1_08_PIN - #define TOUCH_SCK_PIN EXP1_06_PIN - #define TOUCH_CS_PIN EXP1_07_PIN - #define BTN_ENC EXP1_09_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define TFT_CS_PIN EXP2_04_PIN + #define TFT_A0_PIN EXP2_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define TOUCH_INT_PIN EXP1_07_PIN + #define TOUCH_MISO_PIN EXP1_06_PIN + #define TOUCH_MOSI_PIN EXP1_03_PIN + #define TOUCH_SCK_PIN EXP1_05_PIN + #define TOUCH_CS_PIN EXP1_04_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #elif HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #if SD_CONNECTION_IS(ONBOARD) #define SOFTWARE_SPI #endif #else - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN #if SD_CONNECTION_IS(ONBOARD) #define SOFTWARE_SPI #endif //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif // !FYSETC_MINI_12864 #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 4255881baf..8f04ae1d73 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -322,31 +322,31 @@ #endif /** ------ ------ - * (BEEPER) PE8 |10 9 | PE7 (BTN_ENC) (MISO) PA6 |10 9 | PA5 (SCK) - * (LCD_EN) PE9 | 8 7 | PE10 (LCD_RS) (BTN_EN1) PB2 | 8 7 | PA4 (SD_SS) - * (LCD_D4) PE12 6 5 | PE13 (LCD_D5) (BTN_EN2) PB1 6 5 | PA7 (MOSI) - * (LCD_D6) PE14 | 4 3 | PE15 (LCD_D7) (SD_DETECT) PC15 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) PE8 | 1 2 | PE7 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) + * (LCD_EN) PE9 | 3 4 | PE10 (LCD_RS) (BTN_EN1) PB2 | 3 4 | PA4 (SD_SS) + * (LCD_D4) PE12 5 6 | PE13 (LCD_D5) (BTN_EN2) PB1 5 6 | PA7 (MOSI) + * (LCD_D6) PE14 | 7 8 | PE15 (LCD_D7) (SD_DETECT) PC15 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PE15 -#define EXP1_04_PIN PE14 -#define EXP1_05_PIN PE13 -#define EXP1_06_PIN PE12 -#define EXP1_07_PIN PE10 -#define EXP1_08_PIN PE9 -#define EXP1_09_PIN PE7 -#define EXP1_10_PIN PE8 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PC15 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PB2 -#define EXP2_07_PIN PA4 -#define EXP2_08_PIN PB1 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PE15 +#define EXP1_07_PIN PE14 +#define EXP1_06_PIN PE13 +#define EXP1_05_PIN PE12 +#define EXP1_04_PIN PE10 +#define EXP1_03_PIN PE9 +#define EXP1_02_PIN PE7 +#define EXP1_01_PIN PE8 + +#define EXP2_08_PIN -1 +#define EXP2_07_PIN PC15 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PB2 +#define EXP2_04_PIN PA4 +#define EXP2_03_PIN PB1 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 // // Onboard SD card @@ -376,45 +376,45 @@ #if ENABLED(BTT_MOTOR_EXPANSION) /** * ------ ------ - * M3DIAG |10 9 | M3RX M3STP |10 9 | M3DIR - * M2DIAG | 8 7 | M2RX M2STP | 8 7 | M2DIR - * M1DIAG 6 5 | M1RX M1DIR 6 5 | M1STP - * M3EN | 4 3 | M2EN M1EN | 4 3 | -- - * GND | 2 1 | -- GND | 2 1 | -- + * M3DIAG | 1 2 | M3RX M3STP | 1 2 | M3DIR + * M2DIAG | 3 4 | M2RX M2STP | 3 4 | M2DIR + * M1DIAG 5 6 | M1RX M1DIR 5 6 | M1STP + * M3EN | 7 8 | M2EN M1EN | 7 8 | -- + * GND | 9 10 | -- GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ // M1 on Driver Expansion Module - #define E4_STEP_PIN EXP2_05_PIN - #define E4_DIR_PIN EXP2_06_PIN - #define E4_ENABLE_PIN EXP2_04_PIN - #define E4_DIAG_PIN EXP1_06_PIN - #define E4_CS_PIN EXP1_05_PIN + #define E4_STEP_PIN EXP2_06_PIN + #define E4_DIR_PIN EXP2_05_PIN + #define E4_ENABLE_PIN EXP2_07_PIN + #define E4_DIAG_PIN EXP1_05_PIN + #define E4_CS_PIN EXP1_06_PIN #if HAS_TMC_UART - #define E4_SERIAL_TX_PIN EXP1_05_PIN + #define E4_SERIAL_TX_PIN EXP1_06_PIN #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN #endif // M2 on Driver Expansion Module - #define E5_STEP_PIN EXP2_08_PIN - #define E5_DIR_PIN EXP2_07_PIN - #define E5_ENABLE_PIN EXP1_03_PIN - #define E5_DIAG_PIN EXP1_08_PIN - #define E5_CS_PIN EXP1_07_PIN + #define E5_STEP_PIN EXP2_03_PIN + #define E5_DIR_PIN EXP2_04_PIN + #define E5_ENABLE_PIN EXP1_08_PIN + #define E5_DIAG_PIN EXP1_03_PIN + #define E5_CS_PIN EXP1_04_PIN #if HAS_TMC_UART - #define E5_SERIAL_TX_PIN EXP1_07_PIN + #define E5_SERIAL_TX_PIN EXP1_04_PIN #define E5_SERIAL_RX_PIN E5_SERIAL_TX_PIN #endif // M3 on Driver Expansion Module - #define E6_STEP_PIN EXP2_10_PIN - #define E6_DIR_PIN EXP2_09_PIN - #define E6_ENABLE_PIN EXP1_04_PIN - #define E6_DIAG_PIN EXP1_10_PIN - #define E6_CS_PIN EXP1_09_PIN + #define E6_STEP_PIN EXP2_01_PIN + #define E6_DIR_PIN EXP2_02_PIN + #define E6_ENABLE_PIN EXP1_07_PIN + #define E6_DIAG_PIN EXP1_01_PIN + #define E6_CS_PIN EXP1_02_PIN #if HAS_TMC_UART - #define E6_SERIAL_TX_PIN EXP1_09_PIN + #define E6_SERIAL_TX_PIN EXP1_02_PIN #define E6_SERIAL_RX_PIN E6_SERIAL_TX_PIN #endif @@ -426,58 +426,58 @@ #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif #elif HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #else - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif // !FYSETC_MINI_12864 #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -496,21 +496,21 @@ #endif #if HAS_SPI_TFT - #define TFT_CS_PIN EXP2_07_PIN - #define TFT_A0_PIN EXP2_04_PIN - #define TFT_SCK_PIN EXP2_09_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_MOSI_PIN EXP2_05_PIN - - #define TOUCH_INT_PIN EXP1_04_PIN - #define TOUCH_MISO_PIN EXP1_05_PIN - #define TOUCH_MOSI_PIN EXP1_08_PIN - #define TOUCH_SCK_PIN EXP1_06_PIN - #define TOUCH_CS_PIN EXP1_07_PIN - - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define TFT_CS_PIN EXP2_04_PIN + #define TFT_A0_PIN EXP2_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define TOUCH_INT_PIN EXP1_07_PIN + #define TOUCH_MISO_PIN EXP1_06_PIN + #define TOUCH_MOSI_PIN EXP1_03_PIN + #define TOUCH_SCK_PIN EXP1_05_PIN + #define TOUCH_CS_PIN EXP1_04_PIN + + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN #endif // diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 7c902b008c..9b49f27670 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -313,31 +313,31 @@ #endif /** ------ ------ - * (BEEPER) PG4 |10 9 | PA8 (BTN_ENC) (MISO) PB14 |10 9 | PB13 (SCK) - * (LCD_EN) PD11 | 8 7 | PD10 (LCD_RS) (BTN_EN1) PG10 | 8 7 | PB12 (SD_SS) - * (LCD_D4) PG2 6 5 | PG3 (LCD_D5) (BTN_EN2) PF11 6 5 | PB15 (MOSI) - * (LCD_D6) PG6 | 4 3 | PG7 (LCD_D7) (SD_DETECT) PF12 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) PG4 | 1 2 | PA8 (BTN_ENC) (MISO) PB14 | 1 2 | PB13 (SCK) + * (LCD_EN) PD11 | 3 4 | PD10 (LCD_RS) (BTN_EN1) PG10 | 3 4 | PB12 (SD_SS) + * (LCD_D4) PG2 5 6 | PG3 (LCD_D5) (BTN_EN2) PF11 5 6 | PB15 (MOSI) + * (LCD_D6) PG6 | 7 8 | PG7 (LCD_D7) (SD_DETECT) PF12 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PG7 -#define EXP1_04_PIN PG6 -#define EXP1_05_PIN PG3 -#define EXP1_06_PIN PG2 -#define EXP1_07_PIN PD10 -#define EXP1_08_PIN PD11 -#define EXP1_09_PIN PA8 -#define EXP1_10_PIN PG4 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PF12 -#define EXP2_05_PIN PB15 -#define EXP2_06_PIN PF11 -#define EXP2_07_PIN PB12 -#define EXP2_08_PIN PG10 -#define EXP2_09_PIN PB13 -#define EXP2_10_PIN PB14 +#define EXP1_08_PIN PG7 +#define EXP1_07_PIN PG6 +#define EXP1_06_PIN PG3 +#define EXP1_05_PIN PG2 +#define EXP1_04_PIN PD10 +#define EXP1_03_PIN PD11 +#define EXP1_02_PIN PA8 +#define EXP1_01_PIN PG4 + +#define EXP2_08_PIN -1 +#define EXP2_07_PIN PF12 +#define EXP2_06_PIN PB15 +#define EXP2_05_PIN PF11 +#define EXP2_04_PIN PB12 +#define EXP2_03_PIN PG10 +#define EXP2_02_PIN PB13 +#define EXP2_01_PIN PB14 // // Onboard SD card @@ -345,8 +345,8 @@ // #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN EXP2_04_PIN - #define SDSS EXP2_07_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #define SDSS EXP2_04_PIN #elif SD_CONNECTION_IS(ONBOARD) @@ -379,46 +379,46 @@ */ // M1 on Driver Expansion Module - #define E3_STEP_PIN EXP2_05_PIN - #define E3_DIR_PIN EXP2_06_PIN - #define E3_ENABLE_PIN EXP2_04_PIN + #define E3_STEP_PIN EXP2_06_PIN + #define E3_DIR_PIN EXP2_05_PIN + #define E3_ENABLE_PIN EXP2_07_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E3_DIAG_PIN EXP1_06_PIN - #define E3_CS_PIN EXP1_05_PIN + #define E3_DIAG_PIN EXP1_05_PIN + #define E3_CS_PIN EXP1_06_PIN #if HAS_TMC_UART - #define E3_SERIAL_TX_PIN EXP1_05_PIN - #define E3_SERIAL_RX_PIN EXP1_05_PIN + #define E3_SERIAL_TX_PIN EXP1_06_PIN + #define E3_SERIAL_RX_PIN EXP1_06_PIN #endif #endif // M2 on Driver Expansion Module - #define E4_STEP_PIN EXP2_08_PIN - #define E4_DIR_PIN EXP2_07_PIN + #define E4_STEP_PIN EXP2_03_PIN + #define E4_DIR_PIN EXP2_04_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E4_ENABLE_PIN EXP1_03_PIN - #define E4_DIAG_PIN EXP1_08_PIN - #define E4_CS_PIN EXP1_07_PIN + #define E4_ENABLE_PIN EXP1_08_PIN + #define E4_DIAG_PIN EXP1_03_PIN + #define E4_CS_PIN EXP1_04_PIN #if HAS_TMC_UART - #define E4_SERIAL_TX_PIN EXP1_07_PIN - #define E4_SERIAL_RX_PIN EXP1_07_PIN + #define E4_SERIAL_TX_PIN EXP1_04_PIN + #define E4_SERIAL_RX_PIN EXP1_04_PIN #endif #else - #define E4_ENABLE_PIN EXP2_04_PIN + #define E4_ENABLE_PIN EXP2_07_PIN #endif // M3 on Driver Expansion Module - #define E5_STEP_PIN EXP2_10_PIN - #define E5_DIR_PIN EXP2_09_PIN + #define E5_STEP_PIN EXP2_01_PIN + #define E5_DIR_PIN EXP2_02_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E5_ENABLE_PIN EXP1_04_PIN - #define E5_DIAG_PIN EXP1_10_PIN - #define E5_CS_PIN EXP1_09_PIN + #define E5_ENABLE_PIN EXP1_07_PIN + #define E5_DIAG_PIN EXP1_01_PIN + #define E5_CS_PIN EXP1_02_PIN #if HAS_TMC_UART - #define E5_SERIAL_TX_PIN EXP1_09_PIN - #define E5_SERIAL_RX_PIN EXP1_09_PIN + #define E5_SERIAL_TX_PIN EXP1_02_PIN + #define E5_SERIAL_RX_PIN EXP1_02_PIN #endif #else - #define E5_ENABLE_PIN EXP2_04_PIN + #define E5_ENABLE_PIN EXP2_07_PIN #endif #endif // BTT_MOTOR_EXPANSION @@ -429,30 +429,30 @@ #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif #elif HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #elif ENABLED(WYH_L12864) @@ -470,59 +470,59 @@ * * BEFORE AFTER * ------ ------ - * -- |10 9 | MOSI -- |10 9 | MOSI - * BTN_ENC | 8 7 | SCK BTN_ENC | 8 7 | SCK - * BTN_EN1 | 6 5 SID BTN_EN1 | 6 5 SID - * BTN_EN2 | 4 3 | CS BTN_EN2 | 4 3 | CS - * 5V | 2 1 | GND GND | 2 1 | 5V + * -- | 1 2 | MOSI -- | 1 2 | MOSI + * BTN_ENC | 3 4 | SCK BTN_ENC | 3 4 | SCK + * BTN_EN1 | 5 6 SID BTN_EN1 | 5 6 SID + * BTN_EN2 | 7 8 | CS BTN_EN2 | 7 8 | CS + * 5V | 9 10 | GND GND | 9 10 | 5V * ------ ------ * LCD LCD */ #undef BEEPER_PIN #undef BTN_ENC - #define BTN_EN1 EXP1_06_PIN - #define BTN_EN2 EXP1_04_PIN - #define BTN_ENC EXP1_08_PIN - #define DOGLCD_CS EXP1_03_PIN - #define DOGLCD_A0 EXP1_05_PIN - #define DOGLCD_SCK EXP1_07_PIN - #define DOGLCD_MOSI EXP1_09_PIN + #define BTN_EN1 EXP1_05_PIN + #define BTN_EN2 EXP1_07_PIN + #define BTN_ENC EXP1_03_PIN + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_06_PIN + #define DOGLCD_SCK EXP1_04_PIN + #define DOGLCD_MOSI EXP1_02_PIN #define LCD_BACKLIGHT_PIN -1 #else - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif // !FYSETC_MINI_12864 #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -553,10 +553,10 @@ /** * ------ - * RX | 8 7 | 3.3V GPIO0 PF14 ... Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) - * GPIO0 | 6 5 | Reset GPIO2 PF15 ... must be high (ESP3D software configures this with a pullup so OK to leave as floating) - * GPIO2 | 4 3 | Enable Reset PG0 ... active low, probably OK to leave floating - * GND | 2 1 | TX Enable PG1 ... Must be high for module to run + * RX | 3 4 | 3.3V GPIO0 PF14 ... Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) + * GPIO0 | 5 6 | Reset GPIO2 PF15 ... must be high (ESP3D software configures this with a pullup so OK to leave as floating) + * GPIO2 | 7 8 | Enable Reset PG0 ... active low, probably OK to leave floating + * GND | 9 10 | TX Enable PG1 ... Must be high for module to run * ------ * W1 */ diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 4e311d4862..9c22ac804d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -336,43 +336,43 @@ /** * ------ ------ - * (BEEPER) PC5 |10 9 | PB0 (BTN_ENC) (MISO) PA6 |10 9 | PA5 (SCK) - * (LCD_EN) PB1 | 8 7 | PE9 (LCD_RS) (BTN_EN1) PE7 | 8 7 | PA4 (SD_SS) - * (LCD_D4) PE10 | 6 5 PE11 (LCD_D5) (BTN_EN2) PB2 | 6 5 PA7 (MOSI) - * (LCD_D6) PE12 | 4 3 | PE13 (LCD_D7) (SD_DETECT) PC4 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) PC5 | 1 2 | PB0 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) + * (LCD_EN) PB1 | 3 4 | PE9 (LCD_RS) (BTN_EN1) PE7 | 3 4 | PA4 (SD_SS) + * (LCD_D4) PE10 | 5 6 PE11 (LCD_D5) (BTN_EN2) PB2 | 5 6 PA7 (MOSI) + * (LCD_D6) PE12 | 7 8 | PE13 (LCD_D7) (SD_DETECT) PC4 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PE13 -#define EXP1_04_PIN PE12 -#define EXP1_05_PIN PE11 -#define EXP1_06_PIN PE10 -#define EXP1_07_PIN PE9 -#define EXP1_08_PIN PB1 -#define EXP1_09_PIN PB0 -#define EXP1_10_PIN PC5 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PC4 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PB2 -#define EXP2_07_PIN PA4 -#define EXP2_08_PIN PE7 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PE13 +#define EXP1_07_PIN PE12 +#define EXP1_06_PIN PE11 +#define EXP1_05_PIN PE10 +#define EXP1_04_PIN PE9 +#define EXP1_03_PIN PB1 +#define EXP1_02_PIN PB0 +#define EXP1_01_PIN PC5 + +#define EXP2_08_PIN -1 +#define EXP2_07_PIN PC4 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PB2 +#define EXP2_04_PIN PA4 +#define EXP2_03_PIN PE7 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 // // Onboard SD card // Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // #if SD_CONNECTION_IS(LCD) - #define SDSS EXP2_07_PIN + #define SDSS EXP2_04_PIN #define SD_SS_PIN SDSS - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_DETECT_PIN EXP2_07_PIN #elif SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD #elif SD_CONNECTION_IS(CUSTOM_CABLE) @@ -393,46 +393,46 @@ */ // M1 on Driver Expansion Module - #define E2_STEP_PIN EXP2_05_PIN - #define E2_DIR_PIN EXP2_06_PIN - #define E2_ENABLE_PIN EXP2_04_PIN + #define E2_STEP_PIN EXP2_06_PIN + #define E2_DIR_PIN EXP2_05_PIN + #define E2_ENABLE_PIN EXP2_07_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E2_DIAG_PIN EXP1_06_PIN - #define E2_CS_PIN EXP1_05_PIN + #define E2_DIAG_PIN EXP1_05_PIN + #define E2_CS_PIN EXP1_06_PIN #if HAS_TMC_UART - #define E2_SERIAL_TX_PIN EXP1_05_PIN - #define E2_SERIAL_RX_PIN EXP1_05_PIN + #define E2_SERIAL_TX_PIN EXP1_06_PIN + #define E2_SERIAL_RX_PIN EXP1_06_PIN #endif #endif // M2 on Driver Expansion Module - #define E3_STEP_PIN EXP2_08_PIN - #define E3_DIR_PIN EXP2_07_PIN + #define E3_STEP_PIN EXP2_03_PIN + #define E3_DIR_PIN EXP2_04_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E3_ENABLE_PIN EXP1_03_PIN - #define E3_DIAG_PIN EXP1_08_PIN - #define E3_CS_PIN EXP1_07_PIN + #define E3_ENABLE_PIN EXP1_08_PIN + #define E3_DIAG_PIN EXP1_03_PIN + #define E3_CS_PIN EXP1_04_PIN #if HAS_TMC_UART - #define E3_SERIAL_TX_PIN EXP1_07_PIN - #define E3_SERIAL_RX_PIN EXP1_07_PIN + #define E3_SERIAL_TX_PIN EXP1_04_PIN + #define E3_SERIAL_RX_PIN EXP1_04_PIN #endif #else - #define E3_ENABLE_PIN EXP2_04_PIN + #define E3_ENABLE_PIN EXP2_07_PIN #endif // M3 on Driver Expansion Module - #define E4_STEP_PIN EXP2_10_PIN - #define E4_DIR_PIN EXP2_09_PIN + #define E4_STEP_PIN EXP2_01_PIN + #define E4_DIR_PIN EXP2_02_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E4_ENABLE_PIN EXP1_04_PIN - #define E4_DIAG_PIN EXP1_10_PIN - #define E4_CS_PIN EXP1_09_PIN + #define E4_ENABLE_PIN EXP1_07_PIN + #define E4_DIAG_PIN EXP1_01_PIN + #define E4_CS_PIN EXP1_02_PIN #if HAS_TMC_UART - #define E4_SERIAL_TX_PIN EXP1_09_PIN - #define E4_SERIAL_RX_PIN EXP1_09_PIN + #define E4_SERIAL_TX_PIN EXP1_02_PIN + #define E4_SERIAL_RX_PIN EXP1_02_PIN #endif #else - #define E4_ENABLE_PIN EXP2_04_PIN + #define E4_ENABLE_PIN EXP2_07_PIN #endif #endif // BTT_MOTOR_EXPANSION @@ -443,65 +443,65 @@ #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif #elif HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #else - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif // !FYSETC_MINI_12864 #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -528,24 +528,24 @@ #if HAS_SPI_TFT - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN // // e.g., BTT_TFT35_SPI_V1_0 (480x320, 3.5", SPI Stock Display with Rotary Encoder in BIQU B1 SE) // - #define TFT_CS_PIN EXP2_07_PIN - #define TFT_A0_PIN EXP2_04_PIN - #define TFT_SCK_PIN EXP2_09_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_MOSI_PIN EXP2_05_PIN - - #define TOUCH_INT_PIN EXP1_04_PIN - #define TOUCH_MISO_PIN EXP1_05_PIN - #define TOUCH_MOSI_PIN EXP1_08_PIN - #define TOUCH_SCK_PIN EXP1_06_PIN - #define TOUCH_CS_PIN EXP1_07_PIN + #define TFT_CS_PIN EXP2_04_PIN + #define TFT_A0_PIN EXP2_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define TOUCH_INT_PIN EXP1_07_PIN + #define TOUCH_MISO_PIN EXP1_06_PIN + #define TOUCH_MOSI_PIN EXP1_03_PIN + #define TOUCH_SCK_PIN EXP1_05_PIN + #define TOUCH_CS_PIN EXP1_04_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 11b5dbbb6c..b98dcbf5d7 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -177,31 +177,31 @@ /** * ------ ------ - * PB10 |10 9 | PE15 PB14 |10 9 | PB13 - * PE14 | 8 7 | PE12 PC5 | 8 7 | PF11 - * PE10 6 5 | PE9 PC4 6 5 | PB15 - * PE8 | 4 3 | PE7 PB2 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * PB10 | 1 2 | PE15 PB14 | 1 2 | PB13 + * PE14 | 3 4 | PE12 PC5 | 3 4 | PF11 + * PE10 5 6 | PE9 PC4 5 6 | PB15 + * PE8 | 7 8 | PE7 PB2 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PE7 -#define EXP1_04_PIN PE8 -#define EXP1_05_PIN PE9 -#define EXP1_06_PIN PE10 -#define EXP1_07_PIN PE12 -#define EXP1_08_PIN PE14 -#define EXP1_09_PIN PE15 -#define EXP1_10_PIN PB10 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN PB2 -#define EXP2_05_PIN PB15 -#define EXP2_06_PIN PC4 -#define EXP2_07_PIN PF11 -#define EXP2_08_PIN PC5 -#define EXP2_09_PIN PB13 -#define EXP2_10_PIN PB14 +#define EXP1_08_PIN PE7 +#define EXP1_07_PIN PE8 +#define EXP1_06_PIN PE9 +#define EXP1_05_PIN PE10 +#define EXP1_04_PIN PE12 +#define EXP1_03_PIN PE14 +#define EXP1_02_PIN PE15 +#define EXP1_01_PIN PB10 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN PB2 +#define EXP2_06_PIN PB15 +#define EXP2_05_PIN PC4 +#define EXP2_04_PIN PF11 +#define EXP2_03_PIN PC5 +#define EXP2_02_PIN PB13 +#define EXP2_01_PIN PB14 // // Onboard SD support @@ -226,11 +226,11 @@ #elif SD_CONNECTION_IS(LCD) - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN - #define SDSS EXP2_07_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SDSS EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif @@ -239,13 +239,13 @@ // #if ENABLED(TMC_USE_SW_SPI) #ifndef TMC_SW_SCK - #define TMC_SW_SCK EXP2_09_PIN + #define TMC_SW_SCK EXP2_02_PIN #endif #ifndef TMC_SW_MISO - #define TMC_SW_MISO EXP2_10_PIN + #define TMC_SW_MISO EXP2_01_PIN #endif #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI EXP2_05_PIN + #define TMC_SW_MOSI EXP2_06_PIN #endif #endif @@ -286,16 +286,16 @@ // LCD / Controller // #if IS_RRD_SC - #define BEEPER_PIN EXP1_10_PIN - #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN - #define BTN_EN1 EXP2_06_PIN - #define BTN_EN2 EXP2_08_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN + #define BTN_ENC EXP1_02_PIN #endif // diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index 29aff20ffd..f59c6718d5 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -140,100 +140,100 @@ /** * ------ ------ - * (SD_MISO) PA6 |10 9 | PA5 (SD_SCK) (BEEPER) PC9 |10 9 | PC12 (BTN_ENC) - * (BTN_EN1) PC10 | 8 7 | PA4 (SD_SS) (LCD_EN) PB15 | 8 7 | PB12 (LCD_RS) - * (BTN_EN2) PC11 6 5 | PA7 (SD_MOSI) (LCD_D4) PB13 6 5 | PB14 (LCD_D5) - * (SD_DETECT) PC3 | 4 3 | RESET (LCD_D6) PB6 | 4 3 | PB7 (LCD_D7) - * GND | 2 1 | 5V GND | 2 1 | 5V + * (SD_MISO) PA6 | 1 2 | PA5 (SD_SCK) (BEEPER) PC9 | 1 2 | PC12 (BTN_ENC) + * (BTN_EN1) PC10 | 3 4 | PA4 (SD_SS) (LCD_EN) PB15 | 3 4 | PB12 (LCD_RS) + * (BTN_EN2) PC11 5 6 | PA7 (SD_MOSI) (LCD_D4) PB13 5 6 | PB14 (LCD_D5) + * (SD_DETECT) PC3 | 7 8 | RESET (LCD_D6) PB6 | 7 8 | PB7 (LCD_D7) + * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ * EXP2 EXP1 */ /** * ------ - * 5V |10 9 | GND - * (LCD_EN/MOSI) PB15 | 8 7 | PB12 (LCD_RS) - * (LCD_D4/SCK) PB13 6 5 | PC11 (BTN_EN2) - * (LCD_D5/MISO) PB14 | 4 3 | PC10 (BTN_EN1) - * (BTN_ENC) PC12 | 2 1 | PC9 (BEEPER) + * 5V | 1 2 | GND + * (LCD_EN/MOSI) PB15 | 3 4 | PB12 (LCD_RS) + * (LCD_D4/SCK) PB13 5 6 | PC11 (BTN_EN2) + * (LCD_D5/MISO) PB14 | 7 8 | PC10 (BTN_EN1) + * (BTN_ENC) PC12 | 9 10 | PC9 (BEEPER) * ------ * EXP3 */ -#define EXP1_03_PIN PB7 -#define EXP1_04_PIN PB6 -#define EXP1_05_PIN PB14 -#define EXP1_06_PIN PB13 -#define EXP1_07_PIN PB12 -#define EXP1_08_PIN PB15 -#define EXP1_09_PIN PC12 -#define EXP1_10_PIN PC9 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PC3 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PC11 -#define EXP2_07_PIN PA4 -#define EXP2_08_PIN PC10 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PB7 +#define EXP1_07_PIN PB6 +#define EXP1_06_PIN PB14 +#define EXP1_05_PIN PB13 +#define EXP1_04_PIN PB12 +#define EXP1_03_PIN PB15 +#define EXP1_02_PIN PC12 +#define EXP1_01_PIN PC9 + +#define EXP2_08_PIN -1 +#define EXP2_07_PIN PC3 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PC11 +#define EXP2_04_PIN PA4 +#define EXP2_03_PIN PC10 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 #if HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #else - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_06_PIN - #define BTN_EN2 EXP2_08_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif // !FYSETC_MINI_12864 #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -253,7 +253,7 @@ #endif #if ENABLED(TOUCH_UI_FTDI_EVE) - #define BEEPER_PIN EXP1_10_PIN - #define CLCD_MOD_RESET EXP2_08_PIN - #define CLCD_SPI_CS EXP2_06_PIN + #define BEEPER_PIN EXP1_01_PIN + #define CLCD_MOD_RESET EXP2_03_PIN + #define CLCD_SPI_CS EXP2_05_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 3ed18f9abc..e770140dbb 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -199,117 +199,117 @@ /** * ------ ------ - * PC9 |10 9 | PA8 PA6 |10 9 | PA5 - * PC11 | 8 7 | PD2 PC6 | 8 7 | PA4 - * PC10 6 5 | PC12 PC7 6 5 | PA7 - * PD0 | 4 3 | PD1 PB10 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | 5V + * PC9 | 1 2 | PA8 PA6 | 1 2 | PA5 + * PC11 | 3 4 | PD2 PC6 | 3 4 | PA4 + * PC10 5 6 | PC12 PC7 5 6 | PA7 + * PD0 | 7 8 | PD1 PB10 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PD1 -#define EXP1_04_PIN PD0 -#define EXP1_05_PIN PC12 -#define EXP1_06_PIN PC10 -#define EXP1_07_PIN PD2 -#define EXP1_08_PIN PC11 -#define EXP1_09_PIN PA8 -#define EXP1_10_PIN PC9 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN PB10 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PC7 -#define EXP2_07_PIN PA4 -#define EXP2_08_PIN PC6 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PD1 +#define EXP1_07_PIN PD0 +#define EXP1_06_PIN PC12 +#define EXP1_05_PIN PC10 +#define EXP1_04_PIN PD2 +#define EXP1_03_PIN PC11 +#define EXP1_02_PIN PA8 +#define EXP1_01_PIN PC9 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN PB10 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PC7 +#define EXP2_04_PIN PA4 +#define EXP2_03_PIN PC6 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 // // SPI / SD Card // -#define SD_SCK_PIN EXP2_09_PIN -#define SD_MISO_PIN EXP2_10_PIN -#define SD_MOSI_PIN EXP2_05_PIN +#define SD_SCK_PIN EXP2_02_PIN +#define SD_MISO_PIN EXP2_01_PIN +#define SD_MOSI_PIN EXP2_06_PIN -#define SDSS EXP2_07_PIN -#define SD_DETECT_PIN EXP2_04_PIN +#define SDSS EXP2_04_PIN +#define SD_DETECT_PIN EXP2_07_PIN // // LCD / Controller // #if ENABLED(FYSETC_242_OLED_12864) - #define BTN_EN1 EXP1_10_PIN - #define BTN_EN2 EXP1_03_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP1_01_PIN + #define BTN_EN2 EXP1_08_PIN + #define BTN_ENC EXP1_02_PIN - #define BEEPER_PIN EXP2_08_PIN + #define BEEPER_PIN EXP2_03_PIN - #define LCD_PINS_DC EXP1_05_PIN - #define LCD_PINS_RS EXP2_06_PIN // LCD_RST - #define DOGLCD_CS EXP1_07_PIN - #define DOGLCD_MOSI EXP1_06_PIN - #define DOGLCD_SCK EXP1_08_PIN + #define LCD_PINS_DC EXP1_06_PIN + #define LCD_PINS_RS EXP2_05_PIN // LCD_RST + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_MOSI EXP1_05_PIN + #define DOGLCD_SCK EXP1_03_PIN #define DOGLCD_A0 LCD_PINS_DC #define FORCE_SOFT_SPI #define KILL_PIN -1 // NC - #define NEOPIXEL_PIN EXP1_04_PIN + #define NEOPIXEL_PIN EXP1_07_PIN #elif HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #else - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_SDSS EXP2_07_PIN + #define LCD_SDSS EXP2_04_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) // See https://wiki.fysetc.com/Mini12864_Panel - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN #if ENABLED(FYSETC_GENERIC_12864_1_1) - #define LCD_BACKLIGHT_PIN EXP1_04_PIN + #define LCD_BACKLIGHT_PIN EXP1_07_PIN #endif - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h index cc02ac3097..676333b89c 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h @@ -213,31 +213,31 @@ /** * ------ ------ - * (BEEPER) PB2 |10 9 | PE10 (BTN_ENC) (SPI1 MISO) PA6 |10 9 | PA5 (SPI1 SCK) - * (LCD_EN) PE11 | 8 7 | PD10 (LCD_RS) (BTN_EN1) PE9 | 8 7 | PA4 (SPI1 CS) - * (LCD_D4) PD9 6 5 | PD8 (LCD_D5) (BTN_EN2) PE8 6 5 | PA7 (SPI1 MOSI) - * (LCD_D6) PE15 | 4 3 | PE7 (LCD_D7) (SPI1_RS) PB11 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | 3.3V + * (BEEPER) PB2 | 1 2 | PE10 (BTN_ENC) (SPI1 MISO) PA6 | 1 2 | PA5 (SPI1 SCK) + * (LCD_EN) PE11 | 3 4 | PD10 (LCD_RS) (BTN_EN1) PE9 | 3 4 | PA4 (SPI1 CS) + * (LCD_D4) PD9 5 6 | PD8 (LCD_D5) (BTN_EN2) PE8 5 6 | PA7 (SPI1 MOSI) + * (LCD_D6) PE15 | 7 8 | PE7 (LCD_D7) (SPI1_RS) PB11 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 3.3V * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PE7 -#define EXP1_04_PIN PE15 -#define EXP1_05_PIN PD8 -#define EXP1_06_PIN PD9 -#define EXP1_07_PIN PD10 -#define EXP1_08_PIN PE11 -#define EXP1_09_PIN PE10 -#define EXP1_10_PIN PB2 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN PB11 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PE8 -#define EXP2_07_PIN PA4 -#define EXP2_08_PIN PE9 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PE7 +#define EXP1_07_PIN PE15 +#define EXP1_06_PIN PD8 +#define EXP1_05_PIN PD9 +#define EXP1_04_PIN PD10 +#define EXP1_03_PIN PE11 +#define EXP1_02_PIN PE10 +#define EXP1_01_PIN PB2 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN PB11 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PE8 +#define EXP2_04_PIN PA4 +#define EXP2_03_PIN PE9 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 #if ENABLED(SDSUPPORT) #ifndef SDCARD_CONNECTION @@ -253,25 +253,25 @@ #define SD_DETECT_PIN PC4 // SD_DETECT_PIN doesn't work with NO_SD_HOST_DRIVE disabled #elif SD_CONNECTION_IS(LCD) #define ENABLE_SPI1 - #define SDSS EXP2_07_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SDSS EXP2_04_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif #endif #if EITHER(TFT_COLOR_UI, TFT_CLASSIC_UI) - #define TFT_CS_PIN EXP1_04_PIN - #define TFT_SCK_PIN EXP2_09_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_MOSI_PIN EXP2_05_PIN - #define TFT_DC_PIN EXP1_03_PIN + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + #define TFT_DC_PIN EXP1_08_PIN #define TFT_A0_PIN TFT_DC_PIN - #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_RESET_PIN EXP1_04_PIN - #define LCD_BACKLIGHT_PIN EXP1_08_PIN + #define LCD_BACKLIGHT_PIN EXP1_03_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI @@ -284,10 +284,10 @@ #define TFT_HEIGHT 320 #endif - #define TOUCH_CS_PIN EXP1_06_PIN // SPI1_NSS - #define TOUCH_SCK_PIN EXP2_09_PIN // SPI1_SCK - #define TOUCH_MISO_PIN EXP2_10_PIN // SPI1_MISO - #define TOUCH_MOSI_PIN EXP2_05_PIN // SPI1_MOSI + #define TOUCH_CS_PIN EXP1_05_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_02_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_01_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_06_PIN // SPI1_MOSI #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI @@ -312,8 +312,8 @@ #elif HAS_WIRED_LCD - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN #define LCD_BACKLIGHT_PIN -1 // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) @@ -321,23 +321,23 @@ #define ENABLE_SPI1 #define FORCE_SOFT_SPI - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - #define DOGLCD_SCK EXP2_09_PIN - #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN //#define LCD_BACKLIGHT_PIN -1 //#define LCD_RESET_PIN -1 #elif ENABLED(FYSETC_MINI_12864_2_1) - #define LCD_PINS_DC EXP1_07_PIN - #define DOGLCD_CS EXP1_08_PIN + #define LCD_PINS_DC EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN #define DOGLCD_A0 LCD_PINS_DC #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN - #define NEOPIXEL_PIN EXP1_05_PIN - #define DOGLCD_MOSI EXP2_05_PIN - #define DOGLCD_SCK EXP2_09_PIN + #define LCD_RESET_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN + #define DOGLCD_MOSI EXP2_06_PIN + #define DOGLCD_SCK EXP2_02_PIN #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif @@ -345,11 +345,11 @@ #else - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #endif #define BOARD_ST7920_DELAY_1 96 @@ -361,8 +361,8 @@ #endif // HAS_WIRED_LCD #if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, HAS_WIRED_LCD) - #define BEEPER_PIN EXP1_10_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h index 989010e47f..011d56dfe7 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h @@ -236,58 +236,58 @@ /** * ------ ------ - * (BEEPER) PC5 |10 9 | PE13 (BTN_ENC) (SPI1 MISO) PA6 |10 9 | PA5 (SPI1 SCK) - * (LCD_EN) PD13 | 8 7 | PC6 (LCD_RS) (BTN_EN1) PE8 | 8 7 | PE10 (SPI1 CS) - * (LCD_D4) PE14 6 5 | PE15 (LCD_D5) (BTN_EN2) PE11 6 5 | PA7 (SPI1 MOSI) - * (LCD_D6) PD11 | 4 3 | PD10 (LCD_D7) (SPI1_RS) PE12 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | 3.3V + * (BEEPER) PC5 | 1 2 | PE13 (BTN_ENC) (SPI1 MISO) PA6 | 1 2 | PA5 (SPI1 SCK) + * (LCD_EN) PD13 | 3 4 | PC6 (LCD_RS) (BTN_EN1) PE8 | 3 4 | PE10 (SPI1 CS) + * (LCD_D4) PE14 5 6 | PE15 (LCD_D5) (BTN_EN2) PE11 5 6 | PA7 (SPI1 MOSI) + * (LCD_D6) PD11 | 7 8 | PD10 (LCD_D7) (SPI1_RS) PE12 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 3.3V * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PD10 -#define EXP1_04_PIN PD11 -#define EXP1_05_PIN PE15 -#define EXP1_06_PIN PE14 -#define EXP1_07_PIN PC6 -#define EXP1_08_PIN PD13 -#define EXP1_09_PIN PE13 -#define EXP1_10_PIN PC5 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN PE12 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PE11 -#define EXP2_07_PIN PE10 -#define EXP2_08_PIN PE8 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PD10 +#define EXP1_07_PIN PD11 +#define EXP1_06_PIN PE15 +#define EXP1_05_PIN PE14 +#define EXP1_04_PIN PC6 +#define EXP1_03_PIN PD13 +#define EXP1_02_PIN PE13 +#define EXP1_01_PIN PC5 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN PE12 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PE11 +#define EXP2_04_PIN PE10 +#define EXP2_03_PIN PE8 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 // // SPI SD Card // #if SD_CONNECTION_IS(LCD) #define ENABLE_SPI1 - #define SDSS EXP2_07_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SDSS EXP2_04_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif // // LCD / Controller // #if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) - #define TFT_CS_PIN EXP1_04_PIN - #define TFT_SCK_PIN EXP2_09_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_MOSI_PIN EXP2_05_PIN - #define TFT_DC_PIN EXP1_03_PIN + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + #define TFT_DC_PIN EXP1_08_PIN #define TFT_A0_PIN TFT_DC_PIN - #define TFT_RESET_PIN EXP1_07_PIN + #define TFT_RESET_PIN EXP1_04_PIN - #define LCD_BACKLIGHT_PIN EXP1_08_PIN + #define LCD_BACKLIGHT_PIN EXP1_03_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI @@ -300,10 +300,10 @@ #define TFT_HEIGHT 320 #endif - #define TOUCH_CS_PIN EXP1_06_PIN // SPI1_NSS - #define TOUCH_SCK_PIN EXP2_09_PIN // SPI1_SCK - #define TOUCH_MISO_PIN EXP2_10_PIN // SPI1_MISO - #define TOUCH_MOSI_PIN EXP2_05_PIN // SPI1_MOSI + #define TOUCH_CS_PIN EXP1_05_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_02_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_01_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_06_PIN // SPI1_MOSI #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI @@ -328,32 +328,32 @@ #elif HAS_WIRED_LCD - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN #define LCD_BACKLIGHT_PIN -1 // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) //#define LCD_BACKLIGHT_PIN -1 //#define LCD_RESET_PIN -1 - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - //#define DOGLCD_SCK EXP2_09_PIN - //#define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + //#define DOGLCD_SCK EXP2_02_PIN + //#define DOGLCD_MOSI EXP2_06_PIN // Required for MKS_MINI_12864 with this board //#define MKS_LCD12864B //#undef SHOW_BOOTSCREEN #elif ENABLED(FYSETC_MINI_12864_2_1) - #define LCD_PINS_DC EXP1_07_PIN - #define DOGLCD_CS EXP1_08_PIN + #define LCD_PINS_DC EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN #define DOGLCD_A0 LCD_PINS_DC #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN - #define NEOPIXEL_PIN EXP1_05_PIN - #define DOGLCD_MOSI EXP2_05_PIN - #define DOGLCD_SCK EXP2_09_PIN + #define LCD_RESET_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN + #define DOGLCD_MOSI EXP2_06_PIN + #define DOGLCD_SCK EXP2_02_PIN #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif @@ -361,11 +361,11 @@ #else // !MKS_MINI_12864 - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #endif #define BOARD_ST7920_DELAY_1 96 @@ -382,10 +382,10 @@ #endif #if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI, HAS_WIRED_LCD) - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #if DISABLED(USE_SPI_DMA_TC) - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 1627bb909b..9b50705a90 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -230,31 +230,31 @@ #endif /** ------ ------ - * (BEEPER) PC5 |10 9 | PE13 (BTN_ENC) (SPI1 MISO) PA6 |10 9 | PA5 (SPI1 SCK) - * (LCD_EN) PD13 | 8 7 | PC6 (LCD_RS) (BTN_EN1) PE8 | 8 7 | PE10 (SPI1 CS) - * (LCD_D4) PE14 6 5 | PE15 (LCD_D5) (BTN_EN2) PE11 6 5 | PA7 (SPI1 MOSI) - * (LCD_D6) PD11 | 4 3 | PD10 (LCD_D7) (SPI DET) PE12 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | 3.3V + * (BEEPER) PC5 | 1 2 | PE13 (BTN_ENC) (SPI1 MISO) PA6 | 1 2 | PA5 (SPI1 SCK) + * (LCD_EN) PD13 | 3 4 | PC6 (LCD_RS) (BTN_EN1) PE8 | 3 4 | PE10 (SPI1 CS) + * (LCD_D4) PE14 5 6 | PE15 (LCD_D5) (BTN_EN2) PE11 5 6 | PA7 (SPI1 MOSI) + * (LCD_D6) PD11 | 7 8 | PD10 (LCD_D7) (SPI DET) PE12 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 3.3V * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PD10 -#define EXP1_04_PIN PD11 -#define EXP1_05_PIN PE15 -#define EXP1_06_PIN PE14 -#define EXP1_07_PIN PC6 -#define EXP1_08_PIN PD13 -#define EXP1_09_PIN PE13 -#define EXP1_10_PIN PC5 - -#define EXP2_03_PIN -1 // RESET -#define EXP2_04_PIN PE12 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PE11 -#define EXP2_07_PIN PE10 -#define EXP2_08_PIN PE8 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PD10 +#define EXP1_07_PIN PD11 +#define EXP1_06_PIN PE15 +#define EXP1_05_PIN PE14 +#define EXP1_04_PIN PC6 +#define EXP1_03_PIN PD13 +#define EXP1_02_PIN PE13 +#define EXP1_01_PIN PC5 + +#define EXP2_08_PIN -1 // RESET +#define EXP2_07_PIN PE12 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PE11 +#define EXP2_04_PIN PE10 +#define EXP2_03_PIN PE8 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 // // LCD SD @@ -262,11 +262,11 @@ /* #if SD_CONNECTION_IS(LCD) #define ENABLE_SPI1 - #define SDSS EXP2_07_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SDSS EXP2_04_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif */ @@ -300,15 +300,15 @@ #define TOUCH_ORIENTATION TOUCH_LANDSCAPE #endif - #define TFT_CS_PIN EXP1_04_PIN - #define TFT_SCK_PIN EXP2_09_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_MOSI_PIN EXP2_05_PIN - #define TFT_DC_PIN EXP1_03_PIN + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + #define TFT_DC_PIN EXP1_08_PIN #define TFT_A0_PIN TFT_DC_PIN - #define TFT_RESET_PIN EXP1_07_PIN - #define LCD_BACKLIGHT_PIN EXP1_08_PIN + #define TFT_RESET_PIN EXP1_04_PIN + #define LCD_BACKLIGHT_PIN EXP1_03_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI @@ -321,15 +321,15 @@ #define TFT_HEIGHT 320 #endif - #define TOUCH_CS_PIN EXP1_06_PIN // SPI1_NSS - #define TOUCH_SCK_PIN EXP2_09_PIN // SPI1_SCK - #define TOUCH_MISO_PIN EXP2_10_PIN // SPI1_MISO - #define TOUCH_MOSI_PIN EXP2_05_PIN // SPI1_MOSI + #define TOUCH_CS_PIN EXP1_05_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_02_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_01_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_06_PIN // SPI1_MOSI - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI @@ -339,22 +339,22 @@ #elif HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #define LCD_BACKLIGHT_PIN -1 // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) //#define LCD_BACKLIGHT_PIN -1 //#define LCD_RESET_PIN -1 - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - //#define DOGLCD_SCK EXP2_09_PIN - //#define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + //#define DOGLCD_SCK EXP2_02_PIN + //#define DOGLCD_MOSI EXP2_06_PIN // Required for MKS_MINI_12864 with this board //#define MKS_LCD12864B @@ -362,11 +362,11 @@ #else // !MKS_MINI_12864 - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(ULTIPANEL) - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #endif #define BOARD_ST7920_DELAY_1 96 diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h index 1439e6de65..65a396ad3f 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h @@ -199,11 +199,11 @@ /** * ------ - * PA14 |10 9 | PB0 - * PC4 | 8 7 | -- - * PC5 | 6 5 PB13 - * PB12 | 4 3 | PB15 - * GND | 2 1 | 5V + * PA14 | 1 2 | PB0 + * PC4 | 3 4 | -- + * PC5 | 5 6 PB13 + * PB12 | 7 8 | PB15 + * GND | 9 10 | 5V * ------ * EXP1 * @@ -213,30 +213,30 @@ * A remote SD card is currently not supported because the pins routed to the EXP2 * connector are shared with the onboard SD card. */ -#define EXP1_03_PIN PB15 -#define EXP1_04_PIN PB12 -#define EXP1_05_PIN PB13 -#define EXP1_06_PIN PC5 -//#define EXP1_07_PIN -1 -#define EXP1_08_PIN PC4 -#define EXP1_09_PIN PB0 -#define EXP1_10_PIN PA14 +#define EXP1_08_PIN PB15 +#define EXP1_07_PIN PB12 +#define EXP1_06_PIN PB13 +#define EXP1_05_PIN PC5 +//#define EXP1_04_PIN -1 +#define EXP1_03_PIN PC4 +#define EXP1_02_PIN PB0 +#define EXP1_01_PIN PA14 #if ENABLED(CR10_STOCKDISPLAY) /** ------ - * BEEPER |10 9 | ENC - * EN1 | 8 7 | RESET - * EN2 | 6 5 LCD_D4 - * LCD_RS | 4 3 | LCD_EN - * GND | 2 1 | 5V + * BEEPER | 1 2 | ENC + * EN1 | 3 4 | RESET + * EN2 | 5 6 LCD_D4 + * LCD_RS | 7 8 | LCD_EN + * GND | 9 10 | 5V * ------ */ #ifdef DISABLE_JTAGSWD - #define BEEPER_PIN EXP1_10_PIN // Not connected in dev board + #define BEEPER_PIN EXP1_01_PIN // Not connected in dev board #endif - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN //#define KILL_PIN -1 #define BOARD_ST7920_DELAY_1 600 @@ -245,17 +245,17 @@ #elif ENABLED(MKS_MINI_12864) /** ------ - * SCK |10 9 | ENC - * EN1 | 8 7 | -- - * EN2 | 6 5 A0 - * CS | 4 3 | MOSI - * GND | 2 1 | 5V + * SCK | 1 2 | ENC + * EN1 | 3 4 | -- + * EN2 | 5 6 A0 + * CS | 7 8 | MOSI + * GND | 9 10 | 5V * ------ */ - #define DOGLCD_CS EXP1_04_PIN - #define DOGLCD_A0 EXP1_05_PIN - #define DOGLCD_SCK EXP1_10_PIN - #define DOGLCD_MOSI EXP1_03_PIN + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_A0 EXP1_06_PIN + #define DOGLCD_SCK EXP1_01_PIN + #define DOGLCD_MOSI EXP1_08_PIN #define LCD_CONTRAST_INIT 160 #define LCD_CONTRAST_MIN 120 #define LCD_CONTRAST_MAX 180 @@ -269,7 +269,7 @@ #endif #if EITHER(CR10_STOCKDISPLAY, MKS_MINI_12864) - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BTN_ENC EXP1_02_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index 66caec588f..e395ee62dd 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -161,37 +161,37 @@ #define POWER_LOSS_PIN PA4 // ?? Power loss / nAC_FAULT #if ENABLED(SDSUPPORT) - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN #define SD_SS_PIN PB15 // USD_CS -> CS for onboard SD #endif /** * ------ ------ - * PC9 |10 9 | PB12 ? |10 9 | ? - * PD7 | 8 7 | PC12 PD6 | 8 7 | ? - * PD1 | 6 5 PD2 PD0 | 6 5 ? - * PD3 | 4 3 | PD4 PB7 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | 3.3V + * PC9 | 1 2 | PB12 ? | 1 2 | ? + * PD7 | 3 4 | PC12 PD6 | 3 4 | ? + * PD1 | 5 6 PD2 PD0 | 5 6 ? + * PD3 | 7 8 | PD4 PB7 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 3.3V * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PD4 -#define EXP1_04_PIN PD3 -#define EXP1_05_PIN PD2 -#define EXP1_06_PIN PD1 -#define EXP1_07_PIN PC12 -#define EXP1_08_PIN PD7 -#define EXP1_09_PIN PB12 -#define EXP1_10_PIN PC9 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PB7 -//#define EXP2_05_PIN ? -#define EXP2_06_PIN PD0 -//#define EXP2_07_PIN ? -#define EXP2_08_PIN PD6 -//#define EXP2_09_PIN ? -//#define EXP2_10_PIN ? +#define EXP1_08_PIN PD4 +#define EXP1_07_PIN PD3 +#define EXP1_06_PIN PD2 +#define EXP1_05_PIN PD1 +#define EXP1_04_PIN PC12 +#define EXP1_03_PIN PD7 +#define EXP1_02_PIN PB12 +#define EXP1_01_PIN PC9 + +#define EXP2_08_PIN -1 +#define EXP2_07_PIN PB7 +//#define EXP2_06_PIN ? +#define EXP2_05_PIN PD0 +//#define EXP2_04_PIN ? +#define EXP2_03_PIN PD6 +//#define EXP2_02_PIN ? +//#define EXP2_01_PIN ? // // LCD / Controller @@ -202,19 +202,19 @@ #define SDSS PB6 // CS for SD card in LCD #endif - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_D4 EXP1_06_PIN - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #endif diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h index 769f10c8a4..f35bdb227f 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h @@ -145,25 +145,25 @@ /** * SKR Mini E3 V3.0 * ------ - * (BEEPER) PB5 |10 9 | PA15 (BTN_ENC) - * (BTN_EN1) PA9 | 8 7 | RESET - * (BTN_EN2) PA10 6 5 | PB9 (LCD_D4) - * (LCD_RS) PB8 | 4 3 | PD6 (LCD_EN) - * GND | 2 1 | 5V + * (BEEPER) PB5 | 1 2 | PA15 (BTN_ENC) + * (BTN_EN1) PA9 | 3 4 | RESET + * (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) + * (LCD_RS) PB8 | 7 8 | PD6 (LCD_EN) + * GND | 9 10 | 5V * ------ * EXP1 */ -#define EXP1_09_PIN PA15 -#define EXP1_03_PIN PD6 +#define EXP1_02_PIN PA15 +#define EXP1_08_PIN PD6 #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI /** * ------ ------ ------ - * (ENT) |10 9 | (BEEP) |10 9 | |10 9 | - * (RX) | 8 7 | (RX) | 8 7 | (TX) RX | 8 7 | TX - * (TX) 6 5 | (ENT) 6 5 | (BEEP) ENT | 6 5 | BEEP - * (B) | 4 3 | (A) (B) | 4 3 | (A) B | 4 3 | A - * GND | 2 1 | (VCC) GND | 2 1 | VCC GND | 2 1 | VCC + * (ENT) | 1 2 | (BEEP) | 1 2 | | 1 2 | + * (RX) | 3 4 | (RX) | 3 4 | (TX) RX | 3 4 | TX + * (TX) 5 6 | (ENT) 5 6 | (BEEP) ENT | 5 6 | BEEP + * (B) | 7 8 | (A) (B) | 7 8 | (A) B | 7 8 | A + * GND | 9 10 | (VCC) GND | 9 10 | VCC GND | 9 10 | VCC * ------ ------ ------ * EXP1 DWIN DWIN (plug) * @@ -174,8 +174,8 @@ #error "CAUTION! DWIN_CREALITY_LCD requires a custom cable, see diagram above this line. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" #endif - #define BEEPER_PIN EXP1_09_PIN - #define BTN_EN1 EXP1_03_PIN + #define BEEPER_PIN EXP1_02_PIN + #define BTN_EN1 EXP1_08_PIN #define BTN_EN2 PB8 #define BTN_ENC PB5 @@ -184,13 +184,13 @@ #if ENABLED(CR10_STOCKDISPLAY) #define BEEPER_PIN PB5 - #define BTN_ENC EXP1_09_PIN + #define BTN_ENC EXP1_02_PIN #define BTN_EN1 PA9 #define BTN_EN2 PA10 #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN #define LCD_PINS_D4 PB9 #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -200,7 +200,7 @@ #endif #define LCD_PINS_RS PB9 - #define LCD_PINS_ENABLE EXP1_09_PIN + #define LCD_PINS_ENABLE EXP1_02_PIN #define LCD_PINS_D4 PB8 #define LCD_PINS_D5 PA10 #define LCD_PINS_D6 PA9 @@ -209,14 +209,14 @@ #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - #define BTN_ENC EXP1_09_PIN + #define BTN_ENC EXP1_02_PIN #define BTN_EN1 PA9 #define BTN_EN2 PA10 #define DOGLCD_CS PB8 #define DOGLCD_A0 PB9 #define DOGLCD_SCK PB5 - #define DOGLCD_MOSI EXP1_03_PIN + #define DOGLCD_MOSI EXP1_08_PIN #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 @@ -234,11 +234,11 @@ * * Board Display * ------ ------ - * (BEEPER) PB6 |10 9 | PB5 (SD_DET) 5V |10 9 | GND - * RESET | 8 7 | PA9 (MOD_RESET) -- | 8 7 | (SD_DET) - * PB9 6 5 | PA10 (SD_CS) (MOSI) | 6 5 | -- - * PB7 | 4 3 | PB8 (LCD_CS) (SD_CS) | 4 3 | (LCD_CS) - * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * (BEEPER) PB6 | 1 2 | PB5 (SD_DET) 5V | 1 2 | GND + * RESET | 3 4 | PA9 (MOD_RESET) -- | 3 4 | (SD_DET) + * PB9 5 6 | PA10 (SD_CS) (MOSI) | 5 6 | -- + * PB7 | 7 8 | PB8 (LCD_CS) (SD_CS) | 7 8 | (LCD_CS) + * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) * ------ ------ * EXP1 EXP1 * @@ -272,20 +272,20 @@ * * Board Display * ------ ------ - * (EN2) PB5 |10 9 | PA15(BTN_ENC) 5V |10 9 | GND - * (LCD_CS) PA9 | 8 7 | RST (RESET) -- | 8 7 | -- + * (EN2) PB5 | 1 2 | PA15(BTN_ENC) 5V | 1 2 | GND + * (LCD_CS) PA9 | 3 4 | RST (RESET) -- | 3 4 | -- * (LCD_A0) PA10 |#6 5 | PB9 (EN1) (DIN) | 6 5#| (RESET) - * (LCD_SCK)PB8 | 4 3 | PD6 (MOSI) (LCD_A0) | 4 3 | (LCD_CS) - * GND | 2 1 | 5V (BTN_ENC) | 2 1 | -- + * (LCD_SCK)PB8 | 7 8 | PD6 (MOSI) (LCD_A0) | 7 8 | (LCD_CS) + * GND | 9 10 | 5V (BTN_ENC) | 9 10 | -- * ------ ------ * EXP1 EXP1 * * ------ - * -- |10 9 | -- - * --- (RESET) | 8 7 | -- + * -- | 1 2 | -- + * --- (RESET) | 3 4 | -- * | 3 | (MOSI) | 6 5#| (EN2) - * | 2 | (DIN) -- | 4 3 | (EN1) - * | 1 | (LCD_SCK)| 2 1 | -- + * | 2 | (DIN) -- | 7 8 | (EN1) + * | 1 | (LCD_SCK)| 9 10 | -- * --- ------ * Neopixel EXP2 * @@ -294,7 +294,7 @@ * Check twice index position!!! (marked as # here) * On BTT boards pins from IDC10 connector are numbered in unusual order. */ - #define BTN_ENC EXP1_09_PIN + #define BTN_ENC EXP1_02_PIN #define BTN_EN1 PB9 #define BTN_EN2 PB5 #define BEEPER_PIN -1 @@ -324,11 +324,11 @@ * * Board Display * ------ ------ - * (SD_DET) PB5 |10 9 | PB6 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PA9 | 8 7 | RESET (RESET) | 8 7 | (SD_DET) - * (SD_CS) PA10 6 5 | PB9 (FREE) (MOSI) | 6 5 | (LCD_CS) - * (LCD_CS) PB8 | 4 3 | PB7 (FREE) (SD_CS) | 4 3 | (MOD_RESET) - * 5V | 2 1 | GND (SCK) | 2 1 | (MISO) + * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V | 1 2 | GND + * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 3 4 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (FREE) (MOSI) | 5 6 | (LCD_CS) + * (LCD_CS) PB8 | 7 8 | PB7 (FREE) (SD_CS) | 7 8 | (MOD_RESET) + * 5V | 9 10 | GND (SCK) | 9 10 | (MISO) * ------ ------ * EXP1 EXP1 * @@ -350,7 +350,7 @@ #define CLCD_SPI_BUS 1 // SPI1 connector - #define BEEPER_PIN EXP1_09_PIN + #define BEEPER_PIN EXP1_02_PIN #define CLCD_MOD_RESET PA9 #define CLCD_SPI_CS PB8 diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h index 02e195a185..f2f1fa255a 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h @@ -326,43 +326,43 @@ /** * ------ ------ - * (BEEPER) PC5 |10 9 | PB0 (BTN_ENC) (MISO) PA6 |10 9 | PA5 (SCK) - * (LCD_EN) PB1 | 8 7 | PE8 (LCD_RS) (BTN_EN1) PE7 | 8 7 | PA4 (SD_SS) - * (LCD_D4) PE9 | 6 5 PE10 (LCD_D5) (BTN_EN2) PB2 | 6 5 PA7 (MOSI) - * (LCD_D6) PE11 | 4 3 | PE12 (LCD_D7) (SD_DETECT) PC4 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | -- + * (BEEPER) PC5 | 1 2 | PB0 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) + * (LCD_EN) PB1 | 3 4 | PE8 (LCD_RS) (BTN_EN1) PE7 | 3 4 | PA4 (SD_SS) + * (LCD_D4) PE9 | 5 6 PE10 (LCD_D5) (BTN_EN2) PB2 | 5 6 PA7 (MOSI) + * (LCD_D6) PE11 | 7 8 | PE12 (LCD_D7) (SD_DETECT) PC4 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- * ------ ------ * EXP1 EXP2 */ -#define EXP1_03_PIN PE12 -#define EXP1_04_PIN PE11 -#define EXP1_05_PIN PE10 -#define EXP1_06_PIN PE9 -#define EXP1_07_PIN PE8 -#define EXP1_08_PIN PB1 -#define EXP1_09_PIN PB0 -#define EXP1_10_PIN PC5 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PC4 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PB2 -#define EXP2_07_PIN PA4 -#define EXP2_08_PIN PE7 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 +#define EXP1_08_PIN PE12 +#define EXP1_07_PIN PE11 +#define EXP1_06_PIN PE10 +#define EXP1_05_PIN PE9 +#define EXP1_04_PIN PE8 +#define EXP1_03_PIN PB1 +#define EXP1_02_PIN PB0 +#define EXP1_01_PIN PC5 + +#define EXP2_08_PIN -1 +#define EXP2_07_PIN PC4 +#define EXP2_06_PIN PA7 +#define EXP2_05_PIN PB2 +#define EXP2_04_PIN PA4 +#define EXP2_03_PIN PE7 +#define EXP2_02_PIN PA5 +#define EXP2_01_PIN PA6 // // Onboard SD card // Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // #if SD_CONNECTION_IS(LCD) - #define SDSS EXP2_07_PIN + #define SDSS EXP2_04_PIN #define SD_SS_PIN SDSS - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN - #define SD_DETECT_PIN EXP2_04_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_DETECT_PIN EXP2_07_PIN #elif SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT #define SDIO_CLOCK 24000000 // 24MHz @@ -384,46 +384,46 @@ */ // M1 on Driver Expansion Module - #define E2_STEP_PIN EXP2_05_PIN - #define E2_DIR_PIN EXP2_06_PIN - #define E2_ENABLE_PIN EXP2_04_PIN + #define E2_STEP_PIN EXP2_06_PIN + #define E2_DIR_PIN EXP2_05_PIN + #define E2_ENABLE_PIN EXP2_07_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E2_DIAG_PIN EXP1_06_PIN - #define E2_CS_PIN EXP1_05_PIN + #define E2_DIAG_PIN EXP1_05_PIN + #define E2_CS_PIN EXP1_06_PIN #if HAS_TMC_UART - #define E2_SERIAL_TX_PIN EXP1_05_PIN - #define E2_SERIAL_RX_PIN EXP1_05_PIN + #define E2_SERIAL_TX_PIN EXP1_06_PIN + #define E2_SERIAL_RX_PIN EXP1_06_PIN #endif #endif // M2 on Driver Expansion Module - #define E3_STEP_PIN EXP2_08_PIN - #define E3_DIR_PIN EXP2_07_PIN + #define E3_STEP_PIN EXP2_03_PIN + #define E3_DIR_PIN EXP2_04_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E3_ENABLE_PIN EXP1_03_PIN - #define E3_DIAG_PIN EXP1_08_PIN - #define E3_CS_PIN EXP1_07_PIN + #define E3_ENABLE_PIN EXP1_08_PIN + #define E3_DIAG_PIN EXP1_03_PIN + #define E3_CS_PIN EXP1_04_PIN #if HAS_TMC_UART - #define E3_SERIAL_TX_PIN EXP1_07_PIN - #define E3_SERIAL_RX_PIN EXP1_07_PIN + #define E3_SERIAL_TX_PIN EXP1_04_PIN + #define E3_SERIAL_RX_PIN EXP1_04_PIN #endif #else - #define E3_ENABLE_PIN EXP2_04_PIN + #define E3_ENABLE_PIN EXP2_07_PIN #endif // M3 on Driver Expansion Module - #define E4_STEP_PIN EXP2_10_PIN - #define E4_DIR_PIN EXP2_09_PIN + #define E4_STEP_PIN EXP2_01_PIN + #define E4_DIR_PIN EXP2_02_PIN #if !EXP_MOT_USE_EXP2_ONLY - #define E4_ENABLE_PIN EXP1_04_PIN - #define E4_DIAG_PIN EXP1_10_PIN - #define E4_CS_PIN EXP1_09_PIN + #define E4_ENABLE_PIN EXP1_07_PIN + #define E4_DIAG_PIN EXP1_01_PIN + #define E4_CS_PIN EXP1_02_PIN #if HAS_TMC_UART - #define E4_SERIAL_TX_PIN EXP1_09_PIN - #define E4_SERIAL_RX_PIN EXP1_09_PIN + #define E4_SERIAL_TX_PIN EXP1_02_PIN + #define E4_SERIAL_RX_PIN EXP1_02_PIN #endif #else - #define E4_ENABLE_PIN EXP2_04_PIN + #define E4_ENABLE_PIN EXP2_07_PIN #endif #endif // BTT_MOTOR_EXPANSION @@ -434,65 +434,65 @@ #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif #elif HAS_WIRED_LCD - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_RS EXP1_07_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_CS EXP1_05_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #else - #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif // !FYSETC_MINI_12864 #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -521,21 +521,21 @@ // // e.g., BTT_TFT35_SPI_V1_0 (480x320, 3.5", SPI Stock Display with Rotary Encoder in BIQU B1 SE) // - #define TFT_CS_PIN EXP2_07_PIN - #define TFT_A0_PIN EXP2_04_PIN - #define TFT_SCK_PIN EXP2_09_PIN - #define TFT_MISO_PIN EXP2_10_PIN - #define TFT_MOSI_PIN EXP2_05_PIN - - #define TOUCH_INT_PIN EXP1_04_PIN - #define TOUCH_MISO_PIN EXP1_05_PIN - #define TOUCH_MOSI_PIN EXP1_08_PIN - #define TOUCH_SCK_PIN EXP1_06_PIN - #define TOUCH_CS_PIN EXP1_07_PIN - - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - #define BTN_ENC EXP1_09_PIN + #define TFT_CS_PIN EXP2_04_PIN + #define TFT_A0_PIN EXP2_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define TOUCH_INT_PIN EXP1_07_PIN + #define TOUCH_MISO_PIN EXP1_06_PIN + #define TOUCH_MOSI_PIN EXP1_03_PIN + #define TOUCH_SCK_PIN EXP1_05_PIN + #define TOUCH_CS_PIN EXP1_04_PIN + + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN #endif // From 915203f545f6d3114a5965a19125545f5592c42e Mon Sep 17 00:00:00 2001 From: tombrazier <68918209+tombrazier@users.noreply.github.com> Date: Mon, 18 Jul 2022 06:51:44 +0100 Subject: [PATCH 04/54] =?UTF-8?q?=F0=9F=A9=B9=20Arc/Planner=20optimization?= =?UTF-8?q?=20followup=20(#24509)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/motion/G2_G3.cpp | 10 ++++++---- Marlin/src/module/planner.cpp | 2 +- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index c45204c6f6..1a0a9c8ccc 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -294,11 +294,12 @@ void plan_arc( // An arc can always complete within limits from a speed which... // a) is <= any configured maximum speed, // b) does not require centripetal force greater than any configured maximum acceleration, - // c) allows the print head to stop in the remining length of the curve within all configured maximum accelerations. + // c) is <= nominal speed, + // d) allows the print head to stop in the remining length of the curve within all configured maximum accelerations. // The last has to be calculated every time through the loop. const float limiting_accel = _MIN(planner.settings.max_acceleration_mm_per_s2[axis_p], planner.settings.max_acceleration_mm_per_s2[axis_q]), limiting_speed = _MIN(planner.settings.max_feedrate_mm_s[axis_p], planner.settings.max_acceleration_mm_per_s2[axis_q]), - limiting_speed_sqr = _MIN(sq(limiting_speed), limiting_accel * radius); + limiting_speed_sqr = _MIN(sq(limiting_speed), limiting_accel * radius, sq(scaled_fr_mm_s)); float arc_mm_remaining = flat_mm; for (uint16_t i = 1; i < segments; i++) { // Iterate (segments-1) times @@ -357,12 +358,12 @@ void plan_arc( // calculate safe speed for stopping by the end of the arc arc_mm_remaining -= segment_mm; - - hints.curve_radius = i > 1 ? radius : 0; hints.safe_exit_speed_sqr = _MIN(limiting_speed_sqr, 2 * limiting_accel * arc_mm_remaining); if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, hints)) break; + + hints.curve_radius = radius; } } @@ -383,6 +384,7 @@ void plan_arc( #endif hints.curve_radius = 0; + hints.safe_exit_speed_sqr = 0.0f; planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, hints); #if ENABLED(AUTO_BED_LEVELING_UBL) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index de1351babf..b4455ca5ec 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -806,7 +806,7 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t float accelerate_steps_float = (nominal_rate_sq - sq(float(initial_rate))) * (0.5f / accel); accelerate_steps = CEIL(accelerate_steps_float); const float decelerate_steps_float = (nominal_rate_sq - sq(float(final_rate))) * (0.5f / accel); - decelerate_steps = decelerate_steps_float; + decelerate_steps = FLOOR(decelerate_steps_float); // Steps between acceleration and deceleration, if any plateau_steps -= accelerate_steps + decelerate_steps; From 97a73147fa47119d5600c28dd7bfc549a390e53f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 18 Jul 2022 19:52:47 -0500 Subject: [PATCH 05/54] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20manual=20move=20titl?= =?UTF-8?q?es=20(#24518)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_an.h | 1 + Marlin/src/lcd/language/language_bg.h | 1 + Marlin/src/lcd/language/language_ca.h | 1 + Marlin/src/lcd/language/language_cz.h | 1 + Marlin/src/lcd/language/language_da.h | 3 +++ Marlin/src/lcd/language/language_el.h | 1 + Marlin/src/lcd/language/language_el_gr.h | 1 + Marlin/src/lcd/language/language_es.h | 1 + Marlin/src/lcd/language/language_eu.h | 1 + Marlin/src/lcd/language/language_fi.h | 1 + Marlin/src/lcd/language/language_gl.h | 1 + Marlin/src/lcd/language/language_hr.h | 4 ++++ Marlin/src/lcd/language/language_jp_kana.h | 2 ++ Marlin/src/lcd/language/language_nl.h | 1 + Marlin/src/lcd/language/language_pl.h | 1 + Marlin/src/lcd/language/language_pt.h | 1 + Marlin/src/lcd/language/language_pt_br.h | 1 + Marlin/src/lcd/language/language_ro.h | 1 + Marlin/src/lcd/language/language_sv.h | 1 + Marlin/src/lcd/language/language_tr.h | 1 + Marlin/src/lcd/language/language_vi.h | 1 + Marlin/src/lcd/language/language_zh_CN.h | 1 + Marlin/src/lcd/language/language_zh_TW.h | 1 + Marlin/src/lcd/marlinui.h | 2 ++ Marlin/src/lcd/menu/menu.cpp | 2 +- Marlin/src/lcd/menu/menu.h | 2 -- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 2 +- Marlin/src/lcd/menu/menu_item.h | 2 -- Marlin/src/lcd/menu/menu_motion.cpp | 6 ++---- 29 files changed, 35 insertions(+), 10 deletions(-) diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 98f3d4ed97..37c90c34da 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -83,6 +83,7 @@ namespace Language_an { LSTR MSG_MOVE_X = _UxGT("Mover X"); LSTR MSG_MOVE_Y = _UxGT("Mover Y"); LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_N = _UxGT("Mover @"); LSTR MSG_MOVE_E = _UxGT("Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); LSTR MSG_MOVE_N_MM = _UxGT("Mover $mm"); diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 2596d62564..038df3eccb 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -72,6 +72,7 @@ namespace Language_bg { LSTR MSG_MOVE_X = _UxGT("Движение по X"); LSTR MSG_MOVE_Y = _UxGT("Движение по Y"); LSTR MSG_MOVE_Z = _UxGT("Движение по Z"); + LSTR MSG_MOVE_N = _UxGT("Движение по @"); LSTR MSG_MOVE_E = _UxGT("Екструдер"); LSTR MSG_MOVE_EN = _UxGT("Екструдер *"); LSTR MSG_MOVE_N_MM = _UxGT("Премести с $mm"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index fd46bcc28f..54b968ede2 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -83,6 +83,7 @@ namespace Language_ca { LSTR MSG_MOVE_X = _UxGT("Mou X"); LSTR MSG_MOVE_Y = _UxGT("Mou Y"); LSTR MSG_MOVE_Z = _UxGT("Mou Z"); + LSTR MSG_MOVE_N = _UxGT("Mou @"); LSTR MSG_MOVE_E = _UxGT("Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); LSTR MSG_MOVE_N_MM = _UxGT("Mou $mm"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 555fec1d20..9c5bafc96e 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -232,6 +232,7 @@ namespace Language_cz { LSTR MSG_MOVE_X = _UxGT("Posunout X"); LSTR MSG_MOVE_Y = _UxGT("Posunout Y"); LSTR MSG_MOVE_Z = _UxGT("Posunout Z"); + LSTR MSG_MOVE_N = _UxGT("Posunout @"); LSTR MSG_MOVE_E = _UxGT("Extrudér"); LSTR MSG_MOVE_EN = _UxGT("Extrudér *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index 05474744d0..b4afca9d99 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -74,6 +74,9 @@ namespace Language_da { LSTR MSG_MOVE_X = _UxGT("Flyt X"); LSTR MSG_MOVE_Y = _UxGT("Flyt Y"); LSTR MSG_MOVE_Z = _UxGT("Flyt Z"); + LSTR MSG_MOVE_N = _UxGT("Flyt @"); + LSTR MSG_MOVE_E = _UxGT("Flyt E"); + LSTR MSG_MOVE_EN = _UxGT("Flyt *"); LSTR MSG_MOVE_N_MM = _UxGT("Flyt $mm"); LSTR MSG_MOVE_01MM = _UxGT("Flyt 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Flyt 1mm"); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 47d6a5b2da..41b73ddc57 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -92,6 +92,7 @@ namespace Language_el { LSTR MSG_MOVE_X = _UxGT("Μετακίνηση X"); LSTR MSG_MOVE_Y = _UxGT("Μετακίνηση Y"); LSTR MSG_MOVE_Z = _UxGT("Μετακίνηση Z"); + LSTR MSG_MOVE_N = _UxGT("Μετακίνηση @"); LSTR MSG_MOVE_E = _UxGT("Εξωθητής"); LSTR MSG_MOVE_EN = _UxGT("Εξωθητής *"); LSTR MSG_MOVE_N_MM = _UxGT("Μετακίνηση %s μμ"); diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index bd2e7d595d..7306aab123 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -81,6 +81,7 @@ namespace Language_el_gr { LSTR MSG_MOVE_X = _UxGT("Μετακίνηση X"); LSTR MSG_MOVE_Y = _UxGT("Μετακίνηση Y"); LSTR MSG_MOVE_Z = _UxGT("Μετακίνηση Z"); + LSTR MSG_MOVE_N = _UxGT("Μετακίνηση @"); LSTR MSG_MOVE_E = _UxGT("Εξωθητήρας"); LSTR MSG_MOVE_EN = _UxGT("Εξωθητήρας *"); LSTR MSG_MOVE_N_MM = _UxGT("Μετακίνηση %s μμ"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 9cb86c5c32..5f88f8426d 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -226,6 +226,7 @@ namespace Language_es { LSTR MSG_MOVE_X = _UxGT("Mover X"); LSTR MSG_MOVE_Y = _UxGT("Mover Y"); LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_N = _UxGT("Mover @"); LSTR MSG_MOVE_E = _UxGT("Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend muy frio"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 5504d4da94..210fdbdc16 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -136,6 +136,7 @@ namespace Language_eu { LSTR MSG_MOVE_X = _UxGT("Mugitu X"); LSTR MSG_MOVE_Y = _UxGT("Mugitu Y"); LSTR MSG_MOVE_Z = _UxGT("Mugitu Z"); + LSTR MSG_MOVE_N = _UxGT("Mugitu @"); LSTR MSG_MOVE_E = _UxGT("Estrusorea"); LSTR MSG_MOVE_EN = _UxGT("Estrusorea *"); LSTR MSG_MOVE_N_MM = _UxGT("Mugitu $mm"); diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index 8fd53a79e3..ff1c23eee7 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -69,6 +69,7 @@ namespace Language_fi { LSTR MSG_MOVE_X = _UxGT("Liikuta X"); LSTR MSG_MOVE_Y = _UxGT("Liikuta Y"); LSTR MSG_MOVE_Z = _UxGT("Liikuta Z"); + LSTR MSG_MOVE_N = _UxGT("Liikuta @"); LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); LSTR MSG_MOVE_N_MM = _UxGT("Liikuta $mm"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 827130de6c..9ae64f0809 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -223,6 +223,7 @@ namespace Language_gl { LSTR MSG_MOVE_X = _UxGT("Mover X"); LSTR MSG_MOVE_Y = _UxGT("Mover Y"); LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_N = _UxGT("Mover @"); LSTR MSG_MOVE_E = _UxGT("Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Extrusor *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Bico moi frío"); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 10f11f616f..08ff6cc38c 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -78,6 +78,10 @@ namespace Language_hr { LSTR MSG_LEVEL_BED = _UxGT("Niveliraj bed"); LSTR MSG_MOVE_X = _UxGT("Miči X"); LSTR MSG_MOVE_Y = _UxGT("Miči Y"); + LSTR MSG_MOVE_Z = _UxGT("Miči Z"); + LSTR MSG_MOVE_N = _UxGT("Miči @"); + LSTR MSG_MOVE_E = _UxGT("Miči E"); + LSTR MSG_MOVE_EN = _UxGT("Miči *"); LSTR MSG_MOVE_N_MM = _UxGT("Miči $mm"); LSTR MSG_MOVE_01MM = _UxGT("Miči 0.1mm"); LSTR MSG_MOVE_1MM = _UxGT("Miči 1mm"); diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 0a53ee50d2..bc8c9ba40e 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -92,7 +92,9 @@ namespace Language_jp_kana { LSTR MSG_MOVE_X = _UxGT("Xジク イドウ"); // "Move X" LSTR MSG_MOVE_Y = _UxGT("Yジク イドウ"); // "Move Y" LSTR MSG_MOVE_Z = _UxGT("Zジク イドウ"); // "Move Z" + LSTR MSG_MOVE_N = _UxGT("@ジク イドウ"); // "Move @" LSTR MSG_MOVE_E = _UxGT("エクストルーダー"); // "Extruder" + LSTR MSG_MOVE_EN = _UxGT("* エクストルーダー"); // "En" LSTR MSG_MOVE_N_MM = _UxGT("$mm イドウ"); // "Move 0.025mm" LSTR MSG_MOVE_01MM = _UxGT("0.1mm イドウ"); // "Move 0.1mm" LSTR MSG_MOVE_1MM = _UxGT(" 1mm イドウ"); // "Move 1mm" diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index ca51198034..8aa74d7e9f 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -84,6 +84,7 @@ namespace Language_nl { LSTR MSG_MOVE_X = _UxGT("Verplaats X"); LSTR MSG_MOVE_Y = _UxGT("Verplaats Y"); LSTR MSG_MOVE_Z = _UxGT("Verplaats Z"); + LSTR MSG_MOVE_N = _UxGT("Verplaats @"); LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); LSTR MSG_MOVE_N_MM = _UxGT("Verplaats $mm"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 34155f87fe..635866baf1 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -235,6 +235,7 @@ namespace Language_pl { LSTR MSG_MOVE_X = _UxGT("Przesuń w X"); LSTR MSG_MOVE_Y = _UxGT("Przesuń w Y"); LSTR MSG_MOVE_Z = _UxGT("Przesuń w Z"); + LSTR MSG_MOVE_N = _UxGT("Przesuń w @"); LSTR MSG_MOVE_E = _UxGT("Ekstruzja (os E)"); LSTR MSG_MOVE_EN = _UxGT("Ekstruzja (os E) *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Dysza za zimna"); diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 69df8bdf54..55d9c1d7c5 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -78,6 +78,7 @@ namespace Language_pt { LSTR MSG_MOVE_X = _UxGT("Mover X"); LSTR MSG_MOVE_Y = _UxGT("Mover Y"); LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_N = _UxGT("Mover @"); LSTR MSG_MOVE_E = _UxGT("Mover Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Mover Extrusor *"); LSTR MSG_MOVE_N_MM = _UxGT("Mover $mm"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 0f0f8c5287..1d07b2b94f 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -209,6 +209,7 @@ namespace Language_pt_br { LSTR MSG_MOVE_X = _UxGT("Mover X"); LSTR MSG_MOVE_Y = _UxGT("Mover Y"); LSTR MSG_MOVE_Z = _UxGT("Mover Z"); + LSTR MSG_MOVE_N = _UxGT("Mover @"); LSTR MSG_MOVE_E = _UxGT("Mover Extrusor"); LSTR MSG_MOVE_EN = _UxGT("Mover Extrusor *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Extrus. mto fria"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 3bd15f18a4..2cf6fff263 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -222,6 +222,7 @@ namespace Language_ro { LSTR MSG_MOVE_X = _UxGT("Move X"); LSTR MSG_MOVE_Y = _UxGT("Move Y"); LSTR MSG_MOVE_Z = _UxGT("Move Z"); + LSTR MSG_MOVE_N = _UxGT("Move @"); LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Capat Prea Rece"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index 6bfb7100f4..1342ccaad7 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -249,6 +249,7 @@ namespace Language_sv { LSTR MSG_MOVE_X = _UxGT("Flytta X"); LSTR MSG_MOVE_Y = _UxGT("Flytta Y"); LSTR MSG_MOVE_Z = _UxGT("Flytta Z"); + LSTR MSG_MOVE_N = _UxGT("Flytta @"); LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hetände för kall"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index c9967f72ec..cb2766306c 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -225,6 +225,7 @@ namespace Language_tr { LSTR MSG_MOVE_X = _UxGT("X Hareketi"); LSTR MSG_MOVE_Y = _UxGT("Y Hareketi"); LSTR MSG_MOVE_Z = _UxGT("Z Hareketi"); + LSTR MSG_MOVE_N = _UxGT("@ Hareketi"); LSTR MSG_MOVE_E = _UxGT("Ekstruder"); LSTR MSG_MOVE_EN = _UxGT("Ekstruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Nozul Çok Soğuk"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 989a201d4d..27c6ee1181 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -198,6 +198,7 @@ namespace Language_vi { LSTR MSG_MOVE_X = _UxGT("Di chuyển X"); // Move X LSTR MSG_MOVE_Y = _UxGT("Di chuyển Y"); LSTR MSG_MOVE_Z = _UxGT("Di chuyển Z"); + LSTR MSG_MOVE_N = _UxGT("Di chuyển @"); LSTR MSG_MOVE_E = _UxGT("Máy đùn"); // Extruder LSTR MSG_MOVE_EN = _UxGT("Máy đùn *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Đầu nóng quá lạnh"); // Hotend too cold diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index fc61b020ff..4c5a94edcd 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -222,6 +222,7 @@ namespace Language_zh_CN { LSTR MSG_MOVE_X = _UxGT("移动X"); // "Move X" LSTR MSG_MOVE_Y = _UxGT("移动Y"); // "Move Y" LSTR MSG_MOVE_Z = _UxGT("移动Z"); // "Move Z" + LSTR MSG_MOVE_N = _UxGT("移动@"); // "Move @" LSTR MSG_MOVE_E = _UxGT("挤出机"); // "Extruder" LSTR MSG_MOVE_EN = _UxGT("挤出机 *"); // "Extruder" LSTR MSG_HOTEND_TOO_COLD = _UxGT("热端太冷"); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index b35a486e4f..4eba832c4f 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -218,6 +218,7 @@ namespace Language_zh_TW { LSTR MSG_MOVE_X = _UxGT("移動X"); // "Move X" LSTR MSG_MOVE_Y = _UxGT("移動Y"); // "Move Y" LSTR MSG_MOVE_Z = _UxGT("移動Z"); // "Move Z" + LSTR MSG_MOVE_N = _UxGT("移動Q"); // "Move @" LSTR MSG_MOVE_E = _UxGT("擠出機"); // "Extruder" LSTR MSG_MOVE_EN = _UxGT("擠出機 *"); // "Extruder *" LSTR MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); // "Hotend too cold" diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 3e7a9ca1b1..9d2fba446a 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -176,6 +176,8 @@ typedef bool (*statusResetFunc_t)(); static void soon(const AxisEnum axis OPTARG(MULTI_E_MANUAL, const int8_t eindex=active_extruder)); }; + void lcd_move_axis(const AxisEnum); + #endif //////////////////////////////////////////// diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index a1e2beaf72..c11f389276 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -191,7 +191,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co else { #if ENABLED(MOVE_Z_WHEN_IDLE) ui.manual_move.menu_scale = MOVE_Z_IDLE_MULTIPLICATOR; - screen = lcd_move_z; + screen = []{ lcd_move_axis(Z_AXIS); }; #endif } } diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 6f5a9efb15..befffe5f72 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -214,8 +214,6 @@ void menu_move(); //////// Menu Item Helper Functions //////// //////////////////////////////////////////// -void lcd_move_axis(const AxisEnum); -void lcd_move_z(); void _lcd_draw_homing(); #define HAS_LINE_TO_Z ANY(DELTA, PROBE_MANUALLY, MESH_BED_LEVELING, LCD_BED_TRAMMING) diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index b86f101258..ae935e53c4 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -52,7 +52,7 @@ void _man_probe_pt(const xy_pos_t &xy) { ui.wait_for_move = false; ui.synchronize(); ui.manual_move.menu_scale = _MAX(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / planner.settings.axis_steps_per_mm[0]); // Use first axis as for delta XYZ should always match - ui.goto_screen(lcd_move_z); + ui.goto_screen([]{ lcd_move_axis(Z_AXIS); }); } } diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index c009567ef2..b0eab65c64 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -31,8 +31,6 @@ #include "../../module/planner.h" #endif -void lcd_move_z(); - //////////////////////////////////////////// ///////////// Base Menu Items ////////////// //////////////////////////////////////////// diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 3765fe1e4a..d5c2424429 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -74,6 +74,7 @@ void lcd_move_axis(const AxisEnum axis) { } ui.encoderPosition = 0; if (ui.should_draw()) { + MenuEditItemBase::itemIndex = axis; const float pos = ui.manual_move.axis_value(axis); if (parser.using_inch_units()) { const float imp_pos = LINEAR_UNIT(pos); @@ -84,9 +85,6 @@ void lcd_move_axis(const AxisEnum axis) { } } -// Move Z easy accessor -void lcd_move_z() { lcd_move_axis(Z_AXIS); } - #if E_MANUAL static void lcd_move_e(TERN_(MULTI_E_MANUAL, const int8_t eindex=active_extruder)) { @@ -118,7 +116,7 @@ void lcd_move_z() { lcd_move_axis(Z_AXIS); } void _goto_manual_move_z(const_float_t scale) { ui.manual_move.menu_scale = scale; - ui.goto_screen(lcd_move_z); + ui.goto_screen([]{ lcd_move_axis(Z_AXIS); }); } #endif From f752fe75ee6e4304741c743fbb2b52b7d5760ae4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 18 Jul 2022 19:53:36 -0500 Subject: [PATCH 06/54] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Small=20sound=20/=20?= =?UTF-8?q?buzz=20refactor=20(#24520)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/pause.cpp | 4 ++-- Marlin/src/feature/spindle_laser.h | 2 +- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/gcode/lcd/M300.cpp | 4 ++-- Marlin/src/inc/Conditionals_post.h | 12 +++++++---- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 5 +++-- Marlin/src/lcd/e3v2/common/encoder.cpp | 8 +++---- Marlin/src/lcd/e3v2/creality/dwin.cpp | 16 +++++++------- Marlin/src/lcd/marlinui.cpp | 23 +++++++-------------- Marlin/src/lcd/marlinui.h | 8 +++---- Marlin/src/lcd/menu/game/game.h | 2 +- Marlin/src/lcd/menu/menu.cpp | 4 ++-- Marlin/src/libs/buzzer.h | 6 +++--- Marlin/src/module/printcounter.cpp | 4 ++-- ini/features.ini | 2 +- 16 files changed, 49 insertions(+), 55 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index e9cb2df594..78572b0795 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -63,7 +63,7 @@ #include "../lcd/marlinui.h" -#if HAS_BUZZER +#if HAS_SOUND #include "../libs/buzzer.h" #endif @@ -98,7 +98,7 @@ fil_change_settings_t fc_settings[EXTRUDERS]; #define _PMSG(L) L##_LCD #endif -#if HAS_BUZZER +#if HAS_SOUND static void impatient_beep(const int8_t max_beep_count, const bool restart=false) { if (TERN0(HAS_MARLINUI_MENU, pause_mode == PAUSE_MODE_PAUSE_PRINT)) return; diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index b945032d8e..8c73394c9b 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -294,7 +294,7 @@ public: * If not set defaults to 80% power */ static void test_fire_pulse() { - TERN_(HAS_BEEPER, buzzer.tone(30, 3000)); + BUZZ(30, 3000); cutter_mode = CUTTER_MODE_STANDARD;// Menu needs standard mode. laser_menu_toggle(true); // Laser On delay(testPulse); // Delay for time set by user in pulse ms menu screen. diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 1cbd3019c8..0cae1573bc 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -765,7 +765,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 290: M290(); break; // M290: Babystepping #endif - #if HAS_BUZZER + #if HAS_SOUND case 300: M300(); break; // M300: Play beep tone #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 3657ab2b12..135cfc7f43 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -914,7 +914,7 @@ private: static void M290(); #endif - #if HAS_BUZZER + #if HAS_SOUND static void M300(); #endif diff --git a/Marlin/src/gcode/lcd/M300.cpp b/Marlin/src/gcode/lcd/M300.cpp index 5250774955..76d4b96b24 100644 --- a/Marlin/src/gcode/lcd/M300.cpp +++ b/Marlin/src/gcode/lcd/M300.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if HAS_BUZZER +#if HAS_SOUND #include "../gcode.h" @@ -42,4 +42,4 @@ void GcodeSuite::M300() { BUZZ(duration, frequency); } -#endif // HAS_BUZZER +#endif // HAS_SOUND diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 517e95c83e..7d2009dc8f 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -3564,8 +3564,11 @@ #if PIN_EXISTS(BEEPER) #define HAS_BEEPER 1 #endif -#if ANY(HAS_BEEPER, LCD_USE_I2C_BUZZER, PCA9632_BUZZER) - #define HAS_BUZZER 1 +#if ANY(IS_TFTGLCD_PANEL, PCA9632_BUZZER, LCD_USE_I2C_BUZZER) + #define USE_MARLINUI_BUZZER 1 +#endif +#if EITHER(HAS_BEEPER, USE_MARLINUI_BUZZER) + #define HAS_SOUND 1 #endif #if ENABLED(LCD_USE_I2C_BUZZER) @@ -3575,7 +3578,7 @@ #ifndef LCD_FEEDBACK_FREQUENCY_DURATION_MS #define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 #endif -#elif HAS_BUZZER +#elif HAS_SOUND #ifndef LCD_FEEDBACK_FREQUENCY_HZ #define LCD_FEEDBACK_FREQUENCY_HZ 5000 #endif @@ -3584,12 +3587,13 @@ #endif #endif -#if HAS_BUZZER +#if HAS_SOUND #if LCD_FEEDBACK_FREQUENCY_DURATION_MS && LCD_FEEDBACK_FREQUENCY_HZ #define HAS_CHIRP 1 #endif #else #undef SOUND_MENU_ITEM // No buzzer menu item without a buzzer + #undef SOUND_ON_DEFAULT #endif /** diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index d8306dbf94..b8dc8db817 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -120,10 +120,11 @@ static void createChar_P(const char c, const byte * const ptr) { #endif #if ENABLED(LCD_USE_I2C_BUZZER) + void MarlinUI::buzz(const long duration, const uint16_t freq) { - if (!sound_on) return; - lcd.buzz(duration, freq); + if (sound_on) lcd.buzz(duration, freq); } + #endif void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARSET_INFO*/) { diff --git a/Marlin/src/lcd/e3v2/common/encoder.cpp b/Marlin/src/lcd/e3v2/common/encoder.cpp index 9922b70b29..f14d63e7b5 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.cpp +++ b/Marlin/src/lcd/e3v2/common/encoder.cpp @@ -36,7 +36,7 @@ #include "../../marlinui.h" #include "../../../HAL/shared/Delay.h" -#if HAS_BUZZER +#if HAS_SOUND #include "../../../libs/buzzer.h" #endif @@ -50,9 +50,7 @@ ENCODER_Rate EncoderRate; // TODO: Replace with ui.quick_feedback void Encoder_tick() { - #if PIN_EXISTS(BEEPER) - if (ui.sound_on) buzzer.click(10); - #endif + TERN_(HAS_BEEPER, if (ui.sound_on) buzzer.click(10)); } // Encoder initialization @@ -66,7 +64,7 @@ void Encoder_Configuration() { #if BUTTON_EXISTS(ENC) SET_INPUT_PULLUP(BTN_ENC); #endif - #if PIN_EXISTS(BEEPER) + #if HAS_BEEPER SET_OUTPUT(BEEPER_PIN); // TODO: Use buzzer.h which already inits this #endif } diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 3ca7627db0..1232c8e0c9 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -2625,15 +2625,13 @@ void Draw_HomeOff_Menu() { #include "../../../libs/buzzer.h" void HMI_AudioFeedback(const bool success=true) { - #if HAS_BUZZER - if (success) { - buzzer.tone(100, 659); - buzzer.tone(10, 0); - buzzer.tone(100, 698); - } - else - buzzer.tone(40, 440); - #endif + if (success) { + BUZZ(100, 659); + BUZZ(10, 0); + BUZZ(100, 698); + } + else + BUZZ(40, 440); } // Prepare diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 7707cbb052..5b17b0b975 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -119,17 +119,9 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; bool MarlinUI::sound_on = ENABLED(SOUND_ON_DEFAULT); #endif -#if EITHER(PCA9632_BUZZER, HAS_BEEPER) - #if ENABLED(PCA9632_BUZZER) - #include "../feature/leds/pca9632.h" - #endif +#if ENABLED(PCA9632_BUZZER) void MarlinUI::buzz(const long duration, const uint16_t freq) { - if (!sound_on) return; - #if ENABLED(PCA9632_BUZZER) - PCA9632_buzz(duration, freq); - #elif HAS_BEEPER - buzzer.tone(duration, freq); - #endif + if (sound_on) PCA9632_buzz(duration, freq); } #endif @@ -683,7 +675,7 @@ void MarlinUI::init() { if (old_frm != new_frm) { feedrate_percentage = new_frm; encoderPosition = 0; - #if BOTH(HAS_BUZZER, BEEP_ON_FEEDRATE_CHANGE) + #if BOTH(HAS_SOUND, BEEP_ON_FEEDRATE_CHANGE) static millis_t next_beep; #ifndef GOT_MS const millis_t ms = millis(); @@ -741,11 +733,12 @@ void MarlinUI::init() { UNUSED(clear_buttons); #endif - #if HAS_CHIRP - chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) + chirp(); // Buzz and wait. Is the delay needed for buttons to settle? + + #if HAS_CHIRP && HAS_MARLINUI_MENU + #if HAS_BEEPER for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } - #elif HAS_MARLINUI_MENU + #else delay(10); #endif #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 9d2fba446a..a4166c4100 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -225,12 +225,12 @@ public: static constexpr bool sound_on = true; #endif - #if HAS_BUZZER + #if USE_MARLINUI_BUZZER static void buzz(const long duration, const uint16_t freq); #endif - FORCE_INLINE static void chirp() { - TERN_(HAS_CHIRP, TERN(HAS_BUZZER, buzz, BUZZ)(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); + static void chirp() { + TERN_(HAS_CHIRP, TERN(USE_MARLINUI_BUZZER, buzz, BUZZ)(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ)); } #if ENABLED(LCD_HAS_STATUS_INDICATORS) @@ -453,7 +453,7 @@ public: #endif static void quick_feedback(const bool clear_buttons=true); - #if HAS_BUZZER + #if HAS_SOUND static void completion_feedback(const bool good=true); #else static void completion_feedback(const bool=true) { TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); } diff --git a/Marlin/src/lcd/menu/game/game.h b/Marlin/src/lcd/menu/game/game.h index 999aa78100..ba123cb98b 100644 --- a/Marlin/src/lcd/menu/game/game.h +++ b/Marlin/src/lcd/menu/game/game.h @@ -28,7 +28,7 @@ //#define MUTE_GAMES -#if ENABLED(MUTE_GAMES) || !HAS_BUZZER +#if ENABLED(MUTE_GAMES) || !HAS_SOUND #define _BUZZ(D,F) NOOP #else #define _BUZZ(D,F) BUZZ(D,F) diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index c11f389276..9dd74988f3 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -31,7 +31,7 @@ #include "../../module/temperature.h" #include "../../gcode/queue.h" -#if HAS_BUZZER +#if HAS_SOUND #include "../../libs/buzzer.h" #endif @@ -272,7 +272,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { encoderTopLine = encoderLine; } -#if HAS_BUZZER +#if HAS_SOUND void MarlinUI::completion_feedback(const bool good/*=true*/) { TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); // Wake up on rotary encoder click... if (good) OKAY_BUZZ(); else ERR_BUZZ(); diff --git a/Marlin/src/libs/buzzer.h b/Marlin/src/libs/buzzer.h index b1c286a662..cd8e17d004 100644 --- a/Marlin/src/libs/buzzer.h +++ b/Marlin/src/libs/buzzer.h @@ -117,11 +117,11 @@ // Buzz directly via the BEEPER pin tone queue #define BUZZ(d,f) buzzer.tone(d, f) -#elif HAS_BUZZER +#elif USE_MARLINUI_BUZZER - // Buzz indirectly via the MarlinUI instance - #define BUZZ(d,f) ui.buzz(d,f) + // Use MarlinUI for a buzzer on the LCD #include "../lcd/marlinui.h" + #define BUZZ(d,f) ui.buzz(d,f) #else diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index 619fbc137c..ad6f4eff68 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -37,7 +37,7 @@ Stopwatch print_job_timer; // Global Print Job Timer instance #include "../MarlinCore.h" #include "../HAL/shared/eeprom_api.h" -#if HAS_BUZZER && SERVICE_WARNING_BUZZES > 0 +#if HAS_SOUND && SERVICE_WARNING_BUZZES > 0 #include "../libs/buzzer.h" #endif @@ -156,7 +156,7 @@ void PrintCounter::loadStats() { #if SERVICE_INTERVAL_3 > 0 if (data.nextService3 == 0) doBuzz = _service_warn(PSTR(" " SERVICE_NAME_3)); #endif - #if HAS_BUZZER && SERVICE_WARNING_BUZZES > 0 + #if HAS_SOUND && SERVICE_WARNING_BUZZES > 0 if (doBuzz) for (int i = 0; i < SERVICE_WARNING_BUZZES; i++) { BUZZ(200, 404); BUZZ(10, 0); } #else UNUSED(doBuzz); diff --git a/ini/features.ini b/ini/features.ini index 6eebbe8fd2..a763213299 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -202,7 +202,7 @@ HAS_STATUS_MESSAGE = src_filter=+ HAS_LCD_CONTRAST = src_filter=+ HAS_GCODE_M255 = src_filter=+ HAS_LCD_BRIGHTNESS = src_filter=+ -HAS_BUZZER = src_filter=+ +HAS_SOUND = src_filter=+ TOUCH_SCREEN_CALIBRATION = src_filter=+ ARC_SUPPORT = src_filter=+ GCODE_MOTION_MODES = src_filter=+ From 807f2ef9697c241fdb8c354d90ca97050ccbca68 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Mon, 18 Jul 2022 21:12:27 -0400 Subject: [PATCH 07/54] =?UTF-8?q?=F0=9F=9A=B8=20Machine-relative=20Z=5FSTE?= =?UTF-8?q?PPER=5FALIGN=5FXY=20(#24261)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 9 ++++++--- Marlin/src/gcode/calibrate/G34_M422.cpp | 6 ++++-- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 1a327e769a..77e8c0ae25 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -937,9 +937,12 @@ */ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) - // Define probe X and Y positions for Z1, Z2 [, Z3 [, Z4]] - // If not defined, probe limits will be used. - // Override with 'M422 S X Y' + /** + * Define probe X and Y positions for Z1, Z2 [, Z3 [, Z4]] + * These positions are machine-relative and do not shift with the M206 home offset! + * If not defined, probe limits will be used. + * Override with 'M422 S X Y'. + */ //#define Z_STEPPER_ALIGN_XY { { 10, 190 }, { 100, 10 }, { 190, 190 } } /** diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index d68207885d..8cf652cd84 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -224,13 +224,15 @@ void GcodeSuite::G34() { // Safe clearance even on an incline if ((iteration == 0 || i > 0) && z_probe > current_position.z) do_blocking_move_to_z(z_probe); + xy_pos_t &ppos = z_stepper_align.xy[iprobe]; + if (DEBUGGING(LEVELING)) - DEBUG_ECHOLNPGM_P(PSTR("Probing X"), z_stepper_align.xy[iprobe].x, SP_Y_STR, z_stepper_align.xy[iprobe].y); + DEBUG_ECHOLNPGM_P(PSTR("Probing X"), ppos.x, SP_Y_STR, ppos.y); // Probe a Z height for each stepper. // Probing sanity check is disabled, as it would trigger even in normal cases because // current_position.z has been manually altered in the "dirty trick" above. - const float z_probed_height = probe.probe_at_point(z_stepper_align.xy[iprobe], raise_after, 0, true, false); + const float z_probed_height = probe.probe_at_point(DIFF_TERN(HAS_HOME_OFFSET, ppos, xy_pos_t(home_offset)), raise_after, 0, true, false); if (isnan(z_probed_height)) { SERIAL_ECHOLNPGM("Probing failed"); LCD_MESSAGE(MSG_LCD_PROBING_FAILED); From c3085d666ffba28c67890bfc4424c30855188048 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 18 Jul 2022 18:14:58 -0700 Subject: [PATCH 08/54] =?UTF-8?q?=F0=9F=93=9D=20Update=20Contributing=20Gu?= =?UTF-8?q?ide=20(#24320)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/contributing.md | 7 +++++-- README.md | 2 +- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/.github/contributing.md b/.github/contributing.md index fcb87b0141..ef1726366a 100644 --- a/.github/contributing.md +++ b/.github/contributing.md @@ -34,8 +34,11 @@ This project and everyone participating in it is governed by the [Marlin Code of We have a Message Board and a Facebook group where our knowledgable user community can provide helpful advice if you have questions. -* [Marlin RepRap forum](https://reprap.org/forum/list.php?415) -* [MarlinFirmware on Facebook](https://www.facebook.com/groups/1049718498464482/) +- [Marlin Documentation](https://marlinfw.org) - Official Marlin documentation +- Facebook Group ["Marlin Firmware"](https://www.facebook.com/groups/1049718498464482/) +- RepRap.org [Marlin Forum](https://forums.reprap.org/list.php?415) +- Facebook Group ["Marlin Firmware for 3D Printers"](https://www.facebook.com/groups/3Dtechtalk/) +- [Marlin Configuration](https://www.youtube.com/results?search_query=marlin+configuration) on YouTube If chat is more your speed, you can join the MarlinFirmware Discord server: diff --git a/README.md b/README.md index cad9e9a560..9d3ac6baaa 100644 --- a/README.md +++ b/README.md @@ -80,7 +80,7 @@ Regular users can open and close their own issues, but only the administrators c - Scott Lahteine [[@thinkyhead](https://github.com/thinkyhead)] - USA - Project Maintainer   [💸 Donate](https://www.thinkyhead.com/donate-to-marlin) - Roxanne Neufeld [[@Roxy-3D](https://github.com/Roxy-3D)] - USA - Keith Bennett [[@thisiskeithb](https://github.com/thisiskeithb)] - USA   [💸 Donate](https://github.com/sponsors/thisiskeithb) - - Peter Ellens [[@ellensp](https://github.com/ellensp)] - New Zealand + - Peter Ellens [[@ellensp](https://github.com/ellensp)] - New Zealand   [💸 Donate](https://ko-fi.com/ellensp) - Victor Oliveira [[@rhapsodyv](https://github.com/rhapsodyv)] - Brazil - Chris Pepper [[@p3p](https://github.com/p3p)] - UK - Jason Smith [[@sjasonsmith](https://github.com/sjasonsmith)] - USA From 196795c0cc1ea31380d4c06374cf032a25e47c1d Mon Sep 17 00:00:00 2001 From: Eduard Sukharev Date: Wed, 20 Jul 2022 01:30:19 +0300 Subject: [PATCH 09/54] =?UTF-8?q?=E2=9C=85=20More=20ESP32=20(MKS=20TinyBee?= =?UTF-8?q?)=20tests=20(#24493)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/restore_configs | 3 ++- buildroot/tests/mks_tinybee | 33 +++++++++++++++++++++++++++++++++ 2 files changed, 35 insertions(+), 1 deletion(-) create mode 100755 buildroot/tests/mks_tinybee diff --git a/buildroot/bin/restore_configs b/buildroot/bin/restore_configs index 61aa3f9ee1..04df695a00 100755 --- a/buildroot/bin/restore_configs +++ b/buildroot/bin/restore_configs @@ -1,5 +1,6 @@ #!/usr/bin/env bash -git checkout Marlin/Configuration*.h 2>/dev/null +git checkout Marlin/Configuration.h 2>/dev/null +git checkout Marlin/Configuration_adv.h 2>/dev/null git checkout Marlin/src/pins/ramps/pins_RAMPS.h 2>/dev/null rm -f Marlin/_Bootscreen.h Marlin/_Statusscreen.h marlin_config.json .pio/build/mc.zip diff --git a/buildroot/tests/mks_tinybee b/buildroot/tests/mks_tinybee new file mode 100755 index 0000000000..8b5aa0f075 --- /dev/null +++ b/buildroot/tests/mks_tinybee @@ -0,0 +1,33 @@ +#!/usr/bin/env bash +# +# Build tests for MKS TinyBee +# + +# exit on first failure +set -e + +# +# Build with ESP3D WiFi, OTA and custom WIFI commands support +# +restore_configs +opt_set MOTHERBOARD BOARD_MKS_TINYBEE TX_BUFFER_SIZE 64 \ + WIFI_SSID '"ssid"' WIFI_PWD '"password"' \ + SERIAL_PORT_2 -1 BAUDRATE_2 250000 +opt_enable ESP3D_WIFISUPPORT WEBSUPPORT OTASUPPORT WIFI_CUSTOM_COMMAND +exec_test $1 "$2" "MKS TinyBee with ESP3D_WIFISUPPORT" "$3" + +# +# Build with LCD, SD support and Speaker support +# +restore_configs +opt_set MOTHERBOARD BOARD_MKS_TINYBEE \ + LCD_LANGUAGE en \ + LCD_INFO_SCREEN_STYLE 0 \ + DISPLAY_CHARSET_HD44780 WESTERN \ + NEOPIXEL_TYPE NEO_RGB +opt_enable FYSETC_MINI_12864_2_1 SDSUPPORT +opt_enable LED_CONTROL_MENU LED_USER_PRESET_STARTUP LED_COLOR_PRESETS NEOPIXEL_LED +exec_test $1 $2 "MKS TinyBee with NeoPixel LCD, SD and Speaker" "$3" + +# cleanup +restore_configs From f5b972bb103bcac57d3c8bd26f80d93e3f86a5f8 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 20 Jul 2022 10:32:08 +1200 Subject: [PATCH 10/54] =?UTF-8?q?=F0=9F=93=BA=20SKR=5FMINI=5FSCREEN=5FADAP?= =?UTF-8?q?TER=20for=20BTT=20SKR=20Mini=20E3=20V3=20(#24521)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h | 240 +++++++++++------- 1 file changed, 147 insertions(+), 93 deletions(-) diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h index f35bdb227f..2ac0674513 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h @@ -75,10 +75,6 @@ #define POWER_LOSS_PIN PC12 // Power Loss Detection: PWR-DET #endif -#ifndef NEOPIXEL_PIN - #define NEOPIXEL_PIN PA8 // LED driving pin -#endif - #ifndef PS_ON_PIN #define PS_ON_PIN PC13 // Power Supply Control #endif @@ -153,8 +149,16 @@ * ------ * EXP1 */ +#define EXP1_01_PIN PB5 #define EXP1_02_PIN PA15 +#define EXP1_03_PIN PA9 +#define EXP1_04_PIN -1 +#define EXP1_05_PIN PA10 +#define EXP1_06_PIN PB9 +#define EXP1_07_PIN PB8 #define EXP1_08_PIN PD6 +#define EXP1_09_PIN -1 +#define EXP1_10_PIN -1 #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI /** @@ -176,93 +180,135 @@ #define BEEPER_PIN EXP1_02_PIN #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 PB8 - #define BTN_ENC PB5 + #define BTN_EN2 EXP1_07_PIN + #define BTN_ENC EXP1_01_PIN #elif HAS_WIRED_LCD - #if ENABLED(CR10_STOCKDISPLAY) - - #define BEEPER_PIN PB5 - #define BTN_ENC EXP1_02_PIN - - #define BTN_EN1 PA9 - #define BTN_EN2 PA10 - - #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 PB9 - - #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! - - #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING - #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #if ENABLED(SKR_MINI_SCREEN_ADAPTER) + /** https://github.com/VoronDesign/Voron-Hardware/tree/master/SKR-Mini_Screen_Adaptor/SRK%20Mini%20E3%20V3.0 + * + * SKR Mini E3 V3.0 SKR Mini Screen Adaptor + * ------ ------ + * 5V | 1 2 | GND MISO | 1 2 | SCK + * CS | 3 4 | SCK (EN1) PA10 | 3 4 | -- + * MOSI | 5 6 | MISO (EN2) PA9 5 6 | MOSI + * 3V3 | 7 8 | GND -- | 7 8 | -- + * ------ GND | 9 10| RESET (Kill) + * SPI ------ + * EXP2 + * + * ------ ------ + * PB5 | 1 2 | PA15 -- | 1 2 | PB5 (BTN_ENC) + * PA9 | 3 4 | RESET (LCD CS) PB8 | 3 4 | PD6 (LCD_A0) + * PA10 5 6 | PB9 (RESET) PB9 5 6 | PA15 (DIN) + * PB8 | 7 8 | PD6 -- | 7 8 | -- + * GND | 9 10| 5V GND | 9 10| 5V + * ------ ------ + * EXP1 EXP1 + */ + #if ENABLED(FYSETC_MINI_12864_2_1) + #define BTN_ENC EXP1_01_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BEEPER_PIN -1 + #define LCD_RESET_PIN EXP1_06_PIN + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_A0 EXP1_08_PIN + #define DOGLCD_SCK PA5 + #define DOGLCD_MOSI PA7 + + #define FORCE_SOFT_SPI + #define LCD_BACKLIGHT_PIN -1 + #define NEOPIXEL_PIN EXP1_02_PIN + #else + #error "Only CR10_FYSETC_MINI_12864_2_1 and compatibles are currently supported on the BIGTREE_SKR_MINI_E3 with SKR_MINI_SCREEN_ADAPTER" #endif - #define LCD_PINS_RS PB9 - #define LCD_PINS_ENABLE EXP1_02_PIN - #define LCD_PINS_D4 PB8 - #define LCD_PINS_D5 PA10 - #define LCD_PINS_D6 PA9 - #define LCD_PINS_D7 PB5 - #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #else - #define BTN_ENC EXP1_02_PIN - #define BTN_EN1 PA9 - #define BTN_EN2 PA10 + #if ENABLED(CR10_STOCKDISPLAY) - #define DOGLCD_CS PB8 - #define DOGLCD_A0 PB9 - #define DOGLCD_SCK PB5 - #define DOGLCD_MOSI EXP1_08_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN - #define FORCE_SOFT_SPI - #define LCD_BACKLIGHT_PIN -1 + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #elif IS_TFTGLCD_PANEL + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN - #if ENABLED(TFTGLCD_PANEL_SPI) + #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING - #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" #endif - /** - * TFTGLCD_PANEL_SPI display pinout - * - * Board Display - * ------ ------ - * (BEEPER) PB6 | 1 2 | PB5 (SD_DET) 5V | 1 2 | GND - * RESET | 3 4 | PA9 (MOD_RESET) -- | 3 4 | (SD_DET) - * PB9 5 6 | PA10 (SD_CS) (MOSI) | 5 6 | -- - * PB7 | 7 8 | PB8 (LCD_CS) (SD_CS) | 7 8 | (LCD_CS) - * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) - * ------ ------ - * EXP1 EXP1 - * - * Needs custom cable: - * - * Board Display - * - * EXP1-1 ----------- EXP1-10 - * EXP1-2 ----------- EXP1-9 - * SPI1-4 ----------- EXP1-6 - * EXP1-4 ----------- FREE - * SPI1-3 ----------- EXP1-2 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- FREE - * EXP1-8 ----------- EXP1-3 - * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-7 - */ + #define LCD_PINS_RS EXP1_06_PIN + #define LCD_PINS_ENABLE EXP1_02_PIN + #define LCD_PINS_D4 EXP1_07_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_01_PIN + #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! + + #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_A0 EXP1_06_PIN + #define DOGLCD_SCK EXP1_01_PIN + #define DOGLCD_MOSI EXP1_08_PIN + + #define FORCE_SOFT_SPI + #define LCD_BACKLIGHT_PIN -1 + + #elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif + + /** + * TFTGLCD_PANEL_SPI display pinout + * + * Board Display + * ------ ------ + * (BEEPER) PB6 | 1 2 | PB5 (SD_DET) 5V | 1 2 | GND + * RESET | 3 4 | PA9 (MOD_RESET) -- | 3 4 | (SD_DET) + * PB9 5 6 | PA10 (SD_CS) (MOSI) | 5 6 | -- + * PB7 | 7 8 | PB8 (LCD_CS) (SD_CS) | 7 8 | (LCD_CS) + * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) + * ------ ------ + * EXP1 EXP1 + * + * Needs custom cable: + * + * Board Display + * + * EXP1-1 ----------- EXP1-10 + * EXP1-2 ----------- EXP1-9 + * SPI1-4 ----------- EXP1-6 + * EXP1-4 ----------- FREE + * SPI1-3 ----------- EXP1-2 + * EXP1-6 ----------- EXP1-4 + * EXP1-7 ----------- FREE + * EXP1-8 ----------- EXP1-3 + * SPI1-1 ----------- EXP1-1 + * EXP1-10 ----------- EXP1-7 + */ + + #define TFTGLCD_CS EXP1_03_PIN - #define TFTGLCD_CS PA9 - - #endif + #endif - #elif ENABLED(FYSETC_MINI_12864_2_1) + #elif ENABLED(FYSETC_MINI_12864_2_1) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! FYSETC_MINI_12864_2_1 and clones require wiring modifications. See 'pins_BTT_SKR_MINI_E3_V3_0.h' for details. Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning" @@ -294,22 +340,24 @@ * Check twice index position!!! (marked as # here) * On BTT boards pins from IDC10 connector are numbered in unusual order. */ - #define BTN_ENC EXP1_02_PIN - #define BTN_EN1 PB9 - #define BTN_EN2 PB5 - #define BEEPER_PIN -1 + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_01_PIN + #define BEEPER_PIN -1 - #define DOGLCD_CS PA9 - #define DOGLCD_A0 PA10 - #define DOGLCD_SCK PB8 - #define DOGLCD_MOSI PD6 + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_05_PIN + #define DOGLCD_SCK EXP1_07_PIN + #define DOGLCD_MOSI EXP1_08_PIN - #define FORCE_SOFT_SPI - #define LCD_BACKLIGHT_PIN -1 + #define FORCE_SOFT_SPI + #define LCD_BACKLIGHT_PIN -1 - #else - #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, FYSETC_MINI_12864_2_1, and TFTGLCD_PANEL_(SPI|I2C) are currently supported on the BIGTREE_SKR_MINI_E3." - #endif + #else + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, FYSETC_MINI_12864_2_1, and TFTGLCD_PANEL_(SPI|I2C) are currently supported on the BIGTREE_SKR_MINI_E3." + #endif + + #endif // SKR_MINI_SCREEN_ADAPTER #endif // HAS_WIRED_LCD @@ -352,9 +400,8 @@ #define BEEPER_PIN EXP1_02_PIN - #define CLCD_MOD_RESET PA9 - #define CLCD_SPI_CS PB8 - + #define CLCD_MOD_RESET EXP1_03_PIN + #define CLCD_SPI_CS EXP1_07_PIN #endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 // @@ -368,8 +415,8 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC3 #elif SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) - #define SD_DETECT_PIN PB5 - #define SD_SS_PIN PA10 + #define SD_DETECT_PIN EXP1_01_PIN + #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR Mini E3." #endif @@ -383,3 +430,10 @@ #define SD_SCK_PIN PA5 #define SD_MISO_PIN PA6 #define SD_MOSI_PIN PA7 + +// +// Default NEOPIXEL_PIN +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PA8 // LED driving pin +#endif From feafa321d7caa90f886ef7d66f6b0513d5c595e3 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Tue, 19 Jul 2022 18:33:49 -0400 Subject: [PATCH 11/54] =?UTF-8?q?=F0=9F=9A=B8=20Use=20Tool=200=20for=20G30?= =?UTF-8?q?=20(#24511)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/probe/G30.cpp | 74 ++++++++++++++++++++-------------- 1 file changed, 43 insertions(+), 31 deletions(-) diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index a16853bdf8..eae04f2817 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -33,6 +33,10 @@ #include "../../feature/probe_temp_comp.h" #endif +#if HAS_MULTI_HOTEND + #include "../../module/tool_change.h" +#endif + #if ENABLED(DWIN_LCD_PROUI) #include "../../lcd/marlinui.h" #endif @@ -49,6 +53,11 @@ */ void GcodeSuite::G30() { + #if HAS_MULTI_HOTEND + const uint8_t old_tool_index = active_extruder; + tool_change(0); + #endif + const xy_pos_t pos = { parser.linearval('X', current_position.x + probe.offset_xy.x), parser.linearval('Y', current_position.y + probe.offset_xy.y) }; @@ -57,40 +66,43 @@ void GcodeSuite::G30() { SERIAL_ECHOLNF(GET_EN_TEXT_F(MSG_ZPROBE_OUT)); LCD_MESSAGE(MSG_ZPROBE_OUT); #endif - return; } - - // Disable leveling so the planner won't mess with us - TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); - - remember_feedrate_scaling_off(); - - TERN_(DWIN_LCD_PROUI, process_subcommands_now(F("G28O"))); - - const ProbePtRaise raise_after = parser.boolval('E', true) ? PROBE_PT_STOW : PROBE_PT_NONE; - - TERN_(HAS_PTC, ptc.set_enabled(!parser.seen('C') || parser.value_bool())); - const float measured_z = probe.probe_at_point(pos, raise_after, 1); - TERN_(HAS_PTC, ptc.set_enabled(true)); - if (!isnan(measured_z)) { - SERIAL_ECHOLNPGM("Bed X: ", pos.x, " Y: ", pos.y, " Z: ", measured_z); - #if ENABLED(DWIN_LCD_PROUI) - char msg[31], str_1[6], str_2[6], str_3[6]; - sprintf_P(msg, PSTR("X:%s, Y:%s, Z:%s"), - dtostrf(pos.x, 1, 1, str_1), - dtostrf(pos.y, 1, 1, str_2), - dtostrf(measured_z, 1, 2, str_3) - ); - ui.set_status(msg); - #endif + else { + // Disable leveling so the planner won't mess with us + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); + + remember_feedrate_scaling_off(); + + TERN_(DWIN_LCD_PROUI, process_subcommands_now(F("G28O"))); + + const ProbePtRaise raise_after = parser.boolval('E', true) ? PROBE_PT_STOW : PROBE_PT_NONE; + + TERN_(HAS_PTC, ptc.set_enabled(!parser.seen('C') || parser.value_bool())); + const float measured_z = probe.probe_at_point(pos, raise_after, 1); + TERN_(HAS_PTC, ptc.set_enabled(true)); + if (!isnan(measured_z)) { + SERIAL_ECHOLNPGM("Bed X: ", pos.x, " Y: ", pos.y, " Z: ", measured_z); + #if ENABLED(DWIN_LCD_PROUI) + char msg[31], str_1[6], str_2[6], str_3[6]; + sprintf_P(msg, PSTR("X:%s, Y:%s, Z:%s"), + dtostrf(pos.x, 1, 1, str_1), + dtostrf(pos.y, 1, 1, str_2), + dtostrf(measured_z, 1, 2, str_3) + ); + ui.set_status(msg); + #endif + } + + restore_feedrate_and_scaling(); + + if (raise_after == PROBE_PT_STOW) + probe.move_z_after_probing(); + + report_current_position(); } - restore_feedrate_and_scaling(); - - if (raise_after == PROBE_PT_STOW) - probe.move_z_after_probing(); - - report_current_position(); + // Restore the active tool + TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index)); } #endif // HAS_BED_PROBE From d726f641a571b13b7d55307bf50a253a49883d25 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 20 Jul 2022 16:26:33 -0500 Subject: [PATCH 12/54] EXP header pin numbers redux (#24525) Followup to 504fec98 --- Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 28 ++-- Marlin/src/pins/esp32/pins_PANDA_common.h | 20 +-- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 28 ++-- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 48 +++--- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 48 +++--- Marlin/src/pins/lpc1768/pins_EMOTRONIC.h | 32 ++-- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 28 ++-- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 26 ++-- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 28 ++-- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 14 +- Marlin/src/pins/ramps/pins_RAMPS.h | 68 ++++---- Marlin/src/pins/ramps/pins_RAMPS_PLUS.h | 28 ++-- Marlin/src/pins/ramps/pins_ZRIB_V53.h | 28 ++-- Marlin/src/pins/sam/pins_RAMPS_FD_V1.h | 28 ++-- Marlin/src/pins/sam/pins_RAMPS_SMART.h | 28 ++-- Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 28 ++-- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 28 ++-- .../src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h | 44 +++--- Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h | 44 +++--- Marlin/src/pins/sanguino/pins_ZMIB_V2.h | 14 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 32 ++-- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 147 +++++++++--------- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 28 ++-- .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 14 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 70 ++++----- Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h | 28 ++-- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 28 ++-- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 14 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 28 ++-- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 42 ++--- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h | 18 +-- Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h | 40 ++--- Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h | 14 +- Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h | 24 +-- Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h | 28 ++-- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 30 ++-- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 98 ++++++------ Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 26 ++-- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 28 ++-- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 36 ++--- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 28 ++-- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 28 ++-- .../pins/stm32f4/pins_FYSETC_CHEETAH_V20.h | 28 ++-- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 28 ++-- .../pins/stm32f4/pins_MKS_MONSTER8_common.h | 28 ++-- .../stm32f4/pins_MKS_ROBIN_NANO_V3_common.h | 28 ++-- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 28 ++-- .../src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h | 14 +- Marlin/src/pins/stm32f4/pins_VAKE403D.h | 28 ++-- .../pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h | 94 +++++------ .../pins/stm32h7/pins_BTT_SKR_V3_0_common.h | 44 +++--- 51 files changed, 894 insertions(+), 893 deletions(-) diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index 3762f64033..04210bb234 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -128,23 +128,23 @@ * EXP1 EXP2 */ -#define EXP1_08_PIN 17 -#define EXP1_07_PIN 15 -#define EXP1_06_PIN 16 -#define EXP1_05_PIN 0 -#define EXP1_04_PIN 4 -#define EXP1_03_PIN 21 -#define EXP1_02_PIN 13 #define EXP1_01_PIN 149 +#define EXP1_02_PIN 13 +#define EXP1_03_PIN 21 +#define EXP1_04_PIN 4 +#define EXP1_05_PIN 0 +#define EXP1_06_PIN 16 +#define EXP1_07_PIN 15 +#define EXP1_08_PIN 17 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN 34 -#define EXP2_06_PIN 23 -#define EXP2_05_PIN 12 -#define EXP2_04_PIN 5 -#define EXP2_03_PIN 14 -#define EXP2_02_PIN 18 #define EXP2_01_PIN 19 +#define EXP2_02_PIN 18 +#define EXP2_03_PIN 14 +#define EXP2_04_PIN 5 +#define EXP2_05_PIN 12 +#define EXP2_06_PIN 23 +#define EXP2_07_PIN 34 +#define EXP2_08_PIN -1 // RESET // // MicroSD card diff --git a/Marlin/src/pins/esp32/pins_PANDA_common.h b/Marlin/src/pins/esp32/pins_PANDA_common.h index dfd0525521..afc9a78aec 100644 --- a/Marlin/src/pins/esp32/pins_PANDA_common.h +++ b/Marlin/src/pins/esp32/pins_PANDA_common.h @@ -90,19 +90,19 @@ * ------ ------ * EXP2 EXP1 */ -#define EXP1_05_PIN 14 -#define EXP1_04_PIN 27 -#define EXP1_03_PIN 26 -#define EXP1_02_PIN 12 #define EXP1_01_PIN 129 +#define EXP1_02_PIN 12 +#define EXP1_03_PIN 26 +#define EXP1_04_PIN 27 +#define EXP1_05_PIN 14 -#define EXP2_07_PIN 2 // ? -#define EXP2_06_PIN 23 // ? -#define EXP2_05_PIN 32 -#define EXP2_04_PIN 5 // ? -#define EXP2_03_PIN 33 -#define EXP2_02_PIN 18 // ? #define EXP2_01_PIN 19 // ? +#define EXP2_02_PIN 18 // ? +#define EXP2_03_PIN 33 +#define EXP2_04_PIN 5 // ? +#define EXP2_05_PIN 32 +#define EXP2_06_PIN 23 // ? +#define EXP2_07_PIN 2 // ? // // SD Card diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index ba042e3bf5..d11224315b 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -66,23 +66,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN -1 // NC -#define EXP1_07_PIN -1 // NC -#define EXP1_06_PIN -1 // NC -#define EXP1_05_PIN P0_15 -#define EXP1_04_PIN P0_16 -#define EXP1_03_PIN P0_18 -#define EXP1_02_PIN P2_11 #define EXP1_01_PIN P1_30 +#define EXP1_02_PIN P2_11 +#define EXP1_03_PIN P0_18 +#define EXP1_04_PIN P0_16 +#define EXP1_05_PIN P0_15 +#define EXP1_06_PIN -1 // NC +#define EXP1_07_PIN -1 // NC +#define EXP1_08_PIN -1 // NC -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN P1_31 -#define EXP2_06_PIN P0_18 -#define EXP2_05_PIN P3_25 -#define EXP2_04_PIN P1_23 -#define EXP2_03_PIN P3_26 -#define EXP2_02_PIN P0_15 #define EXP2_01_PIN P0_17 +#define EXP2_02_PIN P0_15 +#define EXP2_03_PIN P3_26 +#define EXP2_04_PIN P1_23 +#define EXP2_05_PIN P3_25 +#define EXP2_06_PIN P0_18 +#define EXP2_07_PIN P1_31 +#define EXP2_08_PIN -1 // RESET /** * LCD / Controller diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 4ea4687507..031a42f798 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -199,23 +199,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN P1_23 -#define EXP1_07_PIN P1_22 -#define EXP1_06_PIN P1_21 -#define EXP1_05_PIN P1_20 -#define EXP1_04_PIN P1_19 -#define EXP1_03_PIN P1_18 -#define EXP1_02_PIN P0_28 #define EXP1_01_PIN P1_30 +#define EXP1_02_PIN P0_28 +#define EXP1_03_PIN P1_18 +#define EXP1_04_PIN P1_19 +#define EXP1_05_PIN P1_20 +#define EXP1_06_PIN P1_21 +#define EXP1_07_PIN P1_22 +#define EXP1_08_PIN P1_23 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN P1_31 -#define EXP2_06_PIN P0_18 -#define EXP2_05_PIN P3_25 -#define EXP2_04_PIN P0_16 -#define EXP2_03_PIN P3_26 -#define EXP2_02_PIN P0_15 #define EXP2_01_PIN P0_17 +#define EXP2_02_PIN P0_15 +#define EXP2_03_PIN P3_26 +#define EXP2_04_PIN P0_16 +#define EXP2_05_PIN P3_25 +#define EXP2_06_PIN P0_18 +#define EXP2_07_PIN P1_31 +#define EXP2_08_PIN -1 #if HAS_WIRED_LCD #if ENABLED(ANET_FULL_GRAPHICS_LCD_ALT_WIRING) @@ -239,11 +239,11 @@ * * BEFORE AFTER * ------ ------ - * (CLK) | 1 2 | (BEEPER) (BEEPER) | 1 2 | -- - * -- | 3 4 | (BTN_ENC) (BTN_ENC) | 3 4 | (CLK) - * (SID) 5 6 | (BTN_EN1) (BTN_EN1) 5 6 | (SID) - * (CS) | 7 8 | (BTN_EN2) (BTN_EN2) | 7 8 | (CS) - * GND | 9 10 | 5V GND | 9 10 | 5V + * (CLK) | 1 2 | (BEEPER) (BEEPER) |10 9 | -- + * -- | 3 4 | (BTN_ENC) (BTN_ENC) | 8 7 | (CLK) + * (SID) 5 6 | (BTN_EN1) (BTN_EN1) 6 5 | (SID) + * (CS) | 7 8 | (BTN_EN2) (BTN_EN2) | 4 3 | (CS) + * GND | 9 10 | 5V GND | 2 1 | 5V * ------ ------ * LCD LCD */ @@ -274,11 +274,11 @@ * * BEFORE AFTER * ______ ______ - * | 1 2 | (MOSI) (MOSI) | 1 2 | -- - * (BTN_ENC) | 3 4 | (SCK) (BTN_ENC) | 3 4 | (SCK) - * (BTN_EN1) 5 6 | (SID) (BTN_EN1) 5 6 | (SID) - * (BTN_EN2) | 7 8 | (CS) (BTN_EN2) | 7 8 | (CS) - * 5V | 9 10 | GND GND | 9 10 | 5V + * | 1 2 | (MOSI) (MOSI) |10 9 | -- + * (BTN_ENC) | 3 4 | (SCK) (BTN_ENC) | 8 7 | (SCK) + * (BTN_EN1) 5 6 | (SID) (BTN_EN1) 6 5 | (SID) + * (BTN_EN2) | 7 8 | (CS) (BTN_EN2) | 4 3 | (CS) + * 5V | 9 10 | GND GND | 2 1 | 5V * ------ ------ * LCD LCD */ diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 8f0f46ad85..209529cbe1 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -254,23 +254,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN P1_23 -#define EXP1_07_PIN P1_22 -#define EXP1_06_PIN P1_21 -#define EXP1_05_PIN P1_20 -#define EXP1_04_PIN P1_19 -#define EXP1_03_PIN P1_18 -#define EXP1_02_PIN P0_28 #define EXP1_01_PIN P1_30 +#define EXP1_02_PIN P0_28 +#define EXP1_03_PIN P1_18 +#define EXP1_04_PIN P1_19 +#define EXP1_05_PIN P1_20 +#define EXP1_06_PIN P1_21 +#define EXP1_07_PIN P1_22 +#define EXP1_08_PIN P1_23 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN P1_31 -#define EXP2_06_PIN P0_18 -#define EXP2_05_PIN P3_25 -#define EXP2_04_PIN P0_16 -#define EXP2_03_PIN P3_26 -#define EXP2_02_PIN P0_15 #define EXP2_01_PIN P0_17 +#define EXP2_02_PIN P0_15 +#define EXP2_03_PIN P3_26 +#define EXP2_04_PIN P0_16 +#define EXP2_05_PIN P3_25 +#define EXP2_06_PIN P0_18 +#define EXP2_07_PIN P1_31 +#define EXP2_08_PIN -1 // RESET #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI @@ -300,11 +300,11 @@ * * BEFORE AFTER * ------ ------ - * (BEEPER) | 1 2 | (CLK) (BEEPER) | 1 2 | (CLK) - * (BTN_ENC) | 3 4 | -- (BTN_ENC) | 3 4 | -- - * (BTN_EN1) 5 6 | (SID) (BTN_EN1) 5 6 | (SID) - * (BTN_EN2) | 7 8 | (CS) (BTN_EN2) | 7 8 | (CS) - * 5V | 9 10 | GND GND | 9 10 | 5V + * (BEEPER) | 1 2 | (CLK) (BEEPER) |10 9 | (CLK) + * (BTN_ENC) | 3 4 | -- (BTN_ENC) | 8 7 | -- + * (BTN_EN1) 5 6 | (SID) (BTN_EN1) 6 5 | (SID) + * (BTN_EN2) | 7 8 | (CS) (BTN_EN2) | 4 3 | (CS) + * 5V | 9 10 | GND GND | 2 1 | 5V * ------ ------ * LCD LCD */ @@ -336,11 +336,11 @@ * * BEFORE AFTER * ------ ------ - * (BEEPER) | 1 2 | (CLK) (BEEPER) | 1 2 | -- - * (BTN_ENC) | 3 4 | -- (BTN_ENC) | 3 4 | (CLK) - * (BTN_EN1) 5 6 | (SID) (BTN_EN1) 5 6 | (SID) - * (BTN_EN2) | 7 8 | (CS) (BTN_EN2) | 7 8 | (CS) - * 5V | 9 10 | GND GND | 9 10 | 5V + * (BEEPER) | 1 2 | (CLK) (BEEPER) |10 9 | -- + * (BTN_ENC) | 3 4 | -- (BTN_ENC) | 8 7 | (CLK) + * (BTN_EN1) 5 6 | (SID) (BTN_EN1) 6 5 | (SID) + * (BTN_EN2) | 7 8 | (CS) (BTN_EN2) | 4 3 | (CS) + * 5V | 9 10 | GND GND | 2 1 | 5V * ------ ------ * LCD LCD */ diff --git a/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h b/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h index 59b5068eeb..6e1ea403b1 100644 --- a/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h +++ b/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h @@ -91,25 +91,25 @@ // // Extension ports // -#define EXP1_10_PIN P0_28 // SCL0 -#define EXP1_09_PIN P0_27 // SDA0 -#define EXP1_08_PIN P0_16 // SSEL0 -#define EXP1_07_PIN P0_15 // SCK0 -#define EXP1_06_PIN P0_18 // MOSI0 -#define EXP1_05_PIN P0_17 // MISO0 -#define EXP1_04_PIN P1_31 -#define EXP1_03_PIN P1_30 -#define EXP1_02_PIN P0_02 // TX0 #define EXP1_01_PIN P0_03 // RX0 +#define EXP1_02_PIN P0_02 // TX0 +#define EXP1_03_PIN P1_30 +#define EXP1_04_PIN P1_31 +#define EXP1_05_PIN P0_17 // MISO0 +#define EXP1_06_PIN P0_18 // MOSI0 +#define EXP1_07_PIN P0_15 // SCK0 +#define EXP1_08_PIN P0_16 // SSEL0 +#define EXP1_09_PIN P0_27 // SDA0 +#define EXP1_10_PIN P0_28 // SCL0 -#define EXP2_08_PIN P1_27 -#define EXP2_07_PIN P1_26 -#define EXP2_06_PIN P1_29 -#define EXP2_05_PIN P1_28 -#define EXP2_04_PIN P0_01 // SCL1 -#define EXP2_03_PIN P0_00 // SDA1 -#define EXP2_02_PIN P0_11 #define EXP2_01_PIN P0_10 +#define EXP2_02_PIN P0_11 +#define EXP2_03_PIN P0_00 // SDA1 +#define EXP2_04_PIN P0_01 // SCL1 +#define EXP2_05_PIN P1_28 +#define EXP2_06_PIN P1_29 +#define EXP2_07_PIN P1_26 +#define EXP2_08_PIN P1_27 // // SD Support diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 2ffaef949c..4e9f98c852 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -239,23 +239,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN P1_22 -#define EXP1_07_PIN P1_00 -#define EXP1_06_PIN P0_17 -#define EXP1_05_PIN P0_15 -#define EXP1_04_PIN P0_16 -#define EXP1_03_PIN P0_18 -#define EXP1_02_PIN P1_30 #define EXP1_01_PIN P1_31 +#define EXP1_02_PIN P1_30 +#define EXP1_03_PIN P0_18 +#define EXP1_04_PIN P0_16 +#define EXP1_05_PIN P0_15 +#define EXP1_06_PIN P0_17 +#define EXP1_07_PIN P1_00 +#define EXP1_08_PIN P1_22 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN P0_27 -#define EXP2_06_PIN P0_09 -#define EXP2_05_PIN P3_26 -#define EXP2_04_PIN P0_28 -#define EXP2_03_PIN P3_25 -#define EXP2_02_PIN P0_07 #define EXP2_01_PIN P0_08 +#define EXP2_02_PIN P0_07 +#define EXP2_03_PIN P3_25 +#define EXP2_04_PIN P0_28 +#define EXP2_05_PIN P3_26 +#define EXP2_06_PIN P0_09 +#define EXP2_07_PIN P0_27 +#define EXP2_08_PIN -1 // RESET #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index d8dae61d94..dbaafb89cc 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -194,14 +194,14 @@ * ------ * EXP */ -#define EXP1_08_PIN P0_18 -#define EXP1_07_PIN P0_17 -#define EXP1_06_PIN P0_15 -#define EXP1_05_PIN P0_20 -#define EXP1_04_PIN -1 -#define EXP1_03_PIN P0_19 -#define EXP1_02_PIN P0_16 #define EXP1_01_PIN P2_08 +#define EXP1_02_PIN P0_16 +#define EXP1_03_PIN P0_19 +#define EXP1_04_PIN -1 +#define EXP1_05_PIN P0_20 +#define EXP1_06_PIN P0_15 +#define EXP1_07_PIN P0_17 +#define EXP1_08_PIN P0_18 #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING @@ -210,12 +210,12 @@ /** * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo - * ------ ------ RX 8 --> 5 P0_15 - * -- | 1 2 | -- (BEEPER) P2_08 | 1 2 | P0_16 (BTN_ENC) TX 7 --> 9 P0_16 - * (SKR_TX1) RX | 3 4 | TX (SKR_RX1) (BTN_EN1) P0_19 | 3 4 | RESET BEEPER 5 --> 10 P2_08 - * (BTN_ENC) ENT 5 6 | BEEPER (BTN_EN2) P0_20 5 6 | P0_15 (LCD_D4) - * (BTN_E2) B | 7 8 | A (BTN_E1) (LCD_RS) P0_17 | 7 8 | P0_18 (LCD_EN) - * GND | 9 10 | 5V GND | 9 10 | 5V + * ------ ------ RX 3 --> 5 P0_15 + * -- | 1 2 | -- (BEEPER) P2_08 |10 9 | P0_16 (BTN_ENC) TX 4 --> 9 P0_16 + * (SKR_TX1) RX | 3 4 | TX (SKR_RX1) (BTN_EN1) P0_19 | 8 7 | RESET BEEPER 6 --> 10 P2_08 + * (BTN_ENC) ENT 5 6 | BEEPER (BTN_EN2) P0_20 6 5 | P0_15 (LCD_D4) + * (BTN_E2) B | 7 8 | A (BTN_E1) (LCD_RS) P0_17 | 4 3 | P0_18 (LCD_EN) + * GND | 9 10 | 5V GND | 2 1 | 5V * ------ ------ */ diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index d137bdae91..2f25d8b5fd 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -278,23 +278,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN P1_22 -#define EXP1_07_PIN P1_00 -#define EXP1_06_PIN P0_17 -#define EXP1_05_PIN P0_15 -#define EXP1_04_PIN P0_16 -#define EXP1_03_PIN P0_18 -#define EXP1_02_PIN P1_30 #define EXP1_01_PIN P1_31 +#define EXP1_02_PIN P1_30 +#define EXP1_03_PIN P0_18 +#define EXP1_04_PIN P0_16 +#define EXP1_05_PIN P0_15 +#define EXP1_06_PIN P0_17 +#define EXP1_07_PIN P1_00 +#define EXP1_08_PIN P1_22 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN P0_27 -#define EXP2_06_PIN P0_09 -#define EXP2_05_PIN P3_26 -#define EXP2_04_PIN P0_28 -#define EXP2_03_PIN P3_25 -#define EXP2_02_PIN P0_07 #define EXP2_01_PIN P0_08 +#define EXP2_02_PIN P0_07 +#define EXP2_03_PIN P3_25 +#define EXP2_04_PIN P0_28 +#define EXP2_05_PIN P3_26 +#define EXP2_06_PIN P0_09 +#define EXP2_07_PIN P0_27 +#define EXP2_08_PIN -1 // RESET #if IS_TFTGLCD_PANEL diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index f6d8e40844..f794e178f9 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -171,14 +171,14 @@ * A remote SD card is currently not supported because the pins routed to the EXP2 * connector are shared with the onboard SD card. */ -#define EXP1_08_PIN P0_18 -#define EXP1_07_PIN P0_16 -#define EXP1_06_PIN P0_15 -#define EXP1_05_PIN P3_25 -#define EXP1_04_PIN P2_11 -#define EXP1_03_PIN P3_26 -#define EXP1_02_PIN P1_30 #define EXP1_01_PIN P1_31 +#define EXP1_02_PIN P1_30 +#define EXP1_03_PIN P3_26 +#define EXP1_04_PIN P2_11 +#define EXP1_05_PIN P3_25 +#define EXP1_06_PIN P0_15 +#define EXP1_07_PIN P0_16 +#define EXP1_08_PIN P0_18 #if ENABLED(CR10_STOCKDISPLAY) /** ------ diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index a9824fbb8d..a0edb01a2a 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -515,18 +515,18 @@ */ #ifndef EXP1_08_PIN - #define EXP1_08_PIN AUX4_13_PIN - #define EXP1_07_PIN AUX4_14_PIN - #define EXP1_06_PIN AUX4_15_PIN - #define EXP1_05_PIN AUX4_16_PIN - #define EXP1_04_PIN AUX4_18_PIN #define EXP1_03_PIN AUX4_17_PIN + #define EXP1_04_PIN AUX4_18_PIN + #define EXP1_05_PIN AUX4_16_PIN + #define EXP1_06_PIN AUX4_15_PIN + #define EXP1_07_PIN AUX4_14_PIN + #define EXP1_08_PIN AUX4_13_PIN - #define EXP2_07_PIN AUX3_02_PIN - #define EXP2_06_PIN AUX3_04_PIN - #define EXP2_04_PIN AUX3_06_PIN - #define EXP2_02_PIN AUX3_05_PIN #define EXP2_01_PIN AUX3_03_PIN + #define EXP2_02_PIN AUX3_05_PIN + #define EXP2_04_PIN AUX3_06_PIN + #define EXP2_06_PIN AUX3_04_PIN + #define EXP2_07_PIN AUX3_02_PIN #if ENABLED(G3D_PANEL) /** Gadgets3D Smart Adapter @@ -539,12 +539,12 @@ * ------ ------ * EXP1 EXP2 */ - #define EXP1_02_PIN AUX4_12_PIN #define EXP1_01_PIN AUX4_11_PIN + #define EXP1_02_PIN AUX4_12_PIN - #define EXP2_08_PIN AUX4_07_PIN - #define EXP2_05_PIN AUX4_09_PIN #define EXP2_03_PIN AUX4_10_PIN + #define EXP2_05_PIN AUX4_09_PIN + #define EXP2_08_PIN AUX4_07_PIN #else @@ -558,17 +558,17 @@ * ------ ------ * EXP1 EXP2 */ - #define EXP1_02_PIN AUX4_10_PIN #define EXP1_01_PIN AUX4_09_PIN + #define EXP1_02_PIN AUX4_10_PIN #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) - #define EXP2_08_PIN -1 // RESET - #define EXP2_05_PIN AUX4_12_PIN #define EXP2_03_PIN AUX4_11_PIN + #define EXP2_05_PIN AUX4_12_PIN + #define EXP2_08_PIN -1 // RESET #else - #define EXP2_08_PIN AUX4_07_PIN - #define EXP2_05_PIN AUX4_11_PIN #define EXP2_03_PIN AUX4_12_PIN + #define EXP2_05_PIN AUX4_11_PIN + #define EXP2_08_PIN AUX4_07_PIN #endif #endif @@ -898,28 +898,28 @@ * * Board Display * ------ ------ - * (MISO) 50 | 1 2 | 52 (SCK) 5V | 1 2 | GND - * (BTN_EN2) 33 | 3 4 | 53 (SD_CS) RESET | 3 4 | (SD_DET) - * (BTN_EN1) 31 5 6 | 51 (MOSI) (MOSI) 5 6 | (LCD_CS) - * (SD_DET) 49 | 7 8 | RESET (SD_CS) | 7 8 | (MOD_RESET) - * GND | 9 10 | -- (SCK) | 9 10 | (MISO) + * (MISO) 50 | 1 2 | 52 (SCK) 5V |10 9 | GND + * (LCD_CS) 33 | 3 4 | 53 (SD_CS) RESET | 8 7 | (SD_DET) + * 31 5 6 | 51 (MOSI) (MOSI) 6 5 | (LCD_CS) + * (SD_DET) 49 | 7 8 | RESET (SD_CS) | 4 3 | (MOD_RESET) + * GND | 9 10 | -- (SCK) | 2 1 | (MISO) * ------ ------ - * EXP2 + * EXP2 EXP1 * * Needs custom cable: * * Board Adapter Display - * _________ - * EXP2-1 ----------- EXP1-10 - * EXP2-2 ----------- EXP1-9 - * EXP2-4 ----------- EXP1-8 - * EXP2-4 ----------- EXP1-7 - * EXP2-3 ----------- EXP1-6 - * EXP2-6 ----------- EXP1-5 - * EXP2-7 ----------- EXP1-4 - * EXP2-8 ----------- EXP1-3 - * EXP2-1 ----------- EXP1-2 - * EXP1-10 ---------- EXP1-1 + * ---------------------------------- + * EXP2-1 <--diode--- EXP1-1 MISO + * EXP2-2 ----------- EXP1-2 SCK + * EXP2-4 ----------- EXP1-3 MOD_RST + * EXP2-4 ----------- EXP1-4 SD_CS + * EXP2-3 ----------- EXP1-5 LCD_CS + * EXP2-6 ----------- EXP1-6 MOSI + * EXP2-7 ----------- EXP1-7 SD DET + * EXP2-8 ----------- EXP1-8 RESET + * EXP2-1 ----------- EXP1-9 MISO->GND + * EXP1-10 ---------- EXP1-10 5V * * NOTE: The MISO pin should not get a 5V signal. * To fix, insert a 1N4148 diode in the MISO line. diff --git a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h index f4e811b8e6..8ccb14c866 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h @@ -73,22 +73,22 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN 44 -#define EXP1_07_PIN 42 -#define EXP1_06_PIN 23 -#define EXP1_05_PIN 33 -#define EXP1_04_PIN 41 -#define EXP1_03_PIN 31 -#define EXP1_02_PIN 35 #define EXP1_01_PIN 37 +#define EXP1_02_PIN 35 +#define EXP1_03_PIN 31 +#define EXP1_04_PIN 41 +#define EXP1_05_PIN 33 +#define EXP1_06_PIN 23 +#define EXP1_07_PIN 42 +#define EXP1_08_PIN 44 -#define EXP2_08_PIN 27 -#define EXP2_07_PIN 49 -#define EXP2_06_PIN 51 -#define EXP2_05_PIN 25 -#define EXP2_04_PIN 53 -#define EXP2_03_PIN 29 -#define EXP2_02_PIN 52 #define EXP2_01_PIN 50 +#define EXP2_02_PIN 52 +#define EXP2_03_PIN 29 +#define EXP2_04_PIN 53 +#define EXP2_05_PIN 25 +#define EXP2_06_PIN 51 +#define EXP2_07_PIN 49 +#define EXP2_08_PIN 27 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V53.h b/Marlin/src/pins/ramps/pins_ZRIB_V53.h index 38b8e09b03..cae71f7a8f 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V53.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V53.h @@ -309,23 +309,23 @@ */ #ifndef EXP1_08_PIN - #define EXP1_08_PIN 29 - #define EXP1_07_PIN 27 - #define EXP1_06_PIN 25 - #define EXP1_05_PIN 23 - #define EXP1_04_PIN 16 - #define EXP1_03_PIN 17 - #define EXP1_02_PIN 35 #define EXP1_01_PIN 37 + #define EXP1_02_PIN 35 + #define EXP1_03_PIN 17 + #define EXP1_04_PIN 16 + #define EXP1_05_PIN 23 + #define EXP1_06_PIN 25 + #define EXP1_07_PIN 27 + #define EXP1_08_PIN 29 - #define EXP2_08_PIN 41 - #define EXP2_07_PIN 49 - #define EXP2_06_PIN XS6_05_PIN - #define EXP2_05_PIN 33 - #define EXP2_04_PIN 53 - #define EXP2_03_PIN 31 - #define EXP2_02_PIN XS6_03_PIN #define EXP2_01_PIN XS6_07_PIN + #define EXP2_02_PIN XS6_03_PIN + #define EXP2_03_PIN 31 + #define EXP2_04_PIN 53 + #define EXP2_05_PIN 33 + #define EXP2_06_PIN XS6_05_PIN + #define EXP2_07_PIN 49 + #define EXP2_08_PIN 41 #endif ////////////////////////// diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index e734a08943..00eba994a8 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -143,23 +143,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN 17 -#define EXP1_07_PIN 16 -#define EXP1_06_PIN 23 -#define EXP1_05_PIN 25 -#define EXP1_04_PIN 27 -#define EXP1_03_PIN 29 -#define EXP1_02_PIN 35 #define EXP1_01_PIN 37 +#define EXP1_02_PIN 35 +#define EXP1_03_PIN 29 +#define EXP1_04_PIN 27 +#define EXP1_05_PIN 25 +#define EXP1_06_PIN 23 +#define EXP1_07_PIN 16 +#define EXP1_08_PIN 17 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN 49 -#define EXP2_06_PIN 75 -#define EXP2_05_PIN 33 -#define EXP2_04_PIN 4 -#define EXP2_03_PIN 31 -#define EXP2_02_PIN 76 #define EXP2_01_PIN 74 +#define EXP2_02_PIN 76 +#define EXP2_03_PIN 31 +#define EXP2_04_PIN 4 +#define EXP2_05_PIN 33 +#define EXP2_06_PIN 75 +#define EXP2_07_PIN 49 +#define EXP2_08_PIN -1 // // LCD / Controller diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index 47bc8bbaa6..b02ddef166 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -118,23 +118,23 @@ * ------ ------ * EXP1 EXP2 */ - #define EXP1_08_PIN 44 - #define EXP1_07_PIN 42 - #define EXP1_06_PIN 23 - #define EXP1_05_PIN 33 - #define EXP1_04_PIN 41 - #define EXP1_03_PIN 31 - #define EXP1_02_PIN 35 #define EXP1_01_PIN 37 + #define EXP1_02_PIN 35 + #define EXP1_03_PIN 31 + #define EXP1_04_PIN 41 + #define EXP1_05_PIN 33 + #define EXP1_06_PIN 23 + #define EXP1_07_PIN 42 + #define EXP1_08_PIN 44 - #define EXP2_08_PIN 27 - #define EXP2_07_PIN 49 - #define EXP2_06_PIN 51 - #define EXP2_05_PIN 25 - #define EXP2_04_PIN 53 - #define EXP2_03_PIN 29 - #define EXP2_02_PIN 52 #define EXP2_01_PIN 50 + #define EXP2_02_PIN 52 + #define EXP2_03_PIN 29 + #define EXP2_04_PIN 53 + #define EXP2_05_PIN 25 + #define EXP2_06_PIN 51 + #define EXP2_07_PIN 49 + #define EXP2_08_PIN 27 #endif diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 4f990a0aed..f8ea65a369 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -193,23 +193,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN 53 -#define EXP1_07_PIN 52 -#define EXP1_06_PIN 50 -#define EXP1_05_PIN 48 -#define EXP1_04_PIN 63 -#define EXP1_03_PIN 64 -#define EXP1_02_PIN 40 #define EXP1_01_PIN 62 +#define EXP1_02_PIN 40 +#define EXP1_03_PIN 64 +#define EXP1_04_PIN 63 +#define EXP1_05_PIN 48 +#define EXP1_06_PIN 50 +#define EXP1_07_PIN 52 +#define EXP1_08_PIN 53 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN 51 -#define EXP2_06_PIN 75 // MOSI -#define EXP2_05_PIN 42 -#define EXP2_04_PIN 10 -#define EXP2_03_PIN 44 -#define EXP2_02_PIN 76 // SCK #define EXP2_01_PIN 74 // MISO +#define EXP2_02_PIN 76 // SCK +#define EXP2_03_PIN 44 +#define EXP2_04_PIN 10 +#define EXP2_05_PIN 42 +#define EXP2_06_PIN 75 // MOSI +#define EXP2_07_PIN 51 +#define EXP2_08_PIN -1 // RESET // // LCD / Controller diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 37e7f20976..58cb3f7a75 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -183,23 +183,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN 53 -#define EXP1_07_PIN 52 -#define EXP1_06_PIN 50 -#define EXP1_05_PIN 48 -#define EXP1_04_PIN 63 -#define EXP1_03_PIN 64 -#define EXP1_02_PIN 40 #define EXP1_01_PIN 62 +#define EXP1_02_PIN 40 +#define EXP1_03_PIN 64 +#define EXP1_04_PIN 63 +#define EXP1_05_PIN 48 +#define EXP1_06_PIN 50 +#define EXP1_07_PIN 52 +#define EXP1_08_PIN 53 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN 51 -#define EXP2_06_PIN 75 // MOSI -#define EXP2_05_PIN 42 -#define EXP2_04_PIN 10 -#define EXP2_03_PIN 44 -#define EXP2_02_PIN 76 // SCK #define EXP2_01_PIN 74 // MISO +#define EXP2_02_PIN 76 // SCK +#define EXP2_03_PIN 44 +#define EXP2_04_PIN 10 +#define EXP2_05_PIN 42 +#define EXP2_06_PIN 75 // MOSI +#define EXP2_07_PIN 51 +#define EXP2_08_PIN -1 // RESET // // LCD / Controller diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h index a9199ba84c..a3f98e388a 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h @@ -166,33 +166,33 @@ * BTN_ENCODER 40 KILL_PIN 49 */ -#define EXP1_08_PIN 39 -#define EXP1_07_PIN 38 -#define EXP1_06_PIN 37 -#define EXP1_05_PIN 36 -#define EXP1_04_PIN 34 -#define EXP1_03_PIN 35 -#define EXP1_02_PIN 40 #define EXP1_01_PIN 41 +#define EXP1_02_PIN 40 +#define EXP1_03_PIN 35 +#define EXP1_04_PIN 34 +#define EXP1_05_PIN 36 +#define EXP1_06_PIN 37 +#define EXP1_07_PIN 38 +#define EXP1_08_PIN 39 -#define EXP2_10_PIN 49 -#define EXP2_07_PIN 44 -#define EXP2_06_PIN 51 -#define EXP2_05_PIN 42 -#define EXP2_04_PIN 53 -#define EXP2_03_PIN 43 -#define EXP2_02_PIN 52 #define EXP2_01_PIN 50 +#define EXP2_02_PIN 52 +#define EXP2_03_PIN 43 +#define EXP2_04_PIN 53 +#define EXP2_05_PIN 42 +#define EXP2_06_PIN 51 +#define EXP2_07_PIN 44 +#define EXP2_10_PIN 49 #if ENABLED(CR10_STOCKDISPLAY) - #define EXP3_03_PIN EXP1_08_PIN - #define EXP3_04_PIN EXP1_07_PIN - #define EXP3_05_PIN EXP1_06_PIN - #define EXP3_06_PIN EXP1_05_PIN - #define EXP3_07_PIN EXP1_04_PIN - #define EXP3_08_PIN EXP1_03_PIN - #define EXP3_09_PIN EXP1_02_PIN - #define EXP3_10_PIN EXP1_01_PIN + #define EXP3_01_PIN EXP1_01_PIN + #define EXP3_02_PIN EXP1_02_PIN + #define EXP3_03_PIN EXP1_03_PIN + #define EXP3_04_PIN EXP1_04_PIN + #define EXP3_05_PIN EXP1_05_PIN + #define EXP3_06_PIN EXP1_06_PIN + #define EXP3_07_PIN EXP1_07_PIN + #define EXP3_08_PIN EXP1_08_PIN #endif /************************************/ diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h index 991b4e1ad8..2343dbcf82 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h @@ -218,33 +218,33 @@ * BTN_ENCODER 40 */ -#define EXP1_08_PIN 39 -#define EXP1_07_PIN 38 -#define EXP1_06_PIN 37 -#define EXP1_05_PIN 36 -#define EXP1_04_PIN 34 -#define EXP1_03_PIN 35 -#define EXP1_02_PIN 40 #define EXP1_01_PIN 41 +#define EXP1_02_PIN 40 +#define EXP1_03_PIN 35 +#define EXP1_04_PIN 34 +#define EXP1_05_PIN 36 +#define EXP1_06_PIN 37 +#define EXP1_07_PIN 38 +#define EXP1_08_PIN 39 -#define EXP2_10_PIN 49 -#define EXP2_07_PIN 44 -#define EXP2_06_PIN 51 -#define EXP2_05_PIN 42 -#define EXP2_04_PIN 53 -#define EXP2_03_PIN 43 -#define EXP2_02_PIN 52 #define EXP2_01_PIN 50 +#define EXP2_02_PIN 52 +#define EXP2_03_PIN 43 +#define EXP2_04_PIN 53 +#define EXP2_05_PIN 42 +#define EXP2_06_PIN 51 +#define EXP2_07_PIN 44 +#define EXP2_10_PIN 49 #if ENABLED(CR10_STOCKDISPLAY) - #define EXP3_03_PIN EXP1_08_PIN - #define EXP3_04_PIN EXP1_07_PIN - #define EXP3_05_PIN EXP1_06_PIN - #define EXP3_06_PIN EXP1_05_PIN - #define EXP3_07_PIN EXP1_04_PIN - #define EXP3_08_PIN EXP1_03_PIN - #define EXP3_09_PIN EXP1_02_PIN - #define EXP3_10_PIN EXP1_01_PIN + #define EXP3_01_PIN EXP1_01_PIN + #define EXP3_02_PIN EXP1_02_PIN + #define EXP3_03_PIN EXP1_03_PIN + #define EXP3_04_PIN EXP1_04_PIN + #define EXP3_05_PIN EXP1_05_PIN + #define EXP3_06_PIN EXP1_06_PIN + #define EXP3_07_PIN EXP1_07_PIN + #define EXP3_08_PIN EXP1_08_PIN #endif /************************************/ diff --git a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h index f61f7dc6bb..4e8731c1cb 100644 --- a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h +++ b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h @@ -171,18 +171,18 @@ * (GND) | 9 10 | (5V) * ------ */ -#define EXP1_08_PIN 2 -#define EXP1_07_PIN 29 +#define EXP1_01_PIN 5 +#define EXP1_02_PIN 7 +#define EXP1_03_PIN 11 +#define EXP1_04_PIN 10 +#define EXP1_05_PIN 12 #ifndef IS_ZMIB_V2 #define EXP1_06_PIN 4 // ZMIB V1 #else #define EXP1_06_PIN 3 // ZMIB V2 #endif -#define EXP1_05_PIN 12 -#define EXP1_04_PIN 10 -#define EXP1_03_PIN 11 -#define EXP1_02_PIN 7 -#define EXP1_01_PIN 5 +#define EXP1_07_PIN 29 +#define EXP1_08_PIN 2 #if ENABLED(ZONESTAR_12864LCD) // diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 4e4efc4f73..f9c9de4f03 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -234,28 +234,28 @@ * * Board Display * ------ ------ - * (SD_DET) PA15 | 1 2 | PB6 (BEEPER) 5V | 1 2 | GND - * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 3 4 | (SD_DET) - * (SD_CS) PA10 5 6 | PB9 (MOSI) 5 6 | (LCD_CS) - * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 7 8 | (MOD_RESET) - * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) + * (SD_DET) PA15 | 1 2 | PB6 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 8 7 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) 6 5 | (LCD_CS) + * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 4 3 | (MOD_RESET) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) * ------ ------ * EXP1 EXP1 * * Needs custom cable: * * Board Adapter Display - * _________ - * EXP1-1 ----------- EXP1-10 - * EXP1-2 ----------- EXP1-9 - * SPI1-4 ----------- EXP1-6 - * EXP1-4 ----------- EXP1-5 - * SP11-3 ----------- EXP1-2 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- EXP1-8 - * EXP1-8 ----------- EXP1-3 - * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-7 + * ---------------------------------- + * EXP1-10 ---------- EXP1-10 5V + * EXP1-9 ----------- EXP1-9 GND + * SPI1-4 ----------- EXP1-6 MOSI + * EXP1-7 ----------- EXP1-5 LCD_CS + * SP11-3 ----------- EXP1-2 SCK + * EXP1-5 ----------- EXP1-4 SD_CS + * EXP1-4 ----------- EXP1-8 RESET + * EXP1-3 ----------- EXP1-3 MOD_RST + * SPI1-1 ----------- EXP1-1 MISO + * EXP1-1 ----------- EXP1-7 SD_DET */ #define CLCD_SPI_BUS 1 // SPI1 connector diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index a81f272f26..537e905e21 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -129,21 +129,21 @@ * EXP1 EXP1 */ #ifdef SKR_MINI_E3_V2 - #define EXP1_9 PA15 - #define EXP1_3 PB15 + #define EXP1_02_PIN PA15 + #define EXP1_08_PIN PB15 #else - #define EXP1_9 PB6 - #define EXP1_3 PB7 + #define EXP1_02_PIN PB6 + #define EXP1_08_PIN PB7 #endif #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI /** * ------ ------ ------ - * (ENT) | 1 2 | (BEEP) | 1 2 | | 1 2 | - * (RX) | 3 4 | (RX) | 3 4 | (TX) RX | 3 4 | TX - * (TX) 5 6 | (ENT) 5 6 | (BEEP) ENT | 5 6 | BEEP - * (B) | 7 8 | (A) (B) | 7 8 | (A) B | 7 8 | A - * GND | 9 10 | (VCC) GND | 9 10 | VCC GND | 9 10 | VCC + * (ENT) | 1 2 | (BEEP) |10 9 | |10 9 | + * (RX) | 3 4 | (RX) | 8 7 | (TX) RX | 8 7 | TX + * (TX) 5 6 | (ENT) 6 5 | (BEEP) ENT | 6 5 | BEEP + * (B) | 7 8 | (A) (B) | 4 3 | (A) B | 4 3 | A + * GND | 9 10 | (VCC) GND | 2 1 | VCC GND | 2 1 | VCC * ------ ------ ------ * EXP1 DWIN DWIN (plug) * @@ -154,8 +154,8 @@ #error "CAUTION! Ender-3 V2 display requires a custom cable. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" #endif - #define BEEPER_PIN EXP1_9 - #define BTN_EN1 EXP1_3 + #define BEEPER_PIN EXP1_02_PIN + #define BTN_EN1 EXP1_08_PIN #define BTN_EN2 PB8 #define BTN_ENC PB5 @@ -164,13 +164,13 @@ #if ENABLED(CR10_STOCKDISPLAY) #define BEEPER_PIN PB5 - #define BTN_ENC EXP1_9 + #define BTN_ENC EXP1_02_PIN #define BTN_EN1 PA9 #define BTN_EN2 PA10 #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE EXP1_3 + #define LCD_PINS_ENABLE EXP1_08_PIN #define LCD_PINS_D4 PB9 #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -180,7 +180,7 @@ #endif #define LCD_PINS_RS PB9 - #define LCD_PINS_ENABLE EXP1_9 + #define LCD_PINS_ENABLE EXP1_02_PIN #define LCD_PINS_D4 PB8 #define LCD_PINS_D5 PA10 #define LCD_PINS_D6 PA9 @@ -189,14 +189,14 @@ #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - #define BTN_ENC EXP1_9 + #define BTN_ENC EXP1_02_PIN #define BTN_EN1 PA9 #define BTN_EN2 PA10 #define DOGLCD_CS PB8 #define DOGLCD_A0 PB9 #define DOGLCD_SCK PB5 - #define DOGLCD_MOSI EXP1_3 + #define DOGLCD_MOSI EXP1_08_PIN #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 @@ -214,28 +214,28 @@ * * Board Display * ------ ------ - * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V | 1 2 | GND - * (MOD_RESET) PA9 | 3 4 | RESET -- | 3 4 | (SD_DET) - * (SD_CS) PA10 5 6 | PB9 (MOSI) | 5 6 | -- - * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 7 8 | (LCD_CS) - * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) + * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 3 4 | RESET -- | 8 7 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | -- + * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 4 3 | (LCD_CS) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) * ------ ------ * EXP1 EXP1 * * Needs custom cable: * - * Board Display - * - * EXP1-1 ----------- EXP1-10 - * EXP1-2 ----------- EXP1-9 - * SPI1-4 ----------- EXP1-6 - * EXP1-4 ----------- FREE - * SPI1-3 ----------- EXP1-2 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- FREE - * EXP1-8 ----------- EXP1-3 - * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-7 + * Board Adapter Display + * ---------------------------------- + * EXP1-10 ---------- EXP1-10 5V + * EXP1-9 ----------- EXP1-9 GND + * SPI1-4 ----------- EXP1-6 MOSI + * EXP1-7 ----------- n/c + * SPI1-3 ----------- EXP1-2 SCK + * EXP1-5 ----------- EXP1-4 SD_CS + * EXP1-4 ----------- n/c + * EXP1-3 ----------- EXP1-3 LCD_CS + * SPI1-1 ----------- EXP1-1 MISO + * EXP1-1 ----------- EXP1-7 SD_DET */ #define TFTGLCD_CS PA9 @@ -253,20 +253,20 @@ * * Board Display * ------ ------ - * PB5 | 1 2 | PA15 (BEEP) | 1 2 | BTN_ENC - * PA9 | 3 4 | RESET LCD_CS | 3 4 | LCD A0 - * PA10 | 5 6 | PB9 LCD_RST | 5 6 | RED - * PB8 | 7 8 | PB15 (GREEN) | 7 8 | (BLUE) - * GND | 9 10 | 5V GND | 9 10 | 5V + * PB5 | 1 2 | PA15 (BEEP) |10 9 | BTN_ENC + * PA9 | 3 4 | RESET LCD_CS | 8 7 | LCD A0 + * PA10 | 5 6 | PB9 LCD_RST | 6 5 | RED + * PB8 | 7 8 | PB15 (GREEN) | 4 3 | (BLUE) + * GND | 9 10 | 5V GND | 2 1 | 5V * ------ ------ * EXP1 EXP1 * * --- ------ - * RST | 1 | (MISO) | 1 2 | SCK - * (RX2) PA2 | 2 | BTN_EN1 | 3 4 | (SS) - * (TX2) PA3 | 3 | BTN_EN2 | 5 6 | MOSI - * GND | 4 | (CD) | 7 8 | (RST) - * 5V | 5 | (GND) | 9 10 | (KILL) + * RST | 1 | (MISO) |10 9 | SCK + * (RX2) PA2 | 2 | BTN_EN1 | 8 7 | (SS) + * (TX2) PA3 | 3 | BTN_EN2 | 6 5 | MOSI + * GND | 4 | (CD) | 4 3 | (RST) + * 5V | 5 | (GND) | 2 1 | (KILL) * --- ------ * TFT EXP2 * @@ -274,18 +274,19 @@ * * Board Display * - * EXP1-1 ----------- EXP1-1 - * EXP1-2 ----------- EXP1-2 - * EXP1-3 ----------- EXP2-6 - * EXP1-4 ----------- EXP1-5 - * EXP1-5 ----------- EXP2-8 - * EXP1-6 ----------- EXP1-6 - * EXP1-8 ----------- EXP1-8 - * EXP1-9 ----------- EXP1-9 - * EXP1-10 ----------- EXP1-7 + * EXP1-10 ---------- EXP1-1 5V + * EXP1-9 ----------- EXP1-2 GND + * EXP1-8 ----------- EXP2-6 EN2 + * EXP1-7 ----------- EXP1-5 RED + * EXP1-6 ----------- EXP2-8 EN1 + * EXP1-5 ----------- EXP1-6 LCD_RST + * EXP1-4 ----------- n/c + * EXP1-3 ----------- EXP1-8 LCD_CS + * EXP1-2 ----------- EXP1-9 ENC + * EXP1-1 ----------- EXP1-7 LCD_A0 * - * TFT-2 ----------- EXP2-9 - * TFT-3 ----------- EXP2-5 + * TFT-2 ----------- EXP2-9 SCK + * TFT-3 ----------- EXP2-5 MOSI * * for backlight configuration see steps 2 (V2.1) and 3 in https://wiki.fysetc.com/Mini12864_Panel/ */ @@ -325,33 +326,33 @@ * * Board Display * ------ ------ - * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V | 1 2 | GND - * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 3 4 | (SD_DET) - * (SD_CS) PA10 5 6 | PB9 (MOSI) | 5 6 | (LCD_CS) - * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 7 8 | (MOD_RESET) - * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) + * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 8 7 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | (LCD_CS) + * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 4 3 | (MOD_RESET) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) * ------ ------ * EXP1 EXP1 * * Needs custom cable: * * Board Adapter Display - * _________ - * EXP1-1 ----------- EXP1-10 - * EXP1-2 ----------- EXP1-9 - * SPI1-4 ----------- EXP1-6 - * EXP1-4 ----------- EXP1-5 - * SPI1-3 ----------- EXP1-2 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- EXP1-8 - * EXP1-8 ----------- EXP1-3 - * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-7 + * ---------------------------------- + * EXP1-10 ---------- EXP1-10 5V + * EXP1-9 ----------- EXP1-9 GND + * SPI1-4 ----------- EXP1-6 MOSI + * EXP1-7 ----------- EXP1-5 LCD_CS + * SPI1-3 ----------- EXP1-2 SCK + * EXP1-5 ----------- EXP1-4 SD_CS + * EXP1-4 ----------- EXP1-8 RESET + * EXP1-3 ----------- EXP1-3 MOD_RST + * SPI1-1 ----------- EXP1-1 MISO + * EXP1-1 ----------- EXP1-7 SD_DET */ - #define CLCD_SPI_BUS 1 // SPI1 connector + #define CLCD_SPI_BUS 1 // SPI1 connector - #define BEEPER_PIN EXP1_9 + #define BEEPER_PIN EXP1_02_PIN #define CLCD_MOD_RESET PA9 #define CLCD_SPI_CS PB8 @@ -375,7 +376,7 @@ #error "SD CUSTOM_CABLE is not compatible with SKR Mini E3." #endif -#define ONBOARD_SPI_DEVICE 1 // SPI1 -> used only by HAL/STM32F1... +#define ONBOARD_SPI_DEVICE 1 // SPI1 -> used only by HAL/STM32F1... #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card #define ENABLE_SPI1 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 16ea8de2f0..4e343fa8cd 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -119,23 +119,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PC14 -#define EXP1_07_PIN PC15 -#define EXP1_06_PIN PB7 -#define EXP1_05_PIN PC13 -#define EXP1_04_PIN PC12 -#define EXP1_03_PIN PB6 -#define EXP1_02_PIN PC11 #define EXP1_01_PIN PC10 +#define EXP1_02_PIN PC11 +#define EXP1_03_PIN PB6 +#define EXP1_04_PIN PC12 +#define EXP1_05_PIN PC13 +#define EXP1_06_PIN PB7 +#define EXP1_07_PIN PC15 +#define EXP1_08_PIN PC14 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN PB9 -#define EXP2_06_PIN PB5 -#define EXP2_05_PIN PB8 -#define EXP2_04_PIN PA15 -#define EXP2_03_PIN PD2 -#define EXP2_02_PIN PB3 #define EXP2_01_PIN PB4 +#define EXP2_02_PIN PB3 +#define EXP2_03_PIN PD2 +#define EXP2_04_PIN PA15 +#define EXP2_05_PIN PB8 +#define EXP2_06_PIN PB5 +#define EXP2_07_PIN PB9 +#define EXP2_08_PIN -1 // RESET // // LCD / Controller diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 7f63cb1b24..c73544bf43 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -131,14 +131,14 @@ * ------ * EXP1 */ -#define EXP1_08_PIN PA4 -#define EXP1_07_PIN PB7 -#define EXP1_06_PIN PB8 -#define EXP1_05_PIN PA3 -#define EXP1_04_PIN -1 // RESET -#define EXP1_03_PIN PA2 -#define EXP1_02_PIN PB6 #define EXP1_01_PIN PB5 +#define EXP1_02_PIN PB6 +#define EXP1_03_PIN PA2 +#define EXP1_04_PIN -1 // RESET +#define EXP1_05_PIN PA3 +#define EXP1_06_PIN PB8 +#define EXP1_07_PIN PB7 +#define EXP1_08_PIN PA4 // // LCD / Controller diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 3df8ad2a8e..5a3e7337ad 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -176,17 +176,17 @@ * ------ * EXP1 */ - #define EXP1_03_PIN PB15 - #define EXP1_04_PIN PB12 - #define EXP1_05_PIN PB13 - #define EXP1_06_PIN PB14 - #define EXP1_07_PIN PE8 - #define EXP1_08_PIN PB10 - #define EXP1_09_PIN PB2 - #define EXP1_10_PIN PC6 + #define EXP1_01_PIN PC6 + #define EXP1_02_PIN PB2 + #define EXP1_03_PIN PB10 + #define EXP1_04_PIN PE8 + #define EXP1_05_PIN PB14 + #define EXP1_06_PIN PB13 + #define EXP1_07_PIN PB12 + #define EXP1_08_PIN PB15 #ifndef HAS_PIN_27_BOARD - #define BEEPER_PIN EXP1_10_PIN + #define BEEPER_PIN EXP1_01_PIN #endif #elif ENABLED(VET6_12864_LCD) @@ -202,50 +202,50 @@ * ------ * EXP1 */ - #define EXP1_03_PIN PA7 - #define EXP1_04_PIN PA4 - #define EXP1_05_PIN PA5 - #define EXP1_06_PIN PA6 - #define EXP1_07_PIN -1 - #define EXP1_08_PIN PB10 - #define EXP1_09_PIN PC5 - #define EXP1_10_PIN -1 + #define EXP1_01_PIN -1 + #define EXP1_02_PIN PC5 + #define EXP1_03_PIN PB10 + #define EXP1_04_PIN -1 + #define EXP1_05_PIN PA6 + #define EXP1_06_PIN PA5 + #define EXP1_07_PIN PA4 + #define EXP1_08_PIN PA7 #else #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." #endif - #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN - #define BTN_ENC EXP1_09_PIN - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN #elif ANY(HAS_DWIN_E3V2, IS_DWIN_MARLINUI, DWIN_VET6_CREALITY_LCD) #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI // RET6 DWIN ENCODER LCD - #define EXP1_03_PIN PB15 - #define EXP1_04_PIN PB12 - #define EXP1_05_PIN PB13 - #define EXP1_06_PIN PB14 + #define EXP1_05_PIN PB14 + #define EXP1_06_PIN PB13 + #define EXP1_07_PIN PB12 + #define EXP1_08_PIN PB15 //#define LCD_LED_PIN PB2 #else // VET6 DWIN ENCODER LCD - #define EXP1_03_PIN PA7 - #define EXP1_04_PIN PA4 - #define EXP1_05_PIN PA5 - #define EXP1_06_PIN PA6 + #define EXP1_05_PIN PA6 + #define EXP1_06_PIN PA5 + #define EXP1_07_PIN PA4 + #define EXP1_08_PIN PA7 #endif - #define BTN_ENC EXP1_06_PIN - #define BTN_EN1 EXP1_03_PIN - #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_05_PIN + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_07_PIN #ifndef BEEPER_PIN - #define BEEPER_PIN EXP1_05_PIN + #define BEEPER_PIN EXP1_06_PIN #endif #endif diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index 699bfee563..86ede843be 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -158,14 +158,14 @@ * ------ * EXP1 */ - #define EXP1_08_PIN PB15 - #define EXP1_07_PIN PB12 - #define EXP1_06_PIN PB13 - #define EXP1_05_PIN PB14 - #define EXP1_04_PIN PE8 - #define EXP1_03_PIN PB10 - #define EXP1_02_PIN PB2 #define EXP1_01_PIN PC6 + #define EXP1_02_PIN PB2 + #define EXP1_03_PIN PB10 + #define EXP1_04_PIN PE8 + #define EXP1_05_PIN PB14 + #define EXP1_06_PIN PB13 + #define EXP1_07_PIN PB12 + #define EXP1_08_PIN PB15 #define BEEPER_PIN EXP1_01_PIN @@ -182,14 +182,14 @@ * ------ * EXP1 */ - #define EXP1_08_PIN PA7 - #define EXP1_07_PIN PA4 - #define EXP1_06_PIN PA5 - #define EXP1_05_PIN PA6 - #define EXP1_04_PIN -1 - #define EXP1_03_PIN PB10 - #define EXP1_02_PIN PC5 #define EXP1_01_PIN -1 + #define EXP1_02_PIN PC5 + #define EXP1_03_PIN PB10 + #define EXP1_04_PIN -1 + #define EXP1_05_PIN PA6 + #define EXP1_06_PIN PA5 + #define EXP1_07_PIN PA4 + #define EXP1_08_PIN PA7 #else #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index 5326611672..f39850f755 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -131,23 +131,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PB4 -#define EXP1_07_PIN PB5 -#define EXP1_06_PIN PB6 -#define EXP1_05_PIN PB7 -#define EXP1_04_PIN PB8 -#define EXP1_03_PIN PB9 -#define EXP1_02_PIN PC13 #define EXP1_01_PIN PC14 +#define EXP1_02_PIN PC13 +#define EXP1_03_PIN PB9 +#define EXP1_04_PIN PB8 +#define EXP1_05_PIN PB7 +#define EXP1_06_PIN PB6 +#define EXP1_07_PIN PB5 +#define EXP1_08_PIN PB4 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN PB11 -#define EXP2_06_PIN PB15 -#define EXP2_05_PIN PD2 -#define EXP2_04_PIN PB12 -#define EXP2_03_PIN PB3 -#define EXP2_02_PIN PB13 #define EXP2_01_PIN PB14 +#define EXP2_02_PIN PB13 +#define EXP2_03_PIN PB3 +#define EXP2_04_PIN PB12 +#define EXP2_05_PIN PD2 +#define EXP2_06_PIN PB15 +#define EXP2_07_PIN PB11 +#define EXP2_08_PIN -1 // RESET // // LCD / Controller diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index 7b790ef157..e59e8aef59 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -146,14 +146,14 @@ * - Functionally the pins are assigned in the same order as on the Ender-3 board. * - Pin 4 on the Cheetah board is assigned to an I/O, it is assigned to RESET on the Ender-3 board. */ -#define EXP1_08_PIN PB15 -#define EXP1_07_PIN PB12 -#define EXP1_06_PIN PB13 -#define EXP1_05_PIN PC10 -#define EXP1_04_PIN PB14 -#define EXP1_03_PIN PC11 -#define EXP1_02_PIN PC12 #define EXP1_01_PIN PC9 +#define EXP1_02_PIN PC12 +#define EXP1_03_PIN PC11 +#define EXP1_04_PIN PB14 +#define EXP1_05_PIN PC10 +#define EXP1_06_PIN PB13 +#define EXP1_07_PIN PB12 +#define EXP1_08_PIN PB15 #if HAS_WIRED_LCD #define BEEPER_PIN EXP1_01_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index b6f5dfa87e..b8f6f6a330 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -215,23 +215,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PD10 -#define EXP1_07_PIN PD11 -#define EXP1_06_PIN PE15 -#define EXP1_05_PIN PE14 -#define EXP1_04_PIN PC6 -#define EXP1_03_PIN PD13 -#define EXP1_02_PIN PE13 #define EXP1_01_PIN PC5 +#define EXP1_02_PIN PE13 +#define EXP1_03_PIN PD13 +#define EXP1_04_PIN PC6 +#define EXP1_05_PIN PE14 +#define EXP1_06_PIN PE15 +#define EXP1_07_PIN PD11 +#define EXP1_08_PIN PD10 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN PE12 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PE11 -#define EXP2_04_PIN PE10 -#define EXP2_03_PIN PE8 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PE8 +#define EXP2_04_PIN PE10 +#define EXP2_05_PIN PE11 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PE12 +#define EXP2_08_PIN -1 // // SD Card diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index a25c8950cb..642c97bb11 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -149,33 +149,33 @@ * ------ ------ ------ * EXP1 EXP2 "Ender-3 EXP1" */ -#define EXP1_08_PIN PC5 -#define EXP1_07_PIN PC4 -#define EXP1_06_PIN PA7 -#define EXP1_05_PIN PA6 -#define EXP1_04_PIN PA5 -#define EXP1_03_PIN PA4 -#define EXP1_02_PIN PC3 #define EXP1_01_PIN PC1 +#define EXP1_02_PIN PC3 +#define EXP1_03_PIN PA4 +#define EXP1_04_PIN PA5 +#define EXP1_05_PIN PA6 +#define EXP1_06_PIN PA7 +#define EXP1_07_PIN PC4 +#define EXP1_08_PIN PC5 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN PC10 -#define EXP2_06_PIN PB15 -#define EXP2_05_PIN PB0 -#define EXP2_04_PIN PA15 -#define EXP2_03_PIN PB11 -#define EXP2_02_PIN PB13 #define EXP2_01_PIN PB14 +#define EXP2_02_PIN PB13 +#define EXP2_03_PIN PB11 +#define EXP2_04_PIN PA15 +#define EXP2_05_PIN PB0 +#define EXP2_06_PIN PB15 +#define EXP2_07_PIN PC10 +#define EXP2_08_PIN -1 // RESET // "Ender-3 EXP1" -#define EXP3_08_PIN PA4 -#define EXP3_07_PIN PA5 -#define EXP3_06_PIN PA6 -#define EXP3_05_PIN PB0 -#define EXP3_04_PIN -1 // RESET -#define EXP3_03_PIN PB11 -#define EXP3_02_PIN PC3 #define EXP3_01_PIN PC1 +#define EXP3_02_PIN PC3 +#define EXP3_03_PIN PB11 +#define EXP3_04_PIN -1 // RESET +#define EXP3_05_PIN PB0 +#define EXP3_06_PIN PA6 +#define EXP3_07_PIN PA5 +#define EXP3_08_PIN PA4 #if HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index 227db4b15c..7ead6aa288 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -88,16 +88,16 @@ * ------ * "E3" EXP1 */ -#define EXP3_10_PIN -1 // 5V -#define EXP3_09_PIN -1 // GND -#define EXP3_08_PIN PC2 -#define EXP3_07_PIN PC3 -#define EXP3_06_PIN PC1 -#define EXP3_05_PIN PB4 -#define EXP3_04_PIN PA11 // RESET? -#define EXP3_03_PIN PB5 -#define EXP3_02_PIN PB3 #define EXP3_01_PIN PD2 +#define EXP3_02_PIN PB3 +#define EXP3_03_PIN PB5 +#define EXP3_04_PIN PA11 // RESET? +#define EXP3_05_PIN PB4 +#define EXP3_06_PIN PC1 +#define EXP3_07_PIN PC3 +#define EXP3_08_PIN PC2 +#define EXP3_09_PIN -1 // GND +#define EXP3_10_PIN -1 // 5V // // LCD Pins diff --git a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h index ad28e5c47b..5a82fbcd6d 100644 --- a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h +++ b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h @@ -179,30 +179,30 @@ /** FYSETC TFT TFT81050 display pinout * - * Board Display - * ----- ----- - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 PA10 (SD_CS) (PB8) LCD_CS | 5 6 MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PA15) SD_DET | 7 8 | RESET - * (BEEPER) PB6 | 9 10| PA15 (SD_DET) GND | 9 10| 5V - * ----- ----- - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PA15 | 1 2 | PB6 (BEEPER) (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (MOD_RESET) PA9 | 3 4 | RESET MOD_RESET | 3 4 | SD_CS + * (SD_CS) PA10 5 6 | PB9 (FREE) LCD_CS | 5 6 MOSI (SPI1-MOSI) + * (LCD_CS) PB8 | 7 8 | PB7 (FREE) SD_DET | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * * Board Adapter Display - * _________ - * EXP1-1 ----------- EXP1-10 - * EXP1-2 ----------- EXP1-9 - * SPI1-4 ----------- EXP1-6 - * EXP1-4 ----------- EXP1-5 - * SP11-3 ----------- EXP1-2 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- EXP1-8 - * EXP1-8 ----------- EXP1-3 - * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-7 + * ---------------------------------- + * EXP1-10 ---------- EXP1-10 5V + * EXP1-9 ----------- EXP1-9 GND + * SPI1-4 ----------- EXP1-6 MOSI + * EXP1-7 ----------- EXP1-5 LCD_CS + * SP11-3 ----------- EXP1-2 SCK + * EXP1-5 ----------- EXP1-4 SD_CS + * EXP1-4 ----------- EXP1-8 RESET + * EXP1-3 ----------- EXP1-3 MOD_RST + * SPI1-1 ----------- EXP1-1 MISO + * EXP1-1 ----------- EXP1-7 SD_DET */ #define CLCD_SPI_BUS 1 // SPI1 connector diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h index ed0f00591f..1347a14678 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h @@ -72,14 +72,14 @@ // 2 +5V // 1 GND -#define EXP1_08_PIN PB11 -#define EXP1_07_PIN PB10 -#define EXP1_06_PIN PB2 -#define EXP1_05_PIN PC5 -#define EXP1_04_PIN PA10 -#define EXP1_03_PIN PA9 -#define EXP1_02_PIN PB0 #define EXP1_01_PIN PB1 +#define EXP1_02_PIN PB0 +#define EXP1_03_PIN PA9 +#define EXP1_04_PIN PA10 +#define EXP1_05_PIN PC5 +#define EXP1_06_PIN PB2 +#define EXP1_07_PIN PB10 +#define EXP1_08_PIN PB11 // AUX1 connector // 1 +5V diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h index f59d61434e..9618b3ad1a 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -89,14 +89,14 @@ // 2 +5V +5V // 1 GND GND -#define EXP1_08_PIN PE14 -#define EXP1_07_PIN PE15 -#define EXP1_06_PIN PE9 -#define EXP1_05_PIN PE8 -#define EXP1_04_PIN PE10 -#define EXP1_03_PIN PE12 -#define EXP1_02_PIN PE11 #define EXP1_01_PIN PE13 +#define EXP1_02_PIN PE11 +#define EXP1_03_PIN PE12 +#define EXP1_04_PIN PE10 +#define EXP1_05_PIN PE8 +#define EXP1_06_PIN PE9 +#define EXP1_07_PIN PE15 +#define EXP1_08_PIN PE14 // EXP2 connector // MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 @@ -111,12 +111,12 @@ // 2 +5V +5V // 1 GND GND -#define EXP2_08_PIN PB3 -#define EXP2_07_PIN PB5 -#define EXP2_06_PIN PB4 -#define EXP2_05_PIN PA15 -#define EXP2_04_PIN PA10 #define EXP2_03_PIN PA9 +#define EXP2_04_PIN PA10 +#define EXP2_05_PIN PA15 +#define EXP2_06_PIN PB4 +#define EXP2_07_PIN PB5 +#define EXP2_08_PIN PB3 // AUX1 connector // 1 +5V diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h index f83ce52fe9..d1d8a4c68f 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -90,14 +90,14 @@ // 2 +5V // 1 GND -#define EXP1_08_PIN PE14 -#define EXP1_07_PIN PE15 -#define EXP1_06_PIN PE9 -#define EXP1_05_PIN PE8 -#define EXP1_04_PIN PE10 -#define EXP1_03_PIN PE12 -#define EXP1_02_PIN PE11 #define EXP1_01_PIN PE13 +#define EXP1_02_PIN PE11 +#define EXP1_03_PIN PE12 +#define EXP1_04_PIN PE10 +#define EXP1_05_PIN PE8 +#define EXP1_06_PIN PE9 +#define EXP1_07_PIN PE15 +#define EXP1_08_PIN PE14 // EXP2 connector // MARK I/O ZONESTAR_LCD12864 REPRAPDISCOUNT_LCD12864 @@ -112,14 +112,14 @@ // 2 +5V // 1 GND -#define EXP2_08_PIN PB3 -#define EXP2_07_PIN PB5 -#define EXP2_06_PIN PB4 -#define EXP2_05_PIN PA15 -#define EXP2_04_PIN PA10 -#define EXP2_03_PIN PA9 -#define EXP2_02_PIN PE7 #define EXP2_01_PIN PC0 +#define EXP2_02_PIN PE7 +#define EXP2_03_PIN PA9 +#define EXP2_04_PIN PA10 +#define EXP2_05_PIN PA15 +#define EXP2_06_PIN PB4 +#define EXP2_07_PIN PB5 +#define EXP2_08_PIN PB3 // AUX1 connector // 1 +5V diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index aadce03c56..2147dd9b4f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -208,24 +208,24 @@ * EXP1 EXP2 | * ------------------------------------------------------------------------------ */ -#define EXP1_08_PIN PE13 -#define EXP1_07_PIN PE12 -#define EXP1_06_PIN PE11 -#define EXP1_05_PIN PE10 -#define EXP1_04_PIN PE8 -#define EXP1_03_PIN PE9 -#define EXP1_02_PIN PB1 #define EXP1_01_PIN PE7 +#define EXP1_02_PIN PB1 +#define EXP1_03_PIN PE9 +#define EXP1_04_PIN PE8 +#define EXP1_05_PIN PE10 +#define EXP1_06_PIN PE11 +#define EXP1_07_PIN PE12 +#define EXP1_08_PIN PE13 -#define EXP2_10_PIN PA3 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN PC4 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PB0 -#define EXP2_04_PIN PA4 -#define EXP2_03_PIN PC5 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PC5 +#define EXP2_04_PIN PA4 +#define EXP2_05_PIN PB0 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PC4 +#define EXP2_08_PIN -1 +#define EXP2_10_PIN PA3 // HAL SPI1 pins #define SD_SCK_PIN EXP2_02_PIN // SPI1 SCLK diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index ca257d257b..c29949e814 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -219,28 +219,28 @@ * * BTT E3 RRF Display Ribbon * ------ ------ - * (BEEPER) PE8 | 1 2 | PE9 (BTN_ENC) GND | 1 2 | 5V - * (BTN_EN1) PE7 | 3 4 | RESET BEEPER | 3 4 | ESTOP (RESET) - * (BTN_EN2) PB2 5 6 | PE10 (LCD_D4) (BTN_ENC) ENC_BTN | 5 6 | LCD_SCLK (LCD_D4) - * (LCD_RS) PB1 | 7 8 | PE11 (LCD_EN) (BTN_EN2) ENC_A | 7 8 | LCD_DATA (LCD_EN) - * GND | 9 10 | 5V (BTN_EN1) ENC_B | 9 10 | LCD_CS (LCD_RS) + * (BEEPER) PE8 | 1 2 | PE9 (BTN_ENC) GND |10 9 | 5V + * (BTN_EN1) PE7 | 3 4 | RESET BEEPER | 8 7 | ESTOP (RESET) + * (BTN_EN2) PB2 5 6 | PE10 (LCD_D4) (BTN_ENC) ENC_BTN | 6 5 | LCD_SCLK (LCD_D4) + * (LCD_RS) PB1 | 7 8 | PE11 (LCD_EN) (BTN_EN2) ENC_A | 4 3 | LCD_DATA (LCD_EN) + * GND | 9 10 | 5V (BTN_EN1) ENC_B | 2 1 | LCD_CS (LCD_RS) * ------ ------ - * EXP1 Ribbon + * EXP1 LCD * * Needs custom cable: * * Board Adapter Display Ribbon (coming from display) - * - * EXP1-1 ----------- EXP1-9 - * EXP1-2 ----------- EXP1-10 - * EXP1-3 ----------- EXP1-3 - * EXP1-4 ----------- EXP1-1 - * EXP1-5 ----------- EXP1-5 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- EXP1-7 - * EXP1-8 ----------- EXP1-8 - * EXP1-9 ----------- EXP1-6 - * EXP1-10 ----------- EXP1-8 + * ---------------------------------- + * EXP1-10 ---------- LCD-9 5V + * EXP1-9 ----------- LCD-10 GND + * EXP1-8 ----------- LCD-3 LCD_EN + * EXP1-7 ----------- LCD-1 LCD_RS + * EXP1-6 ----------- LCD-5 LCD_D4 + * EXP1-5 ----------- LCD-4 EN2 + * EXP1-4 ----------- LCD-7 RESET + * EXP1-3 ----------- LCD-2 EN1 + * EXP1-2 ----------- LCD-6 BTN + * EXP1-1 ----------- LCD-8 BEEPER */ #endif @@ -286,28 +286,28 @@ * * Board Display * ------ ------ - * (SD_DET) PE8 | 1 2 | PE9 (BEEPER) 5V | 1 2 | GND - * (MOD_RESET) PE7 | 3 4 | RESET -- | 3 4 | (SD_DET) - * (SD_CS) PB2 5 6 | PE10 (MOSI) 5 6 | -- - * (LCD_CS) PB1 | 7 8 | PE11 (SD_CS) | 7 8 | (LCD_CS) - * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) + * (SD_DET) PE8 | 1 2 | PE9 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PE7 | 3 4 | RESET -- | 8 7 | (SD_DET) + * (SD_CS) PB2 5 6 | PE10 (MOSI) 6 5 | -- + * (LCD_CS) PB1 | 7 8 | PE11 (SD_CS) | 4 3 | (LCD_CS) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) * ------ ------ * EXP1 EXP1 * * Needs custom cable: * * Board Adapter Display - * _________ - * EXP1-1 ----------- EXP1-10 - * EXP1-2 ----------- EXP1-9 - * SPI1-4 ----------- EXP1-6 - * EXP1-4 ----------- FREE - * SPI1-3 ----------- EXP1-2 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- FREE - * EXP1-8 ----------- EXP1-3 - * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-7 + * ---------------------------------- + * EXP1-10 ---------- EXP1-10 5V + * EXP1-9 ----------- EXP1-9 GND + * SPI1-4 ----------- EXP1-6 MOSI + * EXP1-7 ----------- n/c + * SPI1-3 ----------- EXP1-2 SCK + * EXP1-5 ----------- EXP1-4 SD_CS + * EXP1-4 ----------- n/c + * EXP1-3 ----------- EXP1-3 LCD_CS + * SPI1-1 ----------- EXP1-1 MISO + * EXP1-1 ----------- EXP1-7 SD_DET */ #define TFTGLCD_CS PE7 @@ -341,28 +341,28 @@ * * Board Display * ------ ------ - * (SD_DET) PE8 | 1 2 | PE9 (BEEPER) 5V | 1 2 | GND - * (MOD_RESET) PE7 | 3 4 | RESET RESET | 3 4 | (SD_DET) - * (SD_CS) PB2 5 6 | PE10 (MOSI) | 5 6 | (LCD_CS) - * (LCD_CS) PB1 | 7 8 | PE11 (SD_CS) | 7 8 | (MOD_RESET) - * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) + * (SD_DET) PE8 | 1 2 | PE9 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PE7 | 3 4 | RESET RESET | 8 7 | (SD_DET) + * (SD_CS) PB2 5 6 | PE10 (MOSI) | 6 5 | (LCD_CS) + * (LCD_CS) PB1 | 7 8 | PE11 (SD_CS) | 4 3 | (MOD_RESET) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) * ------ ------ * EXP1 EXP1 * * Needs custom cable: * * Board Adapter Display - * - * EXP1-1 ----------- EXP1-10 - * EXP1-2 ----------- EXP1-9 - * SPI1-4 ----------- EXP1-6 - * EXP1-4 ----------- EXP1-5 - * SPI1-3 ----------- EXP1-2 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- EXP1-8 - * EXP1-8 ----------- EXP1-3 - * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-7 + * ---------------------------------- + * EXP1-10 ---------- EXP1-10 5V + * EXP1-9 ----------- EXP1-9 GND + * SPI1-4 ----------- EXP1-6 MOSI + * EXP1-7 ----------- EXP1-5 LCD_CS + * SPI1-3 ----------- EXP1-2 SCK + * EXP1-5 ----------- EXP1-4 SD_CS + * EXP1-4 ----------- EXP1-8 RESET + * EXP1-3 ----------- EXP1-3 MOD_RST + * SPI1-1 ----------- EXP1-1 MISO + * EXP1-1 ----------- EXP1-7 SD_DET */ #define CLCD_SPI_BUS 1 // SPI1 connector diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index b341f3ae07..fe03ec8983 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -374,22 +374,22 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PG5 -#define EXP1_07_PIN PG6 -#define EXP1_06_PIN PG7 -#define EXP1_05_PIN PG8 -#define EXP1_04_PIN PA8 -#define EXP1_03_PIN PC10 -#define EXP1_02_PIN PA15 #define EXP1_01_PIN PC11 +#define EXP1_02_PIN PA15 +#define EXP1_03_PIN PC10 +#define EXP1_04_PIN PA8 +#define EXP1_05_PIN PG8 +#define EXP1_06_PIN PG7 +#define EXP1_07_PIN PG6 +#define EXP1_08_PIN PG5 -#define EXP2_07_PIN PB10 -#define EXP2_06_PIN PB15 -#define EXP2_05_PIN PH10 -#define EXP2_04_PIN PB12 -#define EXP2_03_PIN PD10 -#define EXP2_02_PIN PB13 #define EXP2_01_PIN PB14 +#define EXP2_02_PIN PB13 +#define EXP2_03_PIN PD10 +#define EXP2_04_PIN PB12 +#define EXP2_05_PIN PH10 +#define EXP2_06_PIN PB15 +#define EXP2_07_PIN PB10 // // LCDs and Controllers diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 8f04ae1d73..9ff9f6a475 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -330,23 +330,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PE15 -#define EXP1_07_PIN PE14 -#define EXP1_06_PIN PE13 -#define EXP1_05_PIN PE12 -#define EXP1_04_PIN PE10 -#define EXP1_03_PIN PE9 -#define EXP1_02_PIN PE7 #define EXP1_01_PIN PE8 +#define EXP1_02_PIN PE7 +#define EXP1_03_PIN PE9 +#define EXP1_04_PIN PE10 +#define EXP1_05_PIN PE12 +#define EXP1_06_PIN PE13 +#define EXP1_07_PIN PE14 +#define EXP1_08_PIN PE15 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN PC15 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PB2 -#define EXP2_04_PIN PA4 -#define EXP2_03_PIN PB1 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PB1 +#define EXP2_04_PIN PA4 +#define EXP2_05_PIN PB2 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PC15 +#define EXP2_08_PIN -1 // // Onboard SD card diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 9b49f27670..78a137b35d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -321,23 +321,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PG7 -#define EXP1_07_PIN PG6 -#define EXP1_06_PIN PG3 -#define EXP1_05_PIN PG2 -#define EXP1_04_PIN PD10 -#define EXP1_03_PIN PD11 -#define EXP1_02_PIN PA8 #define EXP1_01_PIN PG4 +#define EXP1_02_PIN PA8 +#define EXP1_03_PIN PD11 +#define EXP1_04_PIN PD10 +#define EXP1_05_PIN PG2 +#define EXP1_06_PIN PG3 +#define EXP1_07_PIN PG6 +#define EXP1_08_PIN PG7 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN PF12 -#define EXP2_06_PIN PB15 -#define EXP2_05_PIN PF11 -#define EXP2_04_PIN PB12 -#define EXP2_03_PIN PG10 -#define EXP2_02_PIN PB13 #define EXP2_01_PIN PB14 +#define EXP2_02_PIN PB13 +#define EXP2_03_PIN PG10 +#define EXP2_04_PIN PB12 +#define EXP2_05_PIN PF11 +#define EXP2_06_PIN PB15 +#define EXP2_07_PIN PF12 +#define EXP2_08_PIN -1 // // Onboard SD card @@ -553,10 +553,10 @@ /** * ------ - * RX | 3 4 | 3.3V GPIO0 PF14 ... Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) - * GPIO0 | 5 6 | Reset GPIO2 PF15 ... must be high (ESP3D software configures this with a pullup so OK to leave as floating) - * GPIO2 | 7 8 | Enable Reset PG0 ... active low, probably OK to leave floating - * GND | 9 10 | TX Enable PG1 ... Must be high for module to run + * RX | 8 7 | 3.3V GPIO0 PF14 ... Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) + * GPIO0 | 6 5 | Reset GPIO2 PF15 ... must be high (ESP3D software configures this with a pullup so OK to leave as floating) + * GPIO2 | 4 3 | Enable Reset PG0 ... active low, probably OK to leave floating + * GND | 2 1 | TX Enable PG1 ... Must be high for module to run * ------ * W1 */ diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 9c22ac804d..7ac9156f40 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -344,23 +344,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PE13 -#define EXP1_07_PIN PE12 -#define EXP1_06_PIN PE11 -#define EXP1_05_PIN PE10 -#define EXP1_04_PIN PE9 -#define EXP1_03_PIN PB1 -#define EXP1_02_PIN PB0 #define EXP1_01_PIN PC5 +#define EXP1_02_PIN PB0 +#define EXP1_03_PIN PB1 +#define EXP1_04_PIN PE9 +#define EXP1_05_PIN PE10 +#define EXP1_06_PIN PE11 +#define EXP1_07_PIN PE12 +#define EXP1_08_PIN PE13 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN PC4 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PB2 -#define EXP2_04_PIN PA4 -#define EXP2_03_PIN PE7 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PE7 +#define EXP2_04_PIN PA4 +#define EXP2_05_PIN PB2 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PC4 +#define EXP2_08_PIN -1 // // Onboard SD card diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index b98dcbf5d7..8d5e094122 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -185,23 +185,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PE7 -#define EXP1_07_PIN PE8 -#define EXP1_06_PIN PE9 -#define EXP1_05_PIN PE10 -#define EXP1_04_PIN PE12 -#define EXP1_03_PIN PE14 -#define EXP1_02_PIN PE15 #define EXP1_01_PIN PB10 +#define EXP1_02_PIN PE15 +#define EXP1_03_PIN PE14 +#define EXP1_04_PIN PE12 +#define EXP1_05_PIN PE10 +#define EXP1_06_PIN PE9 +#define EXP1_07_PIN PE8 +#define EXP1_08_PIN PE7 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN PB2 -#define EXP2_06_PIN PB15 -#define EXP2_05_PIN PC4 -#define EXP2_04_PIN PF11 -#define EXP2_03_PIN PC5 -#define EXP2_02_PIN PB13 #define EXP2_01_PIN PB14 +#define EXP2_02_PIN PB13 +#define EXP2_03_PIN PC5 +#define EXP2_04_PIN PF11 +#define EXP2_05_PIN PC4 +#define EXP2_06_PIN PB15 +#define EXP2_07_PIN PB2 +#define EXP2_08_PIN -1 // RESET // // Onboard SD support diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index f59c6718d5..32ec518bf8 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -160,23 +160,23 @@ * EXP3 */ -#define EXP1_08_PIN PB7 -#define EXP1_07_PIN PB6 -#define EXP1_06_PIN PB14 -#define EXP1_05_PIN PB13 -#define EXP1_04_PIN PB12 -#define EXP1_03_PIN PB15 -#define EXP1_02_PIN PC12 #define EXP1_01_PIN PC9 +#define EXP1_02_PIN PC12 +#define EXP1_03_PIN PB15 +#define EXP1_04_PIN PB12 +#define EXP1_05_PIN PB13 +#define EXP1_06_PIN PB14 +#define EXP1_07_PIN PB6 +#define EXP1_08_PIN PB7 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN PC3 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PC11 -#define EXP2_04_PIN PA4 -#define EXP2_03_PIN PC10 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PC10 +#define EXP2_04_PIN PA4 +#define EXP2_05_PIN PC11 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PC3 +#define EXP2_08_PIN -1 #if HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index e770140dbb..fca181c1f4 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -207,23 +207,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PD1 -#define EXP1_07_PIN PD0 -#define EXP1_06_PIN PC12 -#define EXP1_05_PIN PC10 -#define EXP1_04_PIN PD2 -#define EXP1_03_PIN PC11 -#define EXP1_02_PIN PA8 #define EXP1_01_PIN PC9 +#define EXP1_02_PIN PA8 +#define EXP1_03_PIN PC11 +#define EXP1_04_PIN PD2 +#define EXP1_05_PIN PC10 +#define EXP1_06_PIN PC12 +#define EXP1_07_PIN PD0 +#define EXP1_08_PIN PD1 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN PB10 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PC7 -#define EXP2_04_PIN PA4 -#define EXP2_03_PIN PC6 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PC6 +#define EXP2_04_PIN PA4 +#define EXP2_05_PIN PC7 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PB10 +#define EXP2_08_PIN -1 // RESET // // SPI / SD Card diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h index 676333b89c..8a9b72225d 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h @@ -221,23 +221,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PE7 -#define EXP1_07_PIN PE15 -#define EXP1_06_PIN PD8 -#define EXP1_05_PIN PD9 -#define EXP1_04_PIN PD10 -#define EXP1_03_PIN PE11 -#define EXP1_02_PIN PE10 #define EXP1_01_PIN PB2 +#define EXP1_02_PIN PE10 +#define EXP1_03_PIN PE11 +#define EXP1_04_PIN PD10 +#define EXP1_05_PIN PD9 +#define EXP1_06_PIN PD8 +#define EXP1_07_PIN PE15 +#define EXP1_08_PIN PE7 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN PB11 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PE8 -#define EXP2_04_PIN PA4 -#define EXP2_03_PIN PE9 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PE9 +#define EXP2_04_PIN PA4 +#define EXP2_05_PIN PE8 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PB11 +#define EXP2_08_PIN -1 // RESET #if ENABLED(SDSUPPORT) #ifndef SDCARD_CONNECTION diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h index 011d56dfe7..4ac64ae1d2 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h @@ -244,23 +244,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PD10 -#define EXP1_07_PIN PD11 -#define EXP1_06_PIN PE15 -#define EXP1_05_PIN PE14 -#define EXP1_04_PIN PC6 -#define EXP1_03_PIN PD13 -#define EXP1_02_PIN PE13 #define EXP1_01_PIN PC5 +#define EXP1_02_PIN PE13 +#define EXP1_03_PIN PD13 +#define EXP1_04_PIN PC6 +#define EXP1_05_PIN PE14 +#define EXP1_06_PIN PE15 +#define EXP1_07_PIN PD11 +#define EXP1_08_PIN PD10 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN PE12 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PE11 -#define EXP2_04_PIN PE10 -#define EXP2_03_PIN PE8 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PE8 +#define EXP2_04_PIN PE10 +#define EXP2_05_PIN PE11 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PE12 +#define EXP2_08_PIN -1 // RESET // // SPI SD Card diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 9b50705a90..7e08caaa82 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -238,23 +238,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PD10 -#define EXP1_07_PIN PD11 -#define EXP1_06_PIN PE15 -#define EXP1_05_PIN PE14 -#define EXP1_04_PIN PC6 -#define EXP1_03_PIN PD13 -#define EXP1_02_PIN PE13 #define EXP1_01_PIN PC5 +#define EXP1_02_PIN PE13 +#define EXP1_03_PIN PD13 +#define EXP1_04_PIN PC6 +#define EXP1_05_PIN PE14 +#define EXP1_06_PIN PE15 +#define EXP1_07_PIN PD11 +#define EXP1_08_PIN PD10 -#define EXP2_08_PIN -1 // RESET -#define EXP2_07_PIN PE12 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PE11 -#define EXP2_04_PIN PE10 -#define EXP2_03_PIN PE8 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PE8 +#define EXP2_04_PIN PE10 +#define EXP2_05_PIN PE11 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PE12 +#define EXP2_08_PIN -1 // RESET // // LCD SD diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h index 65a396ad3f..1a75a859e6 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h @@ -213,14 +213,14 @@ * A remote SD card is currently not supported because the pins routed to the EXP2 * connector are shared with the onboard SD card. */ -#define EXP1_08_PIN PB15 -#define EXP1_07_PIN PB12 -#define EXP1_06_PIN PB13 -#define EXP1_05_PIN PC5 -//#define EXP1_04_PIN -1 -#define EXP1_03_PIN PC4 -#define EXP1_02_PIN PB0 #define EXP1_01_PIN PA14 +#define EXP1_02_PIN PB0 +#define EXP1_03_PIN PC4 +//#define EXP1_04_PIN -1 +#define EXP1_05_PIN PC5 +#define EXP1_06_PIN PB13 +#define EXP1_07_PIN PB12 +#define EXP1_08_PIN PB15 #if ENABLED(CR10_STOCKDISPLAY) /** ------ diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index e395ee62dd..21ab9d0e70 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -175,23 +175,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PD4 -#define EXP1_07_PIN PD3 -#define EXP1_06_PIN PD2 -#define EXP1_05_PIN PD1 -#define EXP1_04_PIN PC12 -#define EXP1_03_PIN PD7 -#define EXP1_02_PIN PB12 #define EXP1_01_PIN PC9 +#define EXP1_02_PIN PB12 +#define EXP1_03_PIN PD7 +#define EXP1_04_PIN PC12 +#define EXP1_05_PIN PD1 +#define EXP1_06_PIN PD2 +#define EXP1_07_PIN PD3 +#define EXP1_08_PIN PD4 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN PB7 -//#define EXP2_06_PIN ? -#define EXP2_05_PIN PD0 -//#define EXP2_04_PIN ? -#define EXP2_03_PIN PD6 -//#define EXP2_02_PIN ? //#define EXP2_01_PIN ? +//#define EXP2_02_PIN ? +#define EXP2_03_PIN PD6 +//#define EXP2_04_PIN ? +#define EXP2_05_PIN PD0 +//#define EXP2_06_PIN ? +#define EXP2_07_PIN PB7 +#define EXP2_08_PIN -1 // // LCD / Controller diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h index 2ac0674513..956cb71f83 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h @@ -163,11 +163,11 @@ #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI /** * ------ ------ ------ - * (ENT) | 1 2 | (BEEP) | 1 2 | | 1 2 | - * (RX) | 3 4 | (RX) | 3 4 | (TX) RX | 3 4 | TX - * (TX) 5 6 | (ENT) 5 6 | (BEEP) ENT | 5 6 | BEEP - * (B) | 7 8 | (A) (B) | 7 8 | (A) B | 7 8 | A - * GND | 9 10 | (VCC) GND | 9 10 | VCC GND | 9 10 | VCC + * (ENT) | 1 2 | (BEEP) |10 9 | |10 9 | + * (RX) | 3 4 | (RX) | 8 7 | (TX) RX | 8 7 | TX + * (TX) 5 6 | (ENT) 6 5 | (BEEP) ENT | 6 5 | BEEP + * (B) | 7 8 | (A) (B) | 4 3 | (A) B | 4 3 | A + * GND | 9 10 | (VCC) GND | 2 1 | VCC GND | 2 1 | VCC * ------ ------ ------ * EXP1 DWIN DWIN (plug) * @@ -280,11 +280,11 @@ * * Board Display * ------ ------ - * (BEEPER) PB6 | 1 2 | PB5 (SD_DET) 5V | 1 2 | GND - * RESET | 3 4 | PA9 (MOD_RESET) -- | 3 4 | (SD_DET) - * PB9 5 6 | PA10 (SD_CS) (MOSI) | 5 6 | -- - * PB7 | 7 8 | PB8 (LCD_CS) (SD_CS) | 7 8 | (LCD_CS) - * GND | 9 10 | 5V (SCK) | 9 10 | (MISO) + * (BEEPER) PB6 | 1 2 | PB5 (SD_DET) 5V |10 9 | GND + * RESET | 3 4 | PA9 (MOD_RESET) -- | 8 7 | (SD_DET) + * PB9 5 6 | PA10 (SD_CS) (MOSI) | 6 5 | -- + * PB7 | 7 8 | PB8 (LCD_CS) (SD_CS) | 4 3 | (LCD_CS) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) * ------ ------ * EXP1 EXP1 * @@ -292,16 +292,16 @@ * * Board Display * - * EXP1-1 ----------- EXP1-10 - * EXP1-2 ----------- EXP1-9 - * SPI1-4 ----------- EXP1-6 - * EXP1-4 ----------- FREE - * SPI1-3 ----------- EXP1-2 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- FREE - * EXP1-8 ----------- EXP1-3 - * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-7 + * EXP1-10 ----------- EXP1-10 5V + * EXP1-9 ------------ EXP1-9 GND + * SPI1-4 ------------ EXP1-6 MOSI + * EXP1-7 ------------ n/c + * SPI1-3 ------------ EXP1-2 SCK + * EXP1-5 ------------ EXP1-4 SD_CS + * EXP1-4 ------------ n/c + * EXP1-3 ------------ EXP1-3 LCD_CS + * SPI1-1 ------------ EXP1-1 MISO + * EXP1-1 ------------ EXP1-7 SD_DET */ #define TFTGLCD_CS EXP1_03_PIN @@ -318,26 +318,26 @@ * * Board Display * ------ ------ - * (EN2) PB5 | 1 2 | PA15(BTN_ENC) 5V | 1 2 | GND - * (LCD_CS) PA9 | 3 4 | RST (RESET) -- | 3 4 | -- - * (LCD_A0) PA10 |#6 5 | PB9 (EN1) (DIN) | 6 5#| (RESET) - * (LCD_SCK)PB8 | 7 8 | PD6 (MOSI) (LCD_A0) | 7 8 | (LCD_CS) - * GND | 9 10 | 5V (BTN_ENC) | 9 10 | -- + * (EN2) PB5 | 1 2 | PA15(BTN_ENC) 5V |10 9 | GND + * (LCD_CS) PA9 | 3 4 | RST (RESET) -- | 8 7 | -- + * (LCD_A0) PA10 5 6 | PB9 (EN1) (DIN) | 6 5 (RESET) + * (LCD_SCK)PB8 | 7 8 | PD6 (MOSI) (LCD_A0) | 4 3 | (LCD_CS) + * GND | 9 10 | 5V (BTN_ENC) | 2 1 | -- * ------ ------ * EXP1 EXP1 * * ------ - * -- | 1 2 | -- - * --- (RESET) | 3 4 | -- - * | 3 | (MOSI) | 6 5#| (EN2) - * | 2 | (DIN) -- | 7 8 | (EN1) - * | 1 | (LCD_SCK)| 9 10 | -- + * -- |10 9 | -- + * --- (RESET) | 8 7 | -- + * | 3 | (MOSI) | 6 5 (EN2) + * | 2 | (DIN) -- | 4 3 | (EN1) + * | 1 | (LCD_SCK)| 2 1 | -- * --- ------ * Neopixel EXP2 * * Needs custom cable. Connect EN2-EN2, LCD_CS-LCD_CS and so on. * - * Check twice index position!!! (marked as # here) + * Check the index/notch position twice!!! * On BTT boards pins from IDC10 connector are numbered in unusual order. */ #define BTN_ENC EXP1_02_PIN @@ -372,28 +372,28 @@ * * Board Display * ------ ------ - * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V | 1 2 | GND - * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 3 4 | (SD_DET) - * (SD_CS) PA10 5 6 | PB9 (FREE) (MOSI) | 5 6 | (LCD_CS) - * (LCD_CS) PB8 | 7 8 | PB7 (FREE) (SD_CS) | 7 8 | (MOD_RESET) - * 5V | 9 10 | GND (SCK) | 9 10 | (MISO) + * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 8 7 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (FREE) (MOSI) | 6 5 | (LCD_CS) + * (LCD_CS) PB8 | 7 8 | PB7 (FREE) (SD_CS) | 4 3 | (MOD_RESET) + * 5V | 9 10 | GND (SCK) | 2 1 | (MISO) * ------ ------ * EXP1 EXP1 * * Needs custom cable: * * Board Adapter Display - * _________ - * EXP1-1 ----------- EXP1-10 - * EXP1-2 ----------- EXP1-9 - * SPI1-4 ----------- EXP1-6 - * EXP1-4 ----------- EXP1-5 - * SPI1-3 ----------- EXP1-2 - * EXP1-6 ----------- EXP1-4 - * EXP1-7 ----------- EXP1-8 - * EXP1-8 ----------- EXP1-3 - * SPI1-1 ----------- EXP1-1 - * EXP1-10 ----------- EXP1-7 + * ---------------------------------- + * EXP1-10 ----------- EXP1-10 5V + * EXP1-9 ------------ EXP1-9 GND + * SPI1-4 ------------ EXP1-6 MOSI + * EXP1-7 ------------ EXP1-5 LCD_CS + * SPI1-3 ------------ EXP1-2 SCK + * EXP1-5 ------------ EXP1-4 SD_CS + * EXP1-4 ------------ EXP1-8 RESET + * EXP1-3 ------------ EXP1-3 MOD_RST + * SPI1-1 ------------ EXP1-1 MISO + * EXP1-1 ------------ EXP1-7 SD_DET */ #define CLCD_SPI_BUS 1 // SPI1 connector diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h index f2f1fa255a..24376d6f9c 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h @@ -334,23 +334,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_08_PIN PE12 -#define EXP1_07_PIN PE11 -#define EXP1_06_PIN PE10 -#define EXP1_05_PIN PE9 -#define EXP1_04_PIN PE8 -#define EXP1_03_PIN PB1 -#define EXP1_02_PIN PB0 #define EXP1_01_PIN PC5 +#define EXP1_02_PIN PB0 +#define EXP1_03_PIN PB1 +#define EXP1_04_PIN PE8 +#define EXP1_05_PIN PE9 +#define EXP1_06_PIN PE10 +#define EXP1_07_PIN PE11 +#define EXP1_08_PIN PE12 -#define EXP2_08_PIN -1 -#define EXP2_07_PIN PC4 -#define EXP2_06_PIN PA7 -#define EXP2_05_PIN PB2 -#define EXP2_04_PIN PA4 -#define EXP2_03_PIN PE7 -#define EXP2_02_PIN PA5 #define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PE7 +#define EXP2_04_PIN PA4 +#define EXP2_05_PIN PB2 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PC4 +#define EXP2_08_PIN -1 // // Onboard SD card @@ -371,14 +371,14 @@ #endif #if ENABLED(BTT_MOTOR_EXPANSION) - /** ----- ----- - * -- | . . | GND -- | . . | GND - * -- | . . | M1EN M2EN | . . | M3EN - * M1STP | . . M1DIR M1RX | . . M1DIAG - * M2DIR | . . | M2STP M2RX | . . | M2DIAG - * M3DIR | . . | M3STP M3RX | . . | M3DIAG - * ----- ----- - * EXP2 EXP1 + /** ------ ------ + * M3DIAG | 1 2 | M3RX M3STP | 1 2 | M3DIR + * M2DIAG | 3 4 | M2RX M2STP | 3 4 | M2DIR + * M1DIAG 5 6 | M1RX M1DIR 5 6 | M1STP + * M3EN | 7 8 | M2EN M1EN | 7 8 | -- + * GND | 9 10 | -- GND | 9 10 | -- + * ------ ------ + * EXP1 EXP2 * * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN */ From 53a57ff7bf807684af09b69cd1a3e5713394e544 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Wed, 20 Jul 2022 04:08:19 -0400 Subject: [PATCH 13/54] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Archim2=20USB=20Hang?= =?UTF-8?q?=20(#24314)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 ++ Marlin/src/pins/sam/pins_ARCHIM2.h | 9 ++++++-- .../sd/usb_flashdrive/Sd2Card_FlashDrive.cpp | 22 +++++++++---------- 3 files changed, 20 insertions(+), 13 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 77e8c0ae25..e81b0c3dee 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1605,6 +1605,8 @@ //#define USE_UHS2_USB //#define USE_UHS3_USB + #define DISABLE_DUE_SD_MMC // Disable USB Host access to USB Drive to prevent hangs on block access for DUE platform + /** * Native USB Host supported by some boards (USB OTG) */ diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index ecff888ff0..310dd8e2ac 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -245,8 +245,6 @@ #define LCD_PINS_D5 54 // D54 PA16_SCK1 #define LCD_PINS_D6 68 // D68 PA1_CANRX0 #define LCD_PINS_D7 34 // D34 PC2_PWML0 - - #define SD_DETECT_PIN 2 // D2 PB25_TIOA0 #endif #if ANY(IS_ULTIPANEL, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) @@ -255,3 +253,10 @@ #define BTN_EN2 13 // D13 PB27_TIOB0 #define BTN_ENC 16 // D16 PA13_TXD1 // the click #endif + +#if ANY(HAS_WIRED_LCD, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE, USB_FLASH_DRIVE_SUPPORT) + #define SD_DETECT_PIN 2 // D2 PB25_TIOA0 + #if ENABLED(USB_FLASH_DRIVE_SUPPORT) + #define DISABLE_DUE_SD_MMC + #endif +#endif diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp index 7d698247e5..b5968b7021 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp @@ -159,18 +159,18 @@ void DiskIODriver_USBFlash::idle() { static uint8_t laststate = 232; if (task_state != laststate) { laststate = task_state; - #define UHS_USB_DEBUG(x) case UHS_STATE(x): SERIAL_ECHOLNPGM(#x); break + #define UHS_USB_DEBUG(x,y) case UHS_STATE(x): SERIAL_ECHOLNPGM(y); break switch (task_state) { - UHS_USB_DEBUG(IDLE); - UHS_USB_DEBUG(RESET_DEVICE); - UHS_USB_DEBUG(RESET_NOT_COMPLETE); - UHS_USB_DEBUG(DEBOUNCE); - UHS_USB_DEBUG(DEBOUNCE_NOT_COMPLETE); - UHS_USB_DEBUG(WAIT_SOF); - UHS_USB_DEBUG(ERROR); - UHS_USB_DEBUG(CONFIGURING); - UHS_USB_DEBUG(CONFIGURING_DONE); - UHS_USB_DEBUG(RUNNING); + UHS_USB_DEBUG(IDLE, "IDLE"); + UHS_USB_DEBUG(RESET_DEVICE, "RESET_DEVICE"); + UHS_USB_DEBUG(RESET_NOT_COMPLETE, "RESET_NOT_COMPLETE"); + UHS_USB_DEBUG(DEBOUNCE, "DEBOUNCE"); + UHS_USB_DEBUG(DEBOUNCE_NOT_COMPLETE, "DEBOUNCE_NOT_COMPLETE"); + UHS_USB_DEBUG(WAIT_SOF, "WAIT_SOF"); + UHS_USB_DEBUG(ERROR, "ERROR"); + UHS_USB_DEBUG(CONFIGURING, "CONFIGURING"); + UHS_USB_DEBUG(CONFIGURING_DONE, "CONFIGURING_DONE"); + UHS_USB_DEBUG(RUNNING, "RUNNING"); default: SERIAL_ECHOLNPGM("UHS_USB_HOST_STATE: ", task_state); break; From beacb73d93259486f66a6baf8f5809b3d0807531 Mon Sep 17 00:00:00 2001 From: Frederik Kemner Date: Wed, 20 Jul 2022 23:25:15 +0200 Subject: [PATCH 14/54] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20gcode.h=20include=20?= =?UTF-8?q?(#24527)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/temperature.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index e15e843051..9374971741 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -63,7 +63,7 @@ #include "../feature/host_actions.h" #endif -#if HAS_TEMP_SENSOR +#if EITHER(HAS_TEMP_SENSOR, LASER_FEATURE) #include "../gcode/gcode.h" #endif From c9445cfc4120ab9bcf47bdd2deffb59bcd901cad Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 22 Jul 2022 21:46:38 -0500 Subject: [PATCH 15/54] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20TFT=20image=20PACKED?= =?UTF-8?q?=20conflict?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/tft/tft_image.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/tft/tft_image.h b/Marlin/src/lcd/tft/tft_image.h index 0697510774..aeb1ca2bf5 100644 --- a/Marlin/src/lcd/tft/tft_image.h +++ b/Marlin/src/lcd/tft/tft_image.h @@ -115,12 +115,12 @@ enum colorMode_t : uint8_t { typedef colorMode_t ColorMode; #ifdef __AVR__ - #define PACKED __attribute__((__packed__)) + #define IMG_PACKED __attribute__((__packed__)) #else - #define PACKED + #define IMG_PACKED #endif -typedef struct PACKED { +typedef struct IMG_PACKED { void *data; uint16_t width; uint16_t height; From 6e02f15dd6afffb761da2516a3764a64567a8583 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 21 Jul 2022 04:18:17 -0500 Subject: [PATCH 16/54] =?UTF-8?q?=F0=9F=94=A8=20Minor=20build=20script=20c?= =?UTF-8?q?hanges?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PlatformIO/scripts/common-dependencies.py | 18 ++++++++---------- .../scripts/fix_framework_weakness.py | 2 +- .../share/PlatformIO/scripts/preprocessor.py | 5 ++++- docs/ConfigEmbedding.md | 4 ++-- 4 files changed, 15 insertions(+), 14 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.py b/buildroot/share/PlatformIO/scripts/common-dependencies.py index e9e8c79187..e8219503bd 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.py +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.py @@ -70,10 +70,9 @@ if pioutil.is_pio_build(): feat['lib_deps'] = list(filter(lib_re.match, feat['lib_deps'])) + [dep] blab("[%s] lib_deps = %s" % (feature, dep), 3) - def load_config(): + def load_features(): blab("========== Gather [features] entries...") - items = ProjectConfig().items('features') - for key in items: + for key in ProjectConfig().items('features'): feature = key[0].upper() if not feature in FEATURE_CONFIG: FEATURE_CONFIG[feature] = { 'lib_deps': [] } @@ -81,8 +80,7 @@ if pioutil.is_pio_build(): # Add options matching custom_marlin.MY_OPTION to the pile blab("========== Gather custom_marlin entries...") - all_opts = env.GetProjectOptions() - for n in all_opts: + for n in env.GetProjectOptions(): key = n[0] mat = re.match(r'custom_marlin\.(.+)', key) if mat: @@ -127,10 +125,10 @@ if pioutil.is_pio_build(): set_env_field('lib_ignore', lib_ignore) def apply_features_config(): - load_config() + load_features() blab("========== Apply enabled features...") for feature in FEATURE_CONFIG: - if not env.MarlinFeatureIsEnabled(feature): + if not env.MarlinHas(feature): continue feat = FEATURE_CONFIG[feature] @@ -212,7 +210,7 @@ if pioutil.is_pio_build(): # # Return True if a matching feature is enabled # - def MarlinFeatureIsEnabled(env, feature): + def MarlinHas(env, feature): load_marlin_features() r = re.compile('^' + feature + '$') found = list(filter(r.match, env['MARLIN_FEATURES'])) @@ -225,7 +223,7 @@ if pioutil.is_pio_build(): if val in [ '', '1', 'true' ]: some_on = True elif val in env['MARLIN_FEATURES']: - some_on = env.MarlinFeatureIsEnabled(val) + some_on = env.MarlinHas(val) return some_on @@ -239,7 +237,7 @@ if pioutil.is_pio_build(): # # Add a method for other PIO scripts to query enabled features # - env.AddMethod(MarlinFeatureIsEnabled) + env.AddMethod(MarlinHas) # # Add dependencies for enabled Marlin features diff --git a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py index 663e7c76d9..83ed17ccca 100644 --- a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py +++ b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py @@ -10,7 +10,7 @@ if pioutil.is_pio_build(): Import("env") - if env.MarlinFeatureIsEnabled("POSTMORTEM_DEBUGGING"): + if env.MarlinHas("POSTMORTEM_DEBUGGING"): FRAMEWORK_DIR = env.PioPlatform().get_package_dir("framework-arduinoststm32-maple") patchflag_path = join(FRAMEWORK_DIR, ".exc-patching-done") diff --git a/buildroot/share/PlatformIO/scripts/preprocessor.py b/buildroot/share/PlatformIO/scripts/preprocessor.py index d9c472006c..d0395cd481 100644 --- a/buildroot/share/PlatformIO/scripts/preprocessor.py +++ b/buildroot/share/PlatformIO/scripts/preprocessor.py @@ -40,7 +40,10 @@ def run_preprocessor(env, fn=None): depcmd = cmd + [ filename ] cmd = ' '.join(depcmd) blab(cmd) - define_list = subprocess.check_output(cmd, shell=True).splitlines() + try: + define_list = subprocess.check_output(cmd, shell=True).splitlines() + except: + define_list = {} preprocessor_cache[filename] = define_list return define_list diff --git a/docs/ConfigEmbedding.md b/docs/ConfigEmbedding.md index ed4ea39eda..90075bc373 100644 --- a/docs/ConfigEmbedding.md +++ b/docs/ConfigEmbedding.md @@ -1,9 +1,9 @@ # Configuration Embedding -Starting with version 2.0.9.3, Marlin automatically extracts the configuration used to generate the firmware and stores it in the firmware binary. This is enabled by defining `CONFIGURATION_EMBEDDING` in `Configuration_adv.h`. +Starting with version 2.0.9.3, Marlin can automatically extract the configuration used to generate the firmware and store it in the firmware binary. This is enabled by defining `CONFIGURATION_EMBEDDING` in `Configuration_adv.h`. ## How it's done -To create the embedded configuration, we do a compiler pass to process the Configuration files and extract all active options. The active options are parsed into key/value pairs, serialized to JSON format, and stored in a file called `marlin_config.json`, which also includes specific build information (like the git revision, the build date, and some version information. The JSON file is then compressed in a ZIP archive called `.pio/build/mc.zip` which is converted into a C array and stored in a C++ file called `mc.h` which is included in the build. +At the start of the PlatformIO build process, we create an embedded configuration by extracting all active options from the Configuration files and writing them out as JSON to `marlin_config.json`, which also includes specific build information (like the git revision, the build date, and some version information. The JSON file is then compressed in a ZIP archive called `.pio/build/mc.zip` which is converted into a C array and stored in a C++ file called `mc.h` which is included in the build. ## Extracting configurations from a Marlin binary To get the configuration out of a binary firmware, you'll need a non-write-protected SD card inserted into the printer while running the firmware. From 5b8f7686cb1d514bcddb34aaddee24f6140a97e3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 22 Jul 2022 19:30:29 -0500 Subject: [PATCH 17/54] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Fix?= =?UTF-8?q?=20and=20improve=20build=5Fall=5Fexamples?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/build_all_examples | 132 +++++++++++++++++++++++-------- buildroot/bin/build_example | 11 ++- buildroot/bin/mftest | 2 +- buildroot/bin/mfutil | 22 ++++++ buildroot/share/git/firstpush | 2 +- buildroot/share/git/mfdoc | 2 +- buildroot/share/git/mfpr | 2 +- buildroot/share/git/mfpub | 2 +- 8 files changed, 137 insertions(+), 38 deletions(-) create mode 100755 buildroot/bin/mfutil diff --git a/buildroot/bin/build_all_examples b/buildroot/bin/build_all_examples index bce95dce88..73619ab472 100755 --- a/buildroot/bin/build_all_examples +++ b/buildroot/bin/build_all_examples @@ -1,57 +1,97 @@ #!/usr/bin/env bash # -# build_all_examples base_branch [resume_point] +# Usage: # +# build_all_examples [-b|--branch=] +# [-c|--continue] +# [-d|--debug] +# [-i|--ini] +# [-l|--limit=#] +# [-n|--nobuild] +# [-r|--resume=] +# [-s|--skip] +# +# build_all_examples [...] branch [resume-from] +# + +. mfutil GITREPO=https://github.com/MarlinFirmware/Configurations.git STAT_FILE=./.pio/.buildall -# Check dependencies -which curl 1>/dev/null 2>&1 || { echo "curl not found! Please install it."; exit ; } -which git 1>/dev/null 2>&1 || { echo "git not found! Please install it."; exit ; } +usage() { echo " +Usage: $SELF [-b|--branch=] [-d|--debug] [-i|--ini] [-r|--resume=] + $SELF [-b|--branch=] [-d|--debug] [-i|--ini] [-c|--continue] + $SELF [-b|--branch=] [-d|--debug] [-i|--ini] [-s|--skip] + $SELF [-b|--branch=] [-d|--debug] [-n|--nobuild] + $SELF [...] branch [resume-point] +" +} -SED=$(command -v gsed 2>/dev/null || command -v sed 2>/dev/null) -[[ -z "$SED" ]] && { echo "No sed found, please install sed" ; exit 1 ; } +# Assume the most recent configs +BRANCH=import-2.1.x +unset FIRST_CONF +EXIT_USAGE= +LIMIT=1000 -SELF=`basename "$0"` -HERE=`dirname "$0"` +while getopts 'b:cdhil:nqr:sv-:' OFLAG; do + case "${OFLAG}" in + b) BRANCH=$OPTARG ; bugout "Branch: $BRANCH" ;; + r) FIRST_CONF="$OPTARG" ; bugout "Resume: $FIRST_CONF" ;; + c) CONTINUE=1 ; bugout "Continue" ;; + s) CONTSKIP=1 ; bugout "Continue, skipping" ;; + i) CREATE_INI=1 ; bugout "Generate an INI file" ;; + h) EXIT_USAGE=1 ; break ;; + l) LIMIT=$OPTARG ; bugout "Limit to $LIMIT build(s)" ;; + d|v) DEBUG=1 ; bugout "Debug ON" ;; + n) DRYRUN=1 ; bugout "Dry Run" ;; + -) IFS="=" read -r ONAM OVAL <<< "$OPTARG" + case "$ONAM" in + branch) BRANCH=$OVAL ; bugout "Branch: $BRANCH" ;; + resume) FIRST_CONF="$OVAL" ; bugout "Resume: $FIRST_CONF" ;; + continue) CONTINUE=1 ; bugout "Continue" ;; + skip) CONTSKIP=2 ; bugout "Continue, skipping" ;; + limit) LIMIT=$OVAL ; bugout "Limit to $LIMIT build(s)" ;; + ini) CREATE_INI=1 ; bugout "Generate an INI file" ;; + help) [[ -z "$OVAL" ]] || perror "option can't take value $OVAL" $ONAM ; EXIT_USAGE=1 ;; + debug) DEBUG=1 ; bugout "Debug ON" ;; + nobuild) DRYRUN=1 ; bugout "Dry Run" ;; + *) EXIT_USAGE=2 ; echo "$SELF: unrecognized option \`--$ONAM'" ; break ;; + esac + ;; + *) EXIT_USAGE=2 ; break ;; + esac +done -# Check if called in the right location -[[ -e "Marlin/src" ]] || { echo -e "This script must be called from a Marlin working copy with:\n ./buildroot/bin/$SELF $1" ; exit ; } +# Extra arguments count as BRANCH, FIRST_CONF +shift $((OPTIND - 1)) +[[ $# > 0 ]] && { BRANCH=$1 ; shift 1 ; bugout "BRANCH=$BRANCH" ; } +[[ $# > 0 ]] && { FIRST_CONF=$1 ; shift 1 ; bugout "FIRST_CONF=$FIRST_CONF" ; } +[[ $# > 0 ]] && { EXIT_USAGE=2 ; echo "too many arguments" ; } -if [[ $# -lt 1 || $# -gt 2 ]]; then - echo "Usage: $SELF base_branch [resume_point] - base_branch - Configuration branch to download and build - resume_point - Configuration path to start from" - exit -fi +((EXIT_USAGE)) && { usage ; let EXIT_USAGE-- ; exit $EXIT_USAGE ; } -echo "This script downloads all Configurations and builds Marlin with each one." +echo "This script downloads each Configuration and attempts to build it." echo "On failure the last-built configs will be left in your working copy." echo "Restore your configs with 'git checkout -f' or 'git reset --hard HEAD'." -unset BRANCH -unset FIRST_CONF if [[ -f "$STAT_FILE" ]]; then IFS='*' read BRANCH FIRST_CONF <"$STAT_FILE" fi # If -c is given start from the last attempted build -if [[ $1 == '-c' ]]; then +if ((CONTINUE)); then if [[ -z $BRANCH || -z $FIRST_CONF ]]; then echo "Nothing to continue" exit fi -elif [[ $1 == '-s' ]]; then +elif ((CONTSKIP)); then if [[ -n $BRANCH && -n $FIRST_CONF ]]; then SKIP_CONF=1 else echo "Nothing to skip" exit fi -else - BRANCH=${1:-"import-2.0.x"} - FIRST_CONF=$2 fi # Check if the current repository has unmerged changes @@ -69,33 +109,61 @@ TMP=./.pio/build-$BRANCH # Download Configurations into the temporary folder if [[ ! -e "$TMP/README.md" ]]; then - echo "Downloading Configurations from GitHub into $TMP" + echo "Fetching Configurations from GitHub to $TMP" git clone --depth=1 --single-branch --branch "$BRANCH" $GITREPO "$TMP" || { echo "Failed to clone the configuration repository"; exit ; } else - echo "Using previously downloaded Configurations at $TMP" + echo "Using cached Configurations at $TMP" fi -echo -e "Start building now...\n=====================" +echo -e "Start build...\n=====================" shopt -s nullglob IFS=' ' CONF_TREE=$( ls -d "$TMP"/config/examples/*/ "$TMP"/config/examples/*/*/ "$TMP"/config/examples/*/*/*/ "$TMP"/config/examples/*/*/*/*/ | grep -vE ".+\.(\w+)$" ) -DOSKIP=0 for CONF in $CONF_TREE ; do + # Get a config's directory name DIR=$( echo $CONF | sed "s|$TMP/config/examples/||" ) + # If looking for a config, skip others [[ $FIRST_CONF ]] && [[ $FIRST_CONF != $DIR && "$FIRST_CONF/" != $DIR ]] && continue # Once found, stop looking unset FIRST_CONF + # If skipping, don't build the found one [[ $SKIP_CONF ]] && { unset SKIP_CONF ; continue ; } + # ...if skipping, don't build this one compgen -G "${CONF}Con*.h" > /dev/null || continue + + # Remember where we are in case of failure echo "${BRANCH}*${DIR}" >"$STAT_FILE" - "$HERE/build_example" "internal" "$TMP" "$DIR" || { echo "Failed to build $DIR"; exit ; } + + # Build or pretend to build + if [[ $DRYRUN ]]; then + echo "[DRYRUN] build_example internal \"$TMP\" \"$DIR\"" + else + # Build folder is unknown so delete all "config.ini" files + [[ $CREATE_INI ]] && find ./.pio/build/ -name "config.ini" -exec rm "{}" \; + ((DEBUG)) && echo "\"$HERE/build_example\" \"internal\" \"$TMP\" \"$DIR\"" + "$HERE/build_example" "internal" "$TMP" "$DIR" || { echo "Failed to build $DIR"; exit ; } + # Build folder is unknown so copy any "config.ini" + [[ $CREATE_INI ]] && find ./.pio/build/ -name "config.ini" -exec cp "{}" "$CONF" \; + fi + + ((--LIMIT)) || { echo "Limit reached" ; PAUSE=1 ; break ; } + done -# Delete the temp folder and build state -[[ -e "$TMP/config/examples" ]] && rm -rf "$TMP" -rm "$STAT_FILE" +# Delete the build state if not paused early +[[ $PAUSE ]] || rm "$STAT_FILE" + +# Delete the temp folder if not preserving generated INI files +if [[ -e "$TMP/config/examples" ]]; then + if [[ $CREATE_INI ]]; then + OPEN=$( which gnome-open xdg-open open | head -n1 ) + $OPEN "$TMP" + elif [[ ! $PAUSE ]]; then + rm -rf "$TMP" + fi +fi diff --git a/buildroot/bin/build_example b/buildroot/bin/build_example index cff8ea253e..34549769bb 100755 --- a/buildroot/bin/build_example +++ b/buildroot/bin/build_example @@ -5,6 +5,8 @@ # Usage: build_example internal config-home config-folder # +. mfutil + # Require 'internal' as the first argument [[ "$1" == "internal" ]] || { echo "Don't call this script directly, use build_all_examples instead." ; exit 1 ; } @@ -22,8 +24,15 @@ cp "$SUB"/Configuration_adv.h Marlin/ 2>/dev/null cp "$SUB"/_Bootscreen.h Marlin/ 2>/dev/null cp "$SUB"/_Statusscreen.h Marlin/ 2>/dev/null +set -e + +# Strip #error lines from Configuration.h +IFS=$'\n'; set -f +$SED -i~ -e "20,30{/#error/d}" Marlin/Configuration.h +rm Marlin/Configuration.h~ +unset IFS; set +f + echo "Building the firmware now..." -HERE=`dirname "$0"` $HERE/mftest -s -a -n1 || { echo "Failed"; exit 1; } echo "Success" diff --git a/buildroot/bin/mftest b/buildroot/bin/mftest index edb4068546..8a4f3afd4f 100755 --- a/buildroot/bin/mftest +++ b/buildroot/bin/mftest @@ -3,7 +3,7 @@ # mftest Select a test to apply and build # mftest -b [#] Build the auto-detected environment # mftest -u [#] Upload the auto-detected environment -# mftest [name] [index] [-y] Set config options and optionally build a test +# mftest -tname -n# [-y] Set config options and optionally build a test # [[ -d Marlin/src ]] || { echo "Please 'cd' to the Marlin repo root." ; exit 1 ; } diff --git a/buildroot/bin/mfutil b/buildroot/bin/mfutil new file mode 100755 index 0000000000..75a2791cfe --- /dev/null +++ b/buildroot/bin/mfutil @@ -0,0 +1,22 @@ +#!/usr/bin/env bash +# +# mfutil - check env and define helpers +# + +# Check dependencies +which curl 1>/dev/null 2>&1 || { echo "curl not found! Please install it."; exit ; } +which git 1>/dev/null 2>&1 || { echo "git not found! Please install it."; exit ; } + +SED=$(command -v gsed 2>/dev/null || command -v sed 2>/dev/null) +[[ -z "$SED" ]] && { echo "No sed found, please install sed" ; exit 1 ; } + +OPEN=$( which gnome-open xdg-open open | head -n1 ) + +SELF=`basename "$0"` +HERE=`dirname "$0"` + +# Check if called in the right location +[[ -e "Marlin/src" ]] || { echo -e "This script must be called from a Marlin working copy with:\n ./buildroot/bin/$SELF $1" ; exit ; } + +perror() { echo -e "$0: \033[0;31m$1 -- $2\033[0m" ; } +bugout() { ((DEBUG)) && echo -e "\033[0;32m$1\033[0m" ; } diff --git a/buildroot/share/git/firstpush b/buildroot/share/git/firstpush index 9a68fc5afd..db025f6c52 100755 --- a/buildroot/share/git/firstpush +++ b/buildroot/share/git/firstpush @@ -16,7 +16,7 @@ BRANCH=${INFO[5]} git push --set-upstream origin HEAD:$BRANCH -OPEN=$(echo $(which gnome-open xdg-open open) | awk '{ print $1 }') +OPEN=$( which gnome-open xdg-open open | head -n1 ) URL="https://github.com/$FORK/$REPO/commits/$BRANCH" if [ -z "$OPEN" ]; then diff --git a/buildroot/share/git/mfdoc b/buildroot/share/git/mfdoc index ce21419016..29f0ec6873 100755 --- a/buildroot/share/git/mfdoc +++ b/buildroot/share/git/mfdoc @@ -17,7 +17,7 @@ BRANCH=${INFO[5]} opensite() { URL="http://127.0.0.1:4000/" - OPEN=$(echo $(which gnome-open xdg-open open) | awk '{ print $1 }') + OPEN=$( which gnome-open xdg-open open | head -n1 ) if [ -z "$OPEN" ]; then echo "Can't find a tool to open the URL:" echo $URL diff --git a/buildroot/share/git/mfpr b/buildroot/share/git/mfpr index 230bd2886c..c5eb4522c7 100755 --- a/buildroot/share/git/mfpr +++ b/buildroot/share/git/mfpr @@ -23,7 +23,7 @@ OLDBRANCH=${INFO[5]} # See if it's been pushed yet if [ -z "$(git branch -vv | grep ^\* | grep \\[origin)" ]; then firstpush; fi -OPEN=$(echo $(which gnome-open xdg-open open) | awk '{ print $1 }') +OPEN=$( which gnome-open xdg-open open | head -n1 ) URL="https://github.com/$ORG/$REPO/compare/$TARG...$FORK:$BRANCH?expand=1" if [ -z "$OPEN" ]; then diff --git a/buildroot/share/git/mfpub b/buildroot/share/git/mfpub index 6a912e5515..6ffe627b92 100755 --- a/buildroot/share/git/mfpub +++ b/buildroot/share/git/mfpub @@ -45,7 +45,7 @@ git clean -d -f opensite() { URL="$1" - OPEN=$(echo $(which gnome-open xdg-open open) | awk '{ print $1 }') + OPEN=$( which gnome-open xdg-open open | head -n1 ) if [ -z "$OPEN" ]; then echo "Can't find a tool to open the URL:" echo $URL From 89e9ae06625d6244f172f6aac628d1001abf92e7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 17 Jul 2022 22:19:24 -0500 Subject: [PATCH 18/54] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Give?= =?UTF-8?q?=20the=20simulator=20Stepper=20access?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/stepper.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 787599ce31..d8fb5af229 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -316,6 +316,8 @@ constexpr ena_mask_t enable_overlap[] = { // Stepper class definition // class Stepper { + friend class KinematicSystem; + friend class DeltaKinematicSystem; public: From 0f3c3c419e565bd16a86fbbd0a240ec55e0ae769 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 22 Jul 2022 21:59:00 -0500 Subject: [PATCH 19/54] =?UTF-8?q?=E2=9C=A8=20Reinstate=20JyersUI?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 1 + Marlin/Configuration_adv.h | 2 +- Marlin/src/MarlinCore.cpp | 2 + Marlin/src/gcode/feature/powerloss/M1000.cpp | 4 + Marlin/src/gcode/probe/G30.cpp | 6 +- Marlin/src/inc/Conditionals_LCD.h | 6 +- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/inc/SanityCheck.h | 4 +- Marlin/src/lcd/e3v2/jyersui/README.md | 7 + Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 4848 ++++++++++++++++++ Marlin/src/lcd/e3v2/jyersui/dwin.h | 245 + Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp | 64 + Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h | 34 + Marlin/src/lcd/extui/ui_api.h | 2 +- Marlin/src/lcd/marlinui.cpp | 5 +- Marlin/src/lcd/marlinui.h | 10 +- Marlin/src/module/settings.cpp | 22 + buildroot/tests/STM32F103RE_creality | 5 + ini/features.ini | 1 + 19 files changed, 5256 insertions(+), 14 deletions(-) create mode 100644 Marlin/src/lcd/e3v2/jyersui/README.md create mode 100644 Marlin/src/lcd/e3v2/jyersui/dwin.cpp create mode 100644 Marlin/src/lcd/e3v2/jyersui/dwin.h create mode 100644 Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp create mode 100644 Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 4d9bf8871f..233da942a7 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -3084,6 +3084,7 @@ // //#define DWIN_CREALITY_LCD // Creality UI //#define DWIN_LCD_PROUI // Pro UI by MRiscoC +//#define DWIN_CREALITY_LCD_JYERSUI // Jyers UI by Jacob Myers //#define DWIN_MARLINUI_PORTRAIT // MarlinUI (portrait orientation) //#define DWIN_MARLINUI_LANDSCAPE // MarlinUI (landscape orientation) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e81b0c3dee..3d69cb3feb 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1355,7 +1355,7 @@ #endif // HAS_MARLINUI_MENU -#if EITHER(HAS_DISPLAY, DWIN_LCD_PROUI) +#if ANY(HAS_DISPLAY, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) //#define SOUND_MENU_ITEM // Add a mute option to the LCD menu #define SOUND_ON_DEFAULT // Buzzer/speaker default enabled state #endif diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 099289f35b..37918f619f 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -76,6 +76,8 @@ #include "lcd/e3v2/creality/dwin.h" #elif ENABLED(DWIN_LCD_PROUI) #include "lcd/e3v2/proui/dwin.h" + #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #include "lcd/e3v2/jyersui/dwin.h" #endif #endif diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index 5466b6e127..1629a154bc 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -35,6 +35,8 @@ #include "../../../lcd/e3v2/creality/dwin.h" #elif ENABLED(DWIN_LCD_PROUI) #include "../../../lcd/e3v2/proui/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #include "../../../lcd/e3v2/jyersui/dwin.h" // Temporary fix until it can be better implemented #endif #define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY) @@ -69,6 +71,8 @@ void GcodeSuite::M1000() { ui.goto_screen(menu_job_recovery); #elif HAS_DWIN_E3V2_BASIC recovery.dwin_flag = true; + #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) // Temporary fix until it can be better implemented + CrealityDWIN.Popup_Handler(Resume); #elif ENABLED(EXTENSIBLE_UI) ExtUI::onPowerLossResume(); #else diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index eae04f2817..01e8a51f35 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -73,7 +73,9 @@ void GcodeSuite::G30() { remember_feedrate_scaling_off(); - TERN_(DWIN_LCD_PROUI, process_subcommands_now(F("G28O"))); + #if EITHER(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) + process_subcommands_now(F("G28O")); + #endif const ProbePtRaise raise_after = parser.boolval('E', true) ? PROBE_PT_STOW : PROBE_PT_NONE; @@ -82,7 +84,7 @@ void GcodeSuite::G30() { TERN_(HAS_PTC, ptc.set_enabled(true)); if (!isnan(measured_z)) { SERIAL_ECHOLNPGM("Bed X: ", pos.x, " Y: ", pos.y, " Z: ", measured_z); - #if ENABLED(DWIN_LCD_PROUI) + #if EITHER(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) char msg[31], str_1[6], str_2[6], str_3[6]; sprintf_P(msg, PSTR("X:%s, Y:%s, Z:%s"), dtostrf(pos.x, 1, 1, str_1), diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 1d3ad1c2d5..95deed7b3f 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -477,6 +477,8 @@ // Aliases for LCD features #if EITHER(DWIN_CREALITY_LCD, DWIN_LCD_PROUI) #define HAS_DWIN_E3V2_BASIC 1 +#endif +#if EITHER(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) #define HAS_DWIN_E3V2 1 #endif #if ENABLED(DWIN_LCD_PROUI) @@ -506,7 +508,7 @@ #endif #endif -#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI) +#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) #define HAS_DISPLAY 1 #endif @@ -526,7 +528,7 @@ #define HAS_MANUAL_MOVE_MENU 1 #endif -#if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL, IS_DWIN_MARLINUI) +#if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL, IS_DWIN_MARLINUI, DWIN_CREALITY_LCD_JYERSUI) #define CAN_SHOW_REMAINING_TIME 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 7d2009dc8f..1c67a43ed4 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -3430,7 +3430,7 @@ * Advanced Pause - Filament Change */ #if ENABLED(ADVANCED_PAUSE_FEATURE) - #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) + #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) #define M600_PURGE_MORE_RESUMABLE 1 #endif #ifndef FILAMENT_CHANGE_SLOW_LOAD_LENGTH diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index dff7fb88a8..ef9f3cfead 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -902,7 +902,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "PROGRESS_MSG_EXPIRE must be greater than or equal to 0." #endif #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI, HAS_DWIN_E3V2, IS_DWIN_MARLINUI) - #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_MARLINUI_*, OR EXTENSIBLE_UI." + #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_*, OR EXTENSIBLE_UI." #endif #if ENABLED(USE_M73_REMAINING_TIME) && DISABLED(LCD_SET_PROGRESS_MANUALLY) @@ -2882,7 +2882,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS, DGUS_LCD_UI_RELOADED) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY) \ - + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ + COUNT_ENABLED(MKS_12864OLED, MKS_12864OLED_SSD1306) \ diff --git a/Marlin/src/lcd/e3v2/jyersui/README.md b/Marlin/src/lcd/e3v2/jyersui/README.md new file mode 100644 index 0000000000..91f25e2433 --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/README.md @@ -0,0 +1,7 @@ +# DWIN for Creality Ender 3 v2 + +Marlin's Ender 3 v2 support requires the `DWIN_SET` included with the Ender 3 V2 [example configuration](https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.1.x/config/examples/Creality/Ender-3%20V2). + +## Easy Install + +Copy the `DWIN_SET` folder onto a Micro-SD card and insert the card into the slot on the DWIN screen. Cycle the machine and wait for the screen to go from blue to orange. Turn the machine off and remove the SD card. When you turn on the machine the screen will display a "Creality" loading screen. diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp new file mode 100644 index 0000000000..285013d750 --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -0,0 +1,4848 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/** + * lcd/e3v2/jyersui/dwin.cpp + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + +#include "dwin.h" + +#include "../../marlinui.h" +#include "../../../MarlinCore.h" + +#include "../../../gcode/gcode.h" +#include "../../../module/temperature.h" +#include "../../../module/planner.h" +#include "../../../module/settings.h" +#include "../../../libs/buzzer.h" +#include "../../../inc/Conditionals_post.h" + +//#define DEBUG_OUT 1 +#include "../../../core/debug_out.h" + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #include "../../../feature/pause.h" +#endif + +#if ENABLED(FILAMENT_RUNOUT_SENSOR) + #include "../../../feature/runout.h" +#endif + +#if ENABLED(HOST_ACTION_COMMANDS) + #include "../../../feature/host_actions.h" +#endif + +#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) + #define HAS_ZOFFSET_ITEM 1 +#endif + +#ifndef strcasecmp_P + #define strcasecmp_P(a, b) strcasecmp((a), (b)) +#endif + +#if HAS_LEVELING + #include "../../../feature/bedlevel/bedlevel.h" +#endif + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../../../libs/least_squares_fit.h" + #include "../../../libs/vector_3.h" +#endif + +#if HAS_BED_PROBE + #include "../../../module/probe.h" +#endif + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#define MACHINE_SIZE STRINGIFY(X_BED_SIZE) "x" STRINGIFY(Y_BED_SIZE) "x" STRINGIFY(Z_MAX_POS) + +#define DWIN_FONT_MENU font8x16 +#define DWIN_FONT_STAT font10x20 +#define DWIN_FONT_HEAD font10x20 + +#define MENU_CHAR_LIMIT 24 +#define STATUS_Y 352 + +#define MAX_PRINT_SPEED 500 +#define MIN_PRINT_SPEED 10 + +#if HAS_FAN + #define MAX_FAN_SPEED 255 + #define MIN_FAN_SPEED 0 +#endif + +#define MAX_XY_OFFSET 100 + +#if HAS_ZOFFSET_ITEM + #define MAX_Z_OFFSET 9.99 + #if HAS_BED_PROBE + #define MIN_Z_OFFSET -9.99 + #else + #define MIN_Z_OFFSET -1 + #endif +#endif + +#if HAS_HOTEND + #define MAX_FLOW_RATE 200 + #define MIN_FLOW_RATE 10 + + #define MAX_E_TEMP (HEATER_0_MAXTEMP - HOTEND_OVERSHOOT) + #define MIN_E_TEMP 0 +#endif + +#if HAS_HEATED_BED + #define MAX_BED_TEMP BED_MAXTEMP + #define MIN_BED_TEMP 0 +#endif + +/** + * Custom menu items with jyersLCD + */ +#if ENABLED(CUSTOM_MENU_CONFIG) + #ifdef CONFIG_MENU_ITEM_5_DESC + #define CUSTOM_MENU_COUNT 5 + #elif defined(CONFIG_MENU_ITEM_4_DESC) + #define CUSTOM_MENU_COUNT 4 + #elif defined(CONFIG_MENU_ITEM_3_DESC) + #define CUSTOM_MENU_COUNT 3 + #elif defined(CONFIG_MENU_ITEM_2_DESC) + #define CUSTOM_MENU_COUNT 2 + #elif defined(CONFIG_MENU_ITEM_1_DESC) + #define CUSTOM_MENU_COUNT 1 + #endif + #if CUSTOM_MENU_COUNT + #define HAS_CUSTOM_MENU 1 + #endif +#endif + +constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, + TITLE_HEIGHT = 30, + MLINE = 53, + LBLX = 60, + MENU_CHR_W = 8, MENU_CHR_H = 16, STAT_CHR_W = 10; + +#define MBASE(L) (49 + MLINE * (L)) + +constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; +constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; +constexpr float default_steps[] = DEFAULT_AXIS_STEPS_PER_UNIT; +#if HAS_CLASSIC_JERK + constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; +#endif + +enum SelectItem : uint8_t { + PAGE_PRINT = 0, + PAGE_PREPARE, + PAGE_CONTROL, + PAGE_INFO_LEVELING, + PAGE_COUNT, + + PRINT_SETUP = 0, + PRINT_PAUSE_RESUME, + PRINT_STOP, + PRINT_COUNT +}; + +uint8_t active_menu = MainMenu, last_menu = MainMenu; +uint8_t selection = 0, last_selection = 0; +uint8_t scrollpos = 0; +uint8_t process = Main, last_process = Main; +PopupID popup, last_popup; + +void (*funcpointer)() = nullptr; +void *valuepointer = nullptr; +float tempvalue; +float valuemin; +float valuemax; +uint8_t valueunit; +uint8_t valuetype; + +char cmd[MAX_CMD_SIZE+16], str_1[16], str_2[16], str_3[16]; +char statusmsg[64]; +char filename[LONG_FILENAME_LENGTH]; +bool printing = false; +bool paused = false; +bool sdprint = false; + +int16_t pausetemp, pausebed, pausefan; + +bool livemove = false; +bool liveadjust = false; +uint8_t preheatmode = 0; +float zoffsetvalue = 0; +uint8_t gridpoint; +float corner_avg; +float corner_pos; + +bool probe_deployed = false; + +CrealityDWINClass CrealityDWIN; + +#if HAS_MESH + + struct Mesh_Settings { + bool viewer_asymmetric_range = false; + bool viewer_print_value = false; + bool goto_mesh_value = false; + bool drawing_mesh = false; + uint8_t mesh_x = 0; + uint8_t mesh_y = 0; + + #if ENABLED(AUTO_BED_LEVELING_UBL) + uint8_t tilt_grid = 1; + + void manual_value_update(bool undefined=false) { + sprintf_P(cmd, PSTR("M421 I%i J%i Z%s %s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1), undefined ? "N" : ""); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + } + + bool create_plane_from_mesh() { + struct linear_fit_data lsf_results; + incremental_LSF_reset(&lsf_results); + GRID_LOOP(x, y) { + if (!isnan(bedlevel.z_values[x][y])) { + xy_pos_t rpos = { bedlevel.get_mesh_x(x), bedlevel.get_mesh_y(y) }; + incremental_LSF(&lsf_results, rpos, bedlevel.z_values[x][y]); + } + } + + if (finish_incremental_LSF(&lsf_results)) { + SERIAL_ECHOPGM("Could not complete LSF!"); + return true; + } + + bedlevel.set_all_mesh_points_to_value(0); + + matrix_3x3 rotation = matrix_3x3::create_look_at(vector_3(lsf_results.A, lsf_results.B, 1)); + GRID_LOOP(i, j) { + float mx = bedlevel.get_mesh_x(i), + my = bedlevel.get_mesh_y(j), + mz = bedlevel.z_values[i][j]; + + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOPAIR_F("before rotation = [", mx, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(my, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(mz, 7); + DEBUG_ECHOPGM("] ---> "); + DEBUG_DELAY(20); + } + + rotation.apply_rotation_xyz(mx, my, mz); + + if (DEBUGGING(LEVELING)) { + DEBUG_ECHOPAIR_F("after rotation = [", mx, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(my, 7); + DEBUG_CHAR(','); + DEBUG_ECHO_F(mz, 7); + DEBUG_ECHOLNPGM("]"); + DEBUG_DELAY(20); + } + + bedlevel.z_values[i][j] = mz - lsf_results.D; + } + return false; + } + + #else + + void manual_value_update() { + sprintf_P(cmd, PSTR("G29 I%i J%i Z%s"), mesh_x, mesh_y, dtostrf(current_position.z, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + } + + #endif + + void manual_mesh_move(const bool zmove=false) { + if (zmove) { + planner.synchronize(); + current_position.z = goto_mesh_value ? bedlevel.z_values[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + } + else { + CrealityDWIN.Popup_Handler(MoveWait); + sprintf_P(cmd, PSTR("G0 F300 Z%s"), dtostrf(Z_CLEARANCE_BETWEEN_PROBES, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + sprintf_P(cmd, PSTR("G42 F4000 I%i J%i"), mesh_x, mesh_y); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + current_position.z = goto_mesh_value ? bedlevel.z_values[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES; + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + CrealityDWIN.Redraw_Menu(); + } + } + + float get_max_value() { + float max = __FLT_MIN__; + GRID_LOOP(x, y) { + if (!isnan(bedlevel.z_values[x][y]) && bedlevel.z_values[x][y] > max) + max = bedlevel.z_values[x][y]; + } + return max; + } + + float get_min_value() { + float min = __FLT_MAX__; + GRID_LOOP(x, y) { + if (!isnan(bedlevel.z_values[x][y]) && bedlevel.z_values[x][y] < min) + min = bedlevel.z_values[x][y]; + } + return min; + } + + void Draw_Bed_Mesh(int16_t selected = -1, uint8_t gridline_width = 1, uint16_t padding_x = 8, uint16_t padding_y_top = 40 + 53 - 7) { + drawing_mesh = true; + const uint16_t total_width_px = DWIN_WIDTH - padding_x - padding_x, + cell_width_px = total_width_px / (GRID_MAX_POINTS_X), + cell_height_px = total_width_px / (GRID_MAX_POINTS_Y); + const float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = _MAX(v_min, v_max); + + // Clear background from previous selection and select new square + DWIN_Draw_Rectangle(1, Color_Bg_Black, _MAX(0, padding_x - gridline_width), _MAX(0, padding_y_top - gridline_width), padding_x + total_width_px, padding_y_top + total_width_px); + if (selected >= 0) { + const auto selected_y = selected / (GRID_MAX_POINTS_X); + const auto selected_x = selected - (GRID_MAX_POINTS_X) * selected_y; + const auto start_y_px = padding_y_top + selected_y * cell_height_px; + const auto start_x_px = padding_x + selected_x * cell_width_px; + DWIN_Draw_Rectangle(1, Color_White, _MAX(0, start_x_px - gridline_width), _MAX(0, start_y_px - gridline_width), start_x_px + cell_width_px, start_y_px + cell_height_px); + } + + // Draw value square grid + char buf[8]; + GRID_LOOP(x, y) { + const auto start_x_px = padding_x + x * cell_width_px; + const auto end_x_px = start_x_px + cell_width_px - 1 - gridline_width; + const auto start_y_px = padding_y_top + (GRID_MAX_POINTS_Y - y - 1) * cell_height_px; + const auto end_y_px = start_y_px + cell_height_px - 1 - gridline_width; + DWIN_Draw_Rectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/ + isnan(bedlevel.z_values[x][y]) ? Color_Grey : ( // gray if undefined + (bedlevel.z_values[x][y] < 0 ? + (uint16_t)round(0x1F * -bedlevel.z_values[x][y] / (!viewer_asymmetric_range ? range : v_min)) << 11 : // red if mesh point value is negative + (uint16_t)round(0x3F * bedlevel.z_values[x][y] / (!viewer_asymmetric_range ? range : v_max)) << 5) | // green if mesh point value is positive + _MIN(0x1F, (((uint8_t)abs(bedlevel.z_values[x][y]) / 10) * 4))), // + blue stepping for every mm + start_x_px, start_y_px, end_x_px, end_y_px + ); + + safe_delay(10); + LCD_SERIAL.flushTX(); + + // Draw value text on + if (viewer_print_value) { + int8_t offset_x, offset_y = cell_height_px / 2 - 6; + if (isnan(bedlevel.z_values[x][y])) { // undefined + DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); + } + else { // has value + if (GRID_MAX_POINTS_X < 10) + sprintf_P(buf, PSTR("%s"), dtostrf(abs(bedlevel.z_values[x][y]), 1, 2, str_1)); + else + sprintf_P(buf, PSTR("%02i"), (uint16_t)(abs(bedlevel.z_values[x][y] - (int16_t)bedlevel.z_values[x][y]) * 100)); + offset_x = cell_width_px / 2 - 3 * (strlen(buf)) - 2; + if (!(GRID_MAX_POINTS_X < 10)) + DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px - 2 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, F(".")); + DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + 1 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, buf); + } + safe_delay(10); + LCD_SERIAL.flushTX(); + } + } + } + + void Set_Mesh_Viewer_Status() { // TODO: draw gradient with values as a legend instead + float v_max = abs(get_max_value()), v_min = abs(get_min_value()), range = _MAX(v_min, v_max); + if (v_min > 3e+10F) v_min = 0.0000001; + if (v_max > 3e+10F) v_max = 0.0000001; + if (range > 3e+10F) range = 0.0000001; + char msg[46]; + if (viewer_asymmetric_range) { + dtostrf(-v_min, 1, 3, str_1); + dtostrf( v_max, 1, 3, str_2); + } + else { + dtostrf(-range, 1, 3, str_1); + dtostrf( range, 1, 3, str_2); + } + sprintf_P(msg, PSTR("Red %s..0..%s Green"), str_1, str_2); + CrealityDWIN.Update_Status(msg); + drawing_mesh = false; + } + + }; + Mesh_Settings mesh_conf; + +#endif // HAS_MESH + +/* General Display Functions */ + +struct CrealityDWINClass::EEPROM_Settings CrealityDWINClass::eeprom_settings{0}; +constexpr const char * const CrealityDWINClass::color_names[11]; +constexpr const char * const CrealityDWINClass::preheat_modes[3]; + +// Clear a part of the screen +// 4=Entire screen +// 3=Title bar and Menu area (default) +// 2=Menu area +// 1=Title bar +void CrealityDWINClass::Clear_Screen(uint8_t e/*=3*/) { + if (e == 1 || e == 3 || e == 4) DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.menu_top_bg, Color_Bg_Blue, false), 0, 0, DWIN_WIDTH, TITLE_HEIGHT); // Clear Title Bar + if (e == 2 || e == 3) DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, STATUS_Y); // Clear Menu Area + if (e == 4) DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); // Clear Popup Area +} + +void CrealityDWINClass::Draw_Float(float value, uint8_t row, bool selected/*=false*/, uint8_t minunit/*=10*/) { + const uint8_t digits = (uint8_t)floor(log10(abs(value))) + log10(minunit) + (minunit > 1); + const uint16_t bColor = (selected) ? Select_Color : Color_Bg_Black; + const uint16_t xpos = 240 - (digits * 8); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 194, MBASE(row), 234 - (digits * 8), MBASE(row) + 16); + if (isnan(value)) + DWIN_Draw_String(true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), F(" NaN")); + else { + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, Color_White, bColor, digits - log10(minunit) + 1, log10(minunit), xpos, MBASE(row), (value < 0 ? -value : value)); + DWIN_Draw_String(true, DWIN_FONT_MENU, Color_White, bColor, xpos - 8, MBASE(row), value < 0 ? F("-") : F(" ")); + } +} + +void CrealityDWINClass::Draw_Option(uint8_t value, const char * const * options, uint8_t row, bool selected/*=false*/, bool color/*=false*/) { + uint16_t bColor = (selected) ? Select_Color : Color_Bg_Black, + tColor = (color) ? GetColor(value, Color_White, false) : Color_White; + DWIN_Draw_Rectangle(1, bColor, 202, MBASE(row) + 14, 258, MBASE(row) - 2); + DWIN_Draw_String(false, DWIN_FONT_MENU, tColor, bColor, 202, MBASE(row) - 1, options[value]); +} + +uint16_t CrealityDWINClass::GetColor(uint8_t color, uint16_t original, bool light/*=false*/) { + switch (color) { + case Default: + return original; + break; + case White: + return (light) ? Color_Light_White : Color_White; + break; + case Green: + return (light) ? Color_Light_Green : Color_Green; + break; + case Cyan: + return (light) ? Color_Light_Cyan : Color_Cyan; + break; + case Blue: + return (light) ? Color_Light_Blue : Color_Blue; + break; + case Magenta: + return (light) ? Color_Light_Magenta : Color_Magenta; + break; + case Red: + return (light) ? Color_Light_Red : Color_Red; + break; + case Orange: + return (light) ? Color_Light_Orange : Color_Orange; + break; + case Yellow: + return (light) ? Color_Light_Yellow : Color_Yellow; + break; + case Brown: + return (light) ? Color_Light_Brown : Color_Brown; + break; + case Black: + return Color_Black; + break; + } + return Color_White; +} + +void CrealityDWINClass::Draw_Title(const char * ctitle) { + DWIN_Draw_String(false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen(ctitle) * STAT_CHR_W) / 2, 5, ctitle); +} +void CrealityDWINClass::Draw_Title(FSTR_P const ftitle) { + DWIN_Draw_String(false, DWIN_FONT_HEAD, GetColor(eeprom_settings.menu_top_txt, Color_White, false), Color_Bg_Blue, (DWIN_WIDTH - strlen_P(FTOP(ftitle)) * STAT_CHR_W) / 2, 5, ftitle); +} + +void _Decorate_Menu_Item(uint8_t row, uint8_t icon, bool more) { + if (icon) DWIN_ICON_Show(ICON, icon, 26, MBASE(row) - 3); //Draw Menu Icon + if (more) DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(row) - 3); // Draw More Arrow + DWIN_Draw_Line(CrealityDWIN.GetColor(CrealityDWIN.eeprom_settings.menu_split_line, Line_Color, true), 16, MBASE(row) + 33, 256, MBASE(row) + 33); // Draw Menu Line +} + +void CrealityDWINClass::Draw_Menu_Item(uint8_t row, uint8_t icon/*=0*/, const char * label1, const char * label2, bool more/*=false*/, bool centered/*=false*/) { + const uint8_t label_offset_y = (label1 || label2) ? MENU_CHR_H * 3 / 5 : 0, + label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label1 ? strlen(label1) : 0) * MENU_CHR_W) / 2), + label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (label2 ? strlen(label2) : 0) * MENU_CHR_W) / 2); + if (label1) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, label1); // Draw Label + if (label2) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, label2); // Draw Label + _Decorate_Menu_Item(row, icon, more); +} + +void CrealityDWINClass::Draw_Menu_Item(uint8_t row, uint8_t icon/*=0*/, FSTR_P const flabel1, FSTR_P const flabel2, bool more/*=false*/, bool centered/*=false*/) { + const uint8_t label_offset_y = (flabel1 || flabel2) ? MENU_CHR_H * 3 / 5 : 0, + label1_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (flabel1 ? strlen_P(FTOP(flabel1)) : 0) * MENU_CHR_W) / 2), + label2_offset_x = !centered ? LBLX : LBLX * 4/5 + _MAX(LBLX * 1U/5, (DWIN_WIDTH - LBLX - (flabel2 ? strlen_P(FTOP(flabel2)) : 0) * MENU_CHR_W) / 2); + if (flabel1) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label1_offset_x, MBASE(row) - 1 - label_offset_y, flabel1); // Draw Label + if (flabel2) DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, label2_offset_x, MBASE(row) - 1 + label_offset_y, flabel2); // Draw Label + _Decorate_Menu_Item(row, icon, more); +} + +void CrealityDWINClass::Draw_Checkbox(uint8_t row, bool value) { + #if ENABLED(DWIN_CREALITY_LCD_CUSTOM_ICONS) // Draw appropriate checkbox icon + DWIN_ICON_Show(ICON, (value ? ICON_Checkbox_T : ICON_Checkbox_F), 226, MBASE(row) - 3); + #else // Draw a basic checkbox using rectangles and lines + DWIN_Draw_Rectangle(1, Color_Bg_Black, 226, MBASE(row) - 3, 226 + 20, MBASE(row) - 3 + 20); + DWIN_Draw_Rectangle(0, Color_White, 226, MBASE(row) - 3, 226 + 20, MBASE(row) - 3 + 20); + if (value) { + DWIN_Draw_Line(Check_Color, 227, MBASE(row) - 3 + 11, 226 + 8, MBASE(row) - 3 + 17); + DWIN_Draw_Line(Check_Color, 227 + 8, MBASE(row) - 3 + 17, 226 + 19, MBASE(row) - 3 + 1); + DWIN_Draw_Line(Check_Color, 227, MBASE(row) - 3 + 12, 226 + 8, MBASE(row) - 3 + 18); + DWIN_Draw_Line(Check_Color, 227 + 8, MBASE(row) - 3 + 18, 226 + 19, MBASE(row) - 3 + 2); + DWIN_Draw_Line(Check_Color, 227, MBASE(row) - 3 + 13, 226 + 8, MBASE(row) - 3 + 19); + DWIN_Draw_Line(Check_Color, 227 + 8, MBASE(row) - 3 + 19, 226 + 19, MBASE(row) - 3 + 3); + } + #endif +} + +void CrealityDWINClass::Draw_Menu(uint8_t menu, uint8_t select/*=0*/, uint8_t scroll/*=0*/) { + if (active_menu != menu) { + last_menu = active_menu; + if (process == Menu) last_selection = selection; + } + selection = _MIN(select, Get_Menu_Size(menu)); + scrollpos = scroll; + if (selection - scrollpos > MROWS) + scrollpos = selection - MROWS; + process = Menu; + active_menu = menu; + Clear_Screen(); + Draw_Title(Get_Menu_Title(menu)); + LOOP_L_N(i, TROWS) Menu_Item_Handler(menu, i + scrollpos); + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); +} + +void CrealityDWINClass::Redraw_Menu(bool lastprocess/*=true*/, bool lastselection/*=false*/, bool lastmenu/*=false*/) { + switch ((lastprocess) ? last_process : process) { + case Menu: + Draw_Menu((lastmenu) ? last_menu : active_menu, (lastselection) ? last_selection : selection, (lastmenu) ? 0 : scrollpos); + break; + case Main: Draw_Main_Menu((lastselection) ? last_selection : selection); break; + case Print: Draw_Print_Screen(); break; + case File: Draw_SD_List(); break; + default: break; + } +} + +void CrealityDWINClass::Redraw_Screen() { + Redraw_Menu(false); + Draw_Status_Area(true); + Update_Status_Bar(true); +} + +/* Primary Menus and Screen Elements */ + +void CrealityDWINClass::Main_Menu_Icons() { + if (selection == 0) { + DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 17, 130, 126, 229); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); + } + else { + DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 52, 200, F("Print")); + } + if (selection == 1) { + DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 130, 254, 229); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); + } + else { + DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 170, 200, F("Prepare")); + } + if (selection == 2) { + DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 17, 246, 126, 345); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); + } + else { + DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 43, 317, F("Control")); + } + #if HAS_ABL_OR_UBL + if (selection == 3) { + DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 246, 254, 345); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); + } + else { + DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 179, 317, F("Level")); + } + #else + if (selection == 3) { + DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 145, 246, 254, 345); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); + } + else { + DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 181, 317, F("Info")); + } + #endif +} + +void CrealityDWINClass::Draw_Main_Menu(uint8_t select/*=0*/) { + process = Main; + active_menu = MainMenu; + selection = select; + Clear_Screen(); + Draw_Title(Get_Menu_Title(MainMenu)); + SERIAL_ECHOPGM("\nDWIN handshake "); + DWIN_ICON_Show(ICON, ICON_LOGO, 71, 72); + Main_Menu_Icons(); +} + +void CrealityDWINClass::Print_Screen_Icons() { + if (selection == 0) { + DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 8, 252, 87, 351); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); + } + else { + DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 30, 322, F("Tune")); + } + if (selection == 2) { + DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 184, 252, 263, 351); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); + } + else { + DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 205, 322, F("Stop")); + } + if (paused) { + if (selection == 1) { + DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 96, 252, 175, 351); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); + } + else { + DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Print")); + } + } + else { + if (selection == 1) { + DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 96, 252, 175, 351); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); + } + else { + DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Blue, 114, 322, F("Pause")); + } + } +} + +void CrealityDWINClass::Draw_Print_Screen() { + process = Print; + selection = 0; + Clear_Screen(); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); + Draw_Title("Printing..."); + Print_Screen_Icons(); + DWIN_ICON_Show(ICON, ICON_PrintTime, 14, 171); + DWIN_ICON_Show(ICON, ICON_RemainTime, 147, 169); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 41, 163, F("Elapsed")); + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, 176, 163, F("Remaining")); + Update_Status_Bar(true); + Draw_Print_ProgressBar(); + Draw_Print_ProgressElapsed(); + TERN_(USE_M73_REMAINING_TIME, Draw_Print_ProgressRemain()); + Draw_Print_Filename(true); +} + +void CrealityDWINClass::Draw_Print_Filename(const bool reset/*=false*/) { + static uint8_t namescrl = 0; + if (reset) namescrl = 0; + if (process == Print) { + constexpr int8_t maxlen = 30; + char *outstr = filename; + size_t slen = strlen(filename); + int8_t outlen = slen; + if (slen > maxlen) { + char dispname[maxlen + 1]; + int8_t pos = slen - namescrl, len = maxlen; + if (pos >= 0) { + NOMORE(len, pos); + LOOP_L_N(i, len) dispname[i] = filename[i + namescrl]; + } + else { + const int8_t mp = maxlen + pos; + LOOP_L_N(i, mp) dispname[i] = ' '; + LOOP_S_L_N(i, mp, maxlen) dispname[i] = filename[i - mp]; + if (mp <= 0) namescrl = 0; + } + dispname[len] = '\0'; + outstr = dispname; + outlen = maxlen; + namescrl++; + } + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 50, DWIN_WIDTH - 8, 80); + const int8_t npos = (DWIN_WIDTH - outlen * MENU_CHR_W) / 2; + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, outstr); + } +} + +void CrealityDWINClass::Draw_Print_ProgressBar() { + uint8_t printpercent = sdprint ? card.percentDone() : (ui._get_progress() / 100); + DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); + DWIN_Draw_Rectangle(1, BarFill_Color, 16 + printpercent * 240 / 100, 93, 256, 113); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_percent, Percent_Color), Color_Bg_Black, 3, 109, 133, printpercent); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_percent, Percent_Color), Color_Bg_Black, 133, 133, F("%")); +} + +#if ENABLED(USE_M73_REMAINING_TIME) + + void CrealityDWINClass::Draw_Print_ProgressRemain() { + uint16_t remainingtime = ui.get_remaining_time(); + DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 176, 187, remainingtime / 3600); + DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 200, 187, (remainingtime % 3600) / 60); + if (eeprom_settings.time_format_textual) { + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, F("h")); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 216, 187, F("m")); + } + else + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 192, 187, F(":")); + } + +#endif + +void CrealityDWINClass::Draw_Print_ProgressElapsed() { + duration_t elapsed = print_job_timer.duration(); + DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 42, 187, elapsed.value / 3600); + DWIN_Draw_IntValue(true, true, 1, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 2, 66, 187, (elapsed.value % 3600) / 60); + if (eeprom_settings.time_format_textual) { + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, F("h")); + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 82, 187, F("m")); + } + else + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.progress_time, Color_White), Color_Bg_Black, 58, 187, F(":")); +} + +void CrealityDWINClass::Draw_Print_confirm() { + Draw_Print_Screen(); + process = Confirm; + popup = Complete; + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 252, 263, 351); + DWIN_ICON_Show(ICON, ICON_Confirm_E, 87, 283); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 86, 282, 187, 321); + DWIN_Draw_Rectangle(0, GetColor(eeprom_settings.highlight_box, Color_White), 85, 281, 188, 322); +} + +void CrealityDWINClass::Draw_SD_Item(uint8_t item, uint8_t row) { + if (item == 0) + Draw_Menu_Item(0, ICON_Back, card.flag.workDirIsRoot ? F("Back") : F("..")); + else { + card.getfilename_sorted(SD_ORDER(item - 1, card.get_num_Files())); + char * const filename = card.longest_filename(); + size_t max = MENU_CHAR_LIMIT; + size_t pos = strlen(filename), len = pos; + if (!card.flag.filenameIsDir) + while (pos && filename[pos] != '.') pos--; + len = pos; + if (len > max) len = max; + char name[len + 1]; + LOOP_L_N(i, len) name[i] = filename[i]; + if (pos > max) + LOOP_S_L_N(i, len - 3, len) name[i] = '.'; + name[len] = '\0'; + Draw_Menu_Item(row, card.flag.filenameIsDir ? ICON_More : ICON_File, name); + } +} + +void CrealityDWINClass::Draw_SD_List(bool removed/*=false*/) { + Clear_Screen(); + Draw_Title("Select File"); + selection = 0; + scrollpos = 0; + process = File; + if (card.isMounted() && !removed) { + LOOP_L_N(i, _MIN(card.get_num_Files() + 1, TROWS)) + Draw_SD_Item(i, i); + } + else { + Draw_Menu_Item(0, ICON_Back, F("Back")); + DWIN_Draw_Rectangle(1, Color_Bg_Red, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); + DWIN_Draw_String(false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), F("No Media")); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(0) - 18, 14, MBASE(0) + 33); +} + +void CrealityDWINClass::Draw_Status_Area(bool icons/*=false*/) { + + if (icons) DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); + + #if HAS_HOTEND + static float hotend = -1; + static int16_t hotendtarget = -1, flow = -1; + if (icons) { + hotend = -1; + hotendtarget = -1; + DWIN_ICON_Show(ICON, ICON_HotendTemp, 10, 383); + DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 384, F("/")); + } + if (thermalManager.temp_hotend[0].celsius != hotend) { + hotend = thermalManager.temp_hotend[0].celsius; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 28, 384, thermalManager.temp_hotend[0].celsius); + DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 3 * STAT_CHR_W + 5, 386); + } + if (thermalManager.temp_hotend[0].target != hotendtarget) { + hotendtarget = thermalManager.temp_hotend[0].target; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 384, thermalManager.temp_hotend[0].target); + DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 4 * STAT_CHR_W + 39, 386); + } + if (icons) { + flow = -1; + DWIN_ICON_Show(ICON, ICON_StepE, 112, 417); + DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 417, F("%")); + } + if (planner.flow_percentage[0] != flow) { + flow = planner.flow_percentage[0]; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 417, planner.flow_percentage[0]); + } + #endif + + #if HAS_HEATED_BED + static float bed = -1; + static int16_t bedtarget = -1; + if (icons) { + bed = -1; + bedtarget = -1; + DWIN_ICON_Show(ICON, ICON_BedTemp, 10, 416); + DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 25 + 3 * STAT_CHR_W + 5, 417, F("/")); + } + if (thermalManager.temp_bed.celsius != bed) { + bed = thermalManager.temp_bed.celsius; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 28, 417, thermalManager.temp_bed.celsius); + DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 3 * STAT_CHR_W + 5, 419); + } + if (thermalManager.temp_bed.target != bedtarget) { + bedtarget = thermalManager.temp_bed.target; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 25 + 4 * STAT_CHR_W + 6, 417, thermalManager.temp_bed.target); + DWIN_Draw_DegreeSymbol(GetColor(eeprom_settings.status_area_text, Color_White), 25 + 4 * STAT_CHR_W + 39, 419); + } + #endif + + #if HAS_FAN + static uint8_t fan = -1; + if (icons) { + fan = -1; + DWIN_ICON_Show(ICON, ICON_FanSpeed, 187, 383); + } + if (thermalManager.fan_speed[0] != fan) { + fan = thermalManager.fan_speed[0]; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 195 + 2 * STAT_CHR_W, 384, thermalManager.fan_speed[0]); + } + #endif + + #if HAS_ZOFFSET_ITEM + static float offset = -1; + + if (icons) { + offset = -1; + DWIN_ICON_Show(ICON, ICON_Zoffset, 187, 416); + } + if (zoffsetvalue != offset) { + offset = zoffsetvalue; + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 2, 2, 207, 417, (zoffsetvalue < 0 ? -zoffsetvalue : zoffsetvalue)); + DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 205, 419, zoffsetvalue < 0 ? F("-") : F(" ")); + } + #endif + + static int16_t feedrate = -1; + if (icons) { + feedrate = -1; + DWIN_ICON_Show(ICON, ICON_Speed, 113, 383); + DWIN_Draw_String(false, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 116 + 5 * STAT_CHR_W + 2, 384, F("%")); + } + if (feedrate_percentage != feedrate) { + feedrate = feedrate_percentage; + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, GetColor(eeprom_settings.status_area_text, Color_White), Color_Bg_Black, 3, 116 + 2 * STAT_CHR_W, 384, feedrate_percentage); + } + + static float x = -1, y = -1, z = -1; + static bool update_x = false, update_y = false, update_z = false; + update_x = (current_position.x != x || axis_should_home(X_AXIS) || update_x); + update_y = (current_position.y != y || axis_should_home(Y_AXIS) || update_y); + update_z = (current_position.z != z || axis_should_home(Z_AXIS) || update_z); + if (icons) { + x = y = z = -1; + DWIN_Draw_Line(GetColor(eeprom_settings.coordinates_split_line, Line_Color, true), 16, 450, 256, 450); + DWIN_ICON_Show(ICON, ICON_MaxSpeedX, 10, 456); + DWIN_ICON_Show(ICON, ICON_MaxSpeedY, 95, 456); + DWIN_ICON_Show(ICON, ICON_MaxSpeedZ, 180, 456); + } + if (update_x) { + x = current_position.x; + if ((update_x = axis_should_home(X_AXIS) && ui.get_blink())) + DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 35, 459, F(" -?- ")); + else + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 1, 35, 459, current_position.x); + } + if (update_y) { + y = current_position.y; + if ((update_y = axis_should_home(Y_AXIS) && ui.get_blink())) + DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 120, 459, F(" -?- ")); + else + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 1, 120, 459, current_position.y); + } + if (update_z) { + z = current_position.z; + if ((update_z = axis_should_home(Z_AXIS) && ui.get_blink())) + DWIN_Draw_String(true, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 205, 459, F(" -?- ")); + else + DWIN_Draw_FloatValue(true, true, 0, DWIN_FONT_MENU, GetColor(eeprom_settings.coordinates_text, Color_White), Color_Bg_Black, 3, 2, 205, 459, (current_position.z>=0) ? current_position.z : 0); + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Draw_Popup(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, uint8_t mode, uint8_t icon/*=0*/) { + if (process != Confirm && process != Popup && process != Wait) last_process = process; + if ((process == Menu || process == Wait) && mode == Popup) last_selection = selection; + process = mode; + Clear_Screen(); + DWIN_Draw_Rectangle(0, Color_White, 13, 59, 259, 351); + DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 60, 258, 350); + const uint8_t ypos = (mode == Popup || mode == Confirm) ? 150 : 230; + if (icon > 0) DWIN_ICON_Show(ICON, icon, 101, 105); + DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(FTOP(line1))) / 2, ypos, line1); + DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(FTOP(line2))) / 2, ypos + 30, line2); + DWIN_Draw_String(true, DWIN_FONT_MENU, Popup_Text_Color, Color_Bg_Window, (272 - 8 * strlen_P(FTOP(line3))) / 2, ypos + 60, line3); + if (mode == Popup) { + selection = 0; + DWIN_Draw_Rectangle(1, Confirm_Color, 26, 280, 125, 317); + DWIN_Draw_Rectangle(1, Cancel_Color, 146, 280, 245, 317); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 39, 290, F("Confirm")); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 165, 290, F("Cancel")); + Popup_Select(); + } + else if (mode == Confirm) { + DWIN_Draw_Rectangle(1, Confirm_Color, 87, 280, 186, 317); + DWIN_Draw_String(false, DWIN_FONT_STAT, Color_White, Color_Bg_Window, 96, 290, F("Continue")); + } +} + +void MarlinUI::kill_screen(FSTR_P const error, FSTR_P const) { + CrealityDWIN.Draw_Popup(F("Printer Kill Reason:"), error, F("Restart Required"), Wait, ICON_BLTouch); +} + +void CrealityDWINClass::Popup_Select() { + const uint16_t c1 = (selection == 0) ? GetColor(eeprom_settings.highlight_box, Color_White) : Color_Bg_Window, + c2 = (selection == 0) ? Color_Bg_Window : GetColor(eeprom_settings.highlight_box, Color_White); + DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); + DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); + DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); + DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); +} + +void CrealityDWINClass::Update_Status_Bar(bool refresh/*=false*/) { + static bool new_msg; + static uint8_t msgscrl = 0; + static char lastmsg[64]; + if (strcmp(lastmsg, statusmsg) != 0 || refresh) { + strcpy(lastmsg, statusmsg); + msgscrl = 0; + new_msg = true; + } + size_t len = strlen(statusmsg); + int8_t pos = len; + if (pos > 30) { + pos -= msgscrl; + len = pos; + if (len > 30) + len = 30; + char dispmsg[len + 1]; + if (pos >= 0) { + LOOP_L_N(i, len) dispmsg[i] = statusmsg[i + msgscrl]; + } + else { + LOOP_L_N(i, 30 + pos) dispmsg[i] = ' '; + LOOP_S_L_N(i, 30 + pos, 30) dispmsg[i] = statusmsg[i - (30 + pos)]; + } + dispmsg[len] = '\0'; + if (process == Print) { + DWIN_Draw_Rectangle(1, Color_Grey, 8, 214, DWIN_WIDTH - 8, 238); + const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, dispmsg); + } + else { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); + const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, dispmsg); + } + if (-pos >= 30) msgscrl = 0; + msgscrl++; + } + else { + if (new_msg) { + new_msg = false; + if (process == Print) { + DWIN_Draw_Rectangle(1, Color_Grey, 8, 214, DWIN_WIDTH - 8, 238); + const int8_t npos = (DWIN_WIDTH - strlen(statusmsg) * MENU_CHR_W) / 2; + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 219, statusmsg); + } + else { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 352, DWIN_WIDTH - 8, 376); + const int8_t npos = (DWIN_WIDTH - strlen(statusmsg) * MENU_CHR_W) / 2; + DWIN_Draw_String(false, DWIN_FONT_MENU, GetColor(eeprom_settings.status_bar_text, Color_White), Color_Bg_Black, npos, 357, statusmsg); + } + } + } +} + +/* Menu Item Config */ + +void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/*=true*/) { + const uint8_t row = item - scrollpos; + #if HAS_LEVELING + static bool level_state; + #endif + + #if HAS_PREHEAT + + #define PREHEAT_BACK 0 + #define PREHEAT_SUBMENU_HOTEND (PREHEAT_BACK + ENABLED(HAS_HOTEND)) + #define PREHEAT_SUBMENU_BED (PREHEAT_SUBMENU_HOTEND + ENABLED(HAS_HEATED_BED)) + #define PREHEAT_SUBMENU_FAN (PREHEAT_SUBMENU_BED + ENABLED(HAS_FAN)) + #define PREHEAT_SUBMENU_TOTAL PREHEAT_SUBMENU_FAN + + auto preheat_submenu = [&](const int index, const uint8_t item, const uint8_t sel) { + switch (item) { + case PREHEAT_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(TempMenu, sel); + break; + #if HAS_HOTEND + case PREHEAT_SUBMENU_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); + Draw_Float(ui.material_preset[index].hotend_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[index].hotend_temp, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + #if HAS_HEATED_BED + case PREHEAT_SUBMENU_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); + Draw_Float(ui.material_preset[index].bed_temp, row, false, 1); + } + else + Modify_Value(ui.material_preset[index].bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + #if HAS_FAN + case PREHEAT_SUBMENU_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); + Draw_Float(ui.material_preset[index].fan_speed, row, false, 1); + } + else + Modify_Value(ui.material_preset[index].fan_speed, MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + } + }; + + #endif + + switch (menu) { + case Prepare: + + #define PREPARE_BACK 0 + #define PREPARE_MOVE (PREPARE_BACK + 1) + #define PREPARE_DISABLE (PREPARE_MOVE + 1) + #define PREPARE_HOME (PREPARE_DISABLE + 1) + #define PREPARE_MANUALLEVEL (PREPARE_HOME + 1) + #define PREPARE_ZOFFSET (PREPARE_MANUALLEVEL + ENABLED(HAS_ZOFFSET_ITEM)) + #define PREPARE_PREHEAT (PREPARE_ZOFFSET + ENABLED(HAS_PREHEAT)) + #define PREPARE_COOLDOWN (PREPARE_PREHEAT + EITHER(HAS_HOTEND, HAS_HEATED_BED)) + #define PREPARE_CHANGEFIL (PREPARE_COOLDOWN + ENABLED(ADVANCED_PAUSE_FEATURE)) + #define PREPARE_CUSTOM_MENU (PREPARE_CHANGEFIL + ENABLED(HAS_CUSTOM_MENU)) + #define PREPARE_TOTAL PREPARE_CUSTOM_MENU + + switch (item) { + case PREPARE_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Main_Menu(1); + break; + case PREPARE_MOVE: + if (draw) + Draw_Menu_Item(row, ICON_Axis, F("Move"), nullptr, true); + else + Draw_Menu(Move); + break; + case PREPARE_DISABLE: + if (draw) + Draw_Menu_Item(row, ICON_CloseMotor, F("Disable Stepper")); + else + queue.inject(F("M84")); + break; + case PREPARE_HOME: + if (draw) + Draw_Menu_Item(row, ICON_SetHome, F("Homing"), nullptr, true); + else + Draw_Menu(HomeMenu); + break; + case PREPARE_MANUALLEVEL: + if (draw) + Draw_Menu_Item(row, ICON_PrintSize, F("Manual Leveling"), nullptr, true); + else { + if (axes_should_home()) { + Popup_Handler(Home); + gcode.home_all_axes(true); + } + #if HAS_LEVELING + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + #endif + Draw_Menu(ManualLevel); + } + break; + + #if HAS_ZOFFSET_ITEM + case PREPARE_ZOFFSET: + if (draw) + Draw_Menu_Item(row, ICON_Zoffset, F("Z-Offset"), nullptr, true); + else { + #if HAS_LEVELING + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + #endif + Draw_Menu(ZOffset); + } + break; + #endif + + #if HAS_PREHEAT + case PREPARE_PREHEAT: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, F("Preheat"), nullptr, true); + else + Draw_Menu(Preheat); + break; + #endif + + #if HAS_HOTEND || HAS_HEATED_BED + case PREPARE_COOLDOWN: + if (draw) + Draw_Menu_Item(row, ICON_Cool, F("Cooldown")); + else + thermalManager.cooldown(); + break; + #endif + + #if HAS_CUSTOM_MENU + case PREPARE_CUSTOM_MENU: + #ifndef CUSTOM_MENU_CONFIG_TITLE + #define CUSTOM_MENU_CONFIG_TITLE "Custom Commands" + #endif + if (draw) + Draw_Menu_Item(row, ICON_Version, F(CUSTOM_MENU_CONFIG_TITLE)); + else + Draw_Menu(MenuCustom); + break; + #endif + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + case PREPARE_CHANGEFIL: + if (draw) { + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Change Filament") + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + , nullptr, true + #endif + ); + } + else { + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + Draw_Menu(ChangeFilament); + #else + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) + Popup_Handler(ETemp); + else { + if (thermalManager.temp_hotend[0].is_below_target(-2)) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now(cmd); + } + #endif + } + break; + #endif + } + break; + + case HomeMenu: + + #define HOME_BACK 0 + #define HOME_ALL (HOME_BACK + 1) + #define HOME_X (HOME_ALL + 1) + #define HOME_Y (HOME_X + 1) + #define HOME_Z (HOME_Y + 1) + #define HOME_SET (HOME_Z + 1) + #define HOME_TOTAL HOME_SET + + switch (item) { + case HOME_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Prepare, PREPARE_HOME); + break; + case HOME_ALL: + if (draw) + Draw_Menu_Item(row, ICON_Homing, F("Home All")); + else { + Popup_Handler(Home); + gcode.home_all_axes(true); + Redraw_Menu(); + } + break; + case HOME_X: + if (draw) + Draw_Menu_Item(row, ICON_MoveX, F("Home X")); + else { + Popup_Handler(Home); + gcode.process_subcommands_now(F("G28 X")); + planner.synchronize(); + Redraw_Menu(); + } + break; + case HOME_Y: + if (draw) + Draw_Menu_Item(row, ICON_MoveY, F("Home Y")); + else { + Popup_Handler(Home); + gcode.process_subcommands_now(F("G28 Y")); + planner.synchronize(); + Redraw_Menu(); + } + break; + case HOME_Z: + if (draw) + Draw_Menu_Item(row, ICON_MoveZ, F("Home Z")); + else { + Popup_Handler(Home); + gcode.process_subcommands_now(F("G28 Z")); + planner.synchronize(); + Redraw_Menu(); + } + break; + case HOME_SET: + if (draw) + Draw_Menu_Item(row, ICON_SetHome, F("Set Home Position")); + else { + gcode.process_subcommands_now(F("G92X0Y0Z0")); + AudioFeedback(); + } + break; + } + break; + + case Move: + + #define MOVE_BACK 0 + #define MOVE_X (MOVE_BACK + 1) + #define MOVE_Y (MOVE_X + 1) + #define MOVE_Z (MOVE_Y + 1) + #define MOVE_E (MOVE_Z + ENABLED(HAS_HOTEND)) + #define MOVE_P (MOVE_E + ENABLED(HAS_BED_PROBE)) + #define MOVE_LIVE (MOVE_P + 1) + #define MOVE_TOTAL MOVE_LIVE + + switch (item) { + case MOVE_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else { + #if HAS_BED_PROBE + probe_deployed = false; + probe.set_deployed(probe_deployed); + #endif + Draw_Menu(Prepare, PREPARE_MOVE); + } + break; + case MOVE_X: + if (draw) { + Draw_Menu_Item(row, ICON_MoveX, F("Move X")); + Draw_Float(current_position.x, row, false); + } + else + Modify_Value(current_position.x, X_MIN_POS, X_MAX_POS, 10); + break; + case MOVE_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MoveY, F("Move Y")); + Draw_Float(current_position.y, row); + } + else + Modify_Value(current_position.y, Y_MIN_POS, Y_MAX_POS, 10); + break; + case MOVE_Z: + if (draw) { + Draw_Menu_Item(row, ICON_MoveZ, F("Move Z")); + Draw_Float(current_position.z, row); + } + else + Modify_Value(current_position.z, Z_MIN_POS, Z_MAX_POS, 10); + break; + + #if HAS_HOTEND + case MOVE_E: + if (draw) { + Draw_Menu_Item(row, ICON_Extruder, F("Extruder")); + current_position.e = 0; + sync_plan_position(); + Draw_Float(current_position.e, row); + } + else { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) { + Popup_Handler(ETemp); + } + else { + if (thermalManager.temp_hotend[0].is_below_target(-2)) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + Redraw_Menu(); + } + current_position.e = 0; + sync_plan_position(); + Modify_Value(current_position.e, -500, 500, 10); + } + } + break; + #endif // HAS_HOTEND + + #if HAS_BED_PROBE + case MOVE_P: + if (draw) { + Draw_Menu_Item(row, ICON_StockConfiguration, F("Probe")); + Draw_Checkbox(row, probe_deployed); + } + else { + probe_deployed = !probe_deployed; + probe.set_deployed(probe_deployed); + Draw_Checkbox(row, probe_deployed); + } + break; + #endif + + case MOVE_LIVE: + if (draw) { + Draw_Menu_Item(row, ICON_Axis, F("Live Movement")); + Draw_Checkbox(row, livemove); + } + else { + livemove = !livemove; + Draw_Checkbox(row, livemove); + } + break; + } + break; + case ManualLevel: + + #define MLEVEL_BACK 0 + #define MLEVEL_PROBE (MLEVEL_BACK + ENABLED(HAS_BED_PROBE)) + #define MLEVEL_BL (MLEVEL_PROBE + 1) + #define MLEVEL_TL (MLEVEL_BL + 1) + #define MLEVEL_TR (MLEVEL_TL + 1) + #define MLEVEL_BR (MLEVEL_TR + 1) + #define MLEVEL_C (MLEVEL_BR + 1) + #define MLEVEL_ZPOS (MLEVEL_C + 1) + #define MLEVEL_TOTAL MLEVEL_ZPOS + + static float mlev_z_pos = 0; + static bool use_probe = false; + + switch (item) { + case MLEVEL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else { + TERN_(HAS_LEVELING, set_bed_leveling_enabled(level_state)); + Draw_Menu(Prepare, PREPARE_MANUALLEVEL); + } + break; + #if HAS_BED_PROBE + case MLEVEL_PROBE: + if (draw) { + Draw_Menu_Item(row, ICON_Zoffset, F("Use Probe")); + Draw_Checkbox(row, use_probe); + } + else { + use_probe = !use_probe; + Draw_Checkbox(row, use_probe); + if (use_probe) { + Popup_Handler(Level); + corner_avg = 0; + #define PROBE_X_MIN _MAX(0 + corner_pos, X_MIN_POS + probe.offset.x, X_MIN_POS + PROBING_MARGIN) - probe.offset.x + #define PROBE_X_MAX _MIN((X_BED_SIZE + X_MIN_POS) - corner_pos, X_MAX_POS + probe.offset.x, X_MAX_POS - PROBING_MARGIN) - probe.offset.x + #define PROBE_Y_MIN _MAX(0 + corner_pos, Y_MIN_POS + probe.offset.y, Y_MIN_POS + PROBING_MARGIN) - probe.offset.y + #define PROBE_Y_MAX _MIN((Y_BED_SIZE + Y_MIN_POS) - corner_pos, Y_MAX_POS + probe.offset.y, Y_MAX_POS - PROBING_MARGIN) - probe.offset.y + corner_avg += probe.probe_at_point(PROBE_X_MIN, PROBE_Y_MIN, PROBE_PT_RAISE, 0, false); + corner_avg += probe.probe_at_point(PROBE_X_MIN, PROBE_Y_MAX, PROBE_PT_RAISE, 0, false); + corner_avg += probe.probe_at_point(PROBE_X_MAX, PROBE_Y_MAX, PROBE_PT_RAISE, 0, false); + corner_avg += probe.probe_at_point(PROBE_X_MAX, PROBE_Y_MIN, PROBE_PT_STOW, 0, false); + corner_avg /= 4; + Redraw_Menu(); + } + } + break; + #endif + case MLEVEL_BL: + if (draw) + Draw_Menu_Item(row, ICON_AxisBL, F("Bottom Left")); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MIN, 1, 3, str_1), dtostrf(PROBE_Y_MIN, 1, 3, str_2)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf(corner_pos, 1, 3, str_1), dtostrf(corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_TL: + if (draw) + Draw_Menu_Item(row, ICON_AxisTL, F("Top Left")); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MIN, 1, 3, str_1), dtostrf(PROBE_Y_MAX, 1, 3, str_2)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf(corner_pos, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) - corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_TR: + if (draw) + Draw_Menu_Item(row, ICON_AxisTR, F("Top Right")); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MAX, 1, 3, str_1), dtostrf(PROBE_Y_MAX, 1, 3, str_2)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) - corner_pos, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) - corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_BR: + if (draw) + Draw_Menu_Item(row, ICON_AxisBR, F("Bottom Right")); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(PROBE_X_MAX, 1, 3, str_1), dtostrf(PROBE_Y_MIN, 1, 3, str_2)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) - corner_pos, 1, 3, str_1), dtostrf(corner_pos, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_C: + if (draw) + Draw_Menu_Item(row, ICON_AxisC, F("Center")); + else { + Popup_Handler(MoveWait); + if (use_probe) { + #if HAS_BED_PROBE + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s"), dtostrf(X_MAX_POS / 2.0f - probe.offset.x, 1, 3, str_1), dtostrf(Y_MAX_POS / 2.0f - probe.offset.y, 1, 3, str_2)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Popup_Handler(ManualProbing); + #endif + } + else { + sprintf_P(cmd, PSTR("G0 F4000\nG0 Z10\nG0 X%s Y%s\nG0 F300 Z%s"), dtostrf((X_BED_SIZE + X_MIN_POS) / 2.0f, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 1, 3, str_2), dtostrf(mlev_z_pos, 1, 3, str_3)); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case MLEVEL_ZPOS: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, F("Z Position")); + Draw_Float(mlev_z_pos, row, false, 100); + } + else + Modify_Value(mlev_z_pos, 0, MAX_Z_OFFSET, 100); + break; + } + break; + #if HAS_ZOFFSET_ITEM + case ZOffset: + + #define ZOFFSET_BACK 0 + #define ZOFFSET_HOME (ZOFFSET_BACK + 1) + #define ZOFFSET_MODE (ZOFFSET_HOME + 1) + #define ZOFFSET_OFFSET (ZOFFSET_MODE + 1) + #define ZOFFSET_UP (ZOFFSET_OFFSET + 1) + #define ZOFFSET_DOWN (ZOFFSET_UP + 1) + #define ZOFFSET_SAVE (ZOFFSET_DOWN + ENABLED(EEPROM_SETTINGS)) + #define ZOFFSET_TOTAL ZOFFSET_SAVE + + switch (item) { + case ZOFFSET_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else { + liveadjust = false; + TERN_(HAS_LEVELING, set_bed_leveling_enabled(level_state)); + Draw_Menu(Prepare, PREPARE_ZOFFSET); + } + break; + case ZOFFSET_HOME: + if (draw) + Draw_Menu_Item(row, ICON_Homing, F("Home Z Axis")); + else { + Popup_Handler(Home); + gcode.process_subcommands_now(F("G28 Z")); + Popup_Handler(MoveWait); + #if ENABLED(Z_SAFE_HOMING) + planner.synchronize(); + sprintf_P(cmd, PSTR("G0 F4000 X%s Y%s"), dtostrf(Z_SAFE_HOMING_X_POINT, 1, 3, str_1), dtostrf(Z_SAFE_HOMING_Y_POINT, 1, 3, str_2)); + gcode.process_subcommands_now(cmd); + #else + gcode.process_subcommands_now(F("G0 F4000 X117.5 Y117.5")); + #endif + gcode.process_subcommands_now(F("G0 F300 Z0")); + planner.synchronize(); + Redraw_Menu(); + } + break; + case ZOFFSET_MODE: + if (draw) { + Draw_Menu_Item(row, ICON_Zoffset, F("Live Adjustment")); + Draw_Checkbox(row, liveadjust); + } + else { + if (!liveadjust) { + if (axes_should_home()) { + Popup_Handler(Home); + gcode.home_all_axes(true); + } + Popup_Handler(MoveWait); + #if ENABLED(Z_SAFE_HOMING) + planner.synchronize(); + sprintf_P(cmd, PSTR("G0 F4000 X%s Y%s"), dtostrf(Z_SAFE_HOMING_X_POINT, 1, 3, str_1), dtostrf(Z_SAFE_HOMING_Y_POINT, 1, 3, str_2)); + gcode.process_subcommands_now(cmd); + #else + gcode.process_subcommands_now(F("G0 F4000 X117.5 Y117.5")); + #endif + gcode.process_subcommands_now(F("G0 F300 Z0")); + planner.synchronize(); + Redraw_Menu(); + } + liveadjust = !liveadjust; + Draw_Checkbox(row, liveadjust); + } + break; + case ZOFFSET_OFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, F("Z Offset")); + Draw_Float(zoffsetvalue, row, false, 100); + } + else + Modify_Value(zoffsetvalue, MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + break; + case ZOFFSET_UP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); + else { + if (zoffsetvalue < MAX_Z_OFFSET) { + if (liveadjust) { + gcode.process_subcommands_now(F("M290 Z0.01")); + planner.synchronize(); + } + zoffsetvalue += 0.01; + Draw_Float(zoffsetvalue, row - 1, false, 100); + } + } + break; + case ZOFFSET_DOWN: + if (draw) + Draw_Menu_Item(row, ICON_AxisD, F("Microstep Down")); + else { + if (zoffsetvalue > MIN_Z_OFFSET) { + if (liveadjust) { + gcode.process_subcommands_now(F("M290 Z-0.01")); + planner.synchronize(); + } + zoffsetvalue -= 0.01; + Draw_Float(zoffsetvalue, row - 2, false, 100); + } + } + break; + #if ENABLED(EEPROM_SETTINGS) + case ZOFFSET_SAVE: + if (draw) + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Save")); + else + AudioFeedback(settings.save()); + break; + #endif + } + break; + #endif + + #if HAS_PREHEAT + case Preheat: { + #define PREHEAT_MODE (PREHEAT_BACK + 1) + #define PREHEAT_1 (PREHEAT_MODE + 1) + #define PREHEAT_2 (PREHEAT_1 + (PREHEAT_COUNT >= 2)) + #define PREHEAT_3 (PREHEAT_2 + (PREHEAT_COUNT >= 3)) + #define PREHEAT_4 (PREHEAT_3 + (PREHEAT_COUNT >= 4)) + #define PREHEAT_5 (PREHEAT_4 + (PREHEAT_COUNT >= 5)) + #define PREHEAT_TOTAL PREHEAT_5 + + auto do_preheat = [](const uint8_t m) { + thermalManager.cooldown(); + if (preheatmode == 0 || preheatmode == 1) { ui.preheat_hotend_and_fan(m); } + if (preheatmode == 0 || preheatmode == 2) ui.preheat_bed(m); + }; + + switch (item) { + case PREHEAT_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Prepare, PREPARE_PREHEAT); + break; + + case PREHEAT_MODE: + if (draw) { + Draw_Menu_Item(row, ICON_Homing, F("Preheat Mode")); + Draw_Option(preheatmode, preheat_modes, row); + } + else + Modify_Option(preheatmode, preheat_modes, 2); + break; + + #define _PREHEAT_CASE(N) \ + case PREHEAT_##N: { \ + if (draw) Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_## N ##_LABEL)); \ + else do_preheat(N - 1); \ + } break; + + REPEAT_1(PREHEAT_COUNT, _PREHEAT_CASE) + } + } break; + #endif // HAS_PREHEAT + + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case ChangeFilament: + + #define CHANGEFIL_BACK 0 + #define CHANGEFIL_LOAD (CHANGEFIL_BACK + 1) + #define CHANGEFIL_UNLOAD (CHANGEFIL_LOAD + 1) + #define CHANGEFIL_CHANGE (CHANGEFIL_UNLOAD + 1) + #define CHANGEFIL_TOTAL CHANGEFIL_CHANGE + + switch (item) { + case CHANGEFIL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Prepare, PREPARE_CHANGEFIL); + break; + case CHANGEFIL_LOAD: + if (draw) + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Load Filament")); + else { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) + Popup_Handler(ETemp); + else { + if (thermalManager.temp_hotend[0].is_below_target(-2)) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilLoad); + gcode.process_subcommands_now(F("M701")); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case CHANGEFIL_UNLOAD: + if (draw) + Draw_Menu_Item(row, ICON_ReadEEPROM, F("Unload Filament")); + else { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) { + Popup_Handler(ETemp); + } + else { + if (thermalManager.temp_hotend[0].is_below_target(-2)) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilLoad, true); + gcode.process_subcommands_now(F("M702")); + planner.synchronize(); + Redraw_Menu(); + } + } + break; + case CHANGEFIL_CHANGE: + if (draw) + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Change Filament")); + else { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) + Popup_Handler(ETemp); + else { + if (thermalManager.temp_hotend[0].is_below_target(-2)) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now(cmd); + } + } + break; + } + break; + #endif // FILAMENT_LOAD_UNLOAD_GCODES + + #if HAS_CUSTOM_MENU + + case MenuCustom: + + #define CUSTOM_MENU_BACK 0 + #define CUSTOM_MENU_1 1 + #define CUSTOM_MENU_2 2 + #define CUSTOM_MENU_3 3 + #define CUSTOM_MENU_4 4 + #define CUSTOM_MENU_5 5 + #define CUSTOM_MENU_TOTAL CUSTOM_MENU_COUNT + + switch (item) { + case CUSTOM_MENU_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Prepare, PREPARE_CUSTOM_MENU); + break; + + #if CUSTOM_MENU_COUNT >= 1 + case CUSTOM_MENU_1: + if (draw) + Draw_Menu_Item(row, ICON_Info, F(CONFIG_MENU_ITEM_1_DESC)); + else { + Popup_Handler(Custom); + //queue.inject(F(CONFIG_MENU_ITEM_1_GCODE)); // Old code + gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_1_GCODE)); + planner.synchronize(); + Redraw_Menu(); + #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) + AudioFeedback(); + #endif + #ifdef CUSTOM_MENU_CONFIG_SCRIPT_RETURN + queue.inject(F(CUSTOM_MENU_CONFIG_SCRIPT_DONE)); + #endif + } + break; + #endif + + #if CUSTOM_MENU_COUNT >= 2 + case CUSTOM_MENU_2: + if (draw) + Draw_Menu_Item(row, ICON_Info, F(CONFIG_MENU_ITEM_2_DESC)); + else { + Popup_Handler(Custom); + gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_2_GCODE)); + planner.synchronize(); + Redraw_Menu(); + #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) + AudioFeedback(); + #endif + #ifdef CUSTOM_MENU_CONFIG_SCRIPT_RETURN + queue.inject(F(CUSTOM_MENU_CONFIG_SCRIPT_DONE)); + #endif + } + break; + #endif + + #if CUSTOM_MENU_COUNT >= 3 + case CUSTOM_MENU_3: + if (draw) + Draw_Menu_Item(row, ICON_Info, F(CONFIG_MENU_ITEM_3_DESC)); + else { + Popup_Handler(Custom); + gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_3_GCODE)); + planner.synchronize(); + Redraw_Menu(); + #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) + AudioFeedback(); + #endif + #ifdef CUSTOM_MENU_CONFIG_SCRIPT_RETURN + queue.inject(F(CUSTOM_MENU_CONFIG_SCRIPT_DONE)); + #endif + } + break; + #endif + + #if CUSTOM_MENU_COUNT >= 4 + case CUSTOM_MENU_4: + if (draw) + Draw_Menu_Item(row, ICON_Info, F(CONFIG_MENU_ITEM_4_DESC)); + else { + Popup_Handler(Custom); + gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_4_GCODE)); + planner.synchronize(); + Redraw_Menu(); + #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) + AudioFeedback(); + #endif + #ifdef CUSTOM_MENU_CONFIG_SCRIPT_RETURN + queue.inject(F(CUSTOM_MENU_CONFIG_SCRIPT_DONE)); + #endif + } + break; + #endif + + #if CUSTOM_MENU_COUNT >= 5 + case CUSTOM_MENU_5: + if (draw) + Draw_Menu_Item(row, ICON_Info, F(CONFIG_MENU_ITEM_5_DESC)); + else { + Popup_Handler(Custom); + gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_5_GCODE)); + planner.synchronize(); + Redraw_Menu(); + #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) + AudioFeedback(); + #endif + #ifdef CUSTOM_MENU_CONFIG_SCRIPT_RETURN + queue.inject(F(CUSTOM_MENU_CONFIG_SCRIPT_DONE)); + #endif + } + break; + #endif // Custom Menu + } + break; + + #endif // HAS_CUSTOM_MENU + + case Control: + + #define CONTROL_BACK 0 + #define CONTROL_TEMP (CONTROL_BACK + 1) + #define CONTROL_MOTION (CONTROL_TEMP + 1) + #define CONTROL_VISUAL (CONTROL_MOTION + 1) + #define CONTROL_ADVANCED (CONTROL_VISUAL + 1) + #define CONTROL_SAVE (CONTROL_ADVANCED + ENABLED(EEPROM_SETTINGS)) + #define CONTROL_RESTORE (CONTROL_SAVE + ENABLED(EEPROM_SETTINGS)) + #define CONTROL_RESET (CONTROL_RESTORE + ENABLED(EEPROM_SETTINGS)) + #define CONTROL_INFO (CONTROL_RESET + 1) + #define CONTROL_TOTAL CONTROL_INFO + + switch (item) { + case CONTROL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Main_Menu(2); + break; + case CONTROL_TEMP: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, F("Temperature"), nullptr, true); + else + Draw_Menu(TempMenu); + break; + case CONTROL_MOTION: + if (draw) + Draw_Menu_Item(row, ICON_Motion, F("Motion"), nullptr, true); + else + Draw_Menu(Motion); + break; + case CONTROL_VISUAL: + if (draw) + Draw_Menu_Item(row, ICON_PrintSize, F("Visual"), nullptr, true); + else + Draw_Menu(Visual); + break; + case CONTROL_ADVANCED: + if (draw) + Draw_Menu_Item(row, ICON_Version, F("Advanced"), nullptr, true); + else + Draw_Menu(Advanced); + break; + #if ENABLED(EEPROM_SETTINGS) + case CONTROL_SAVE: + if (draw) + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Store Settings")); + else + AudioFeedback(settings.save()); + break; + case CONTROL_RESTORE: + if (draw) + Draw_Menu_Item(row, ICON_ReadEEPROM, F("Restore Settings")); + else + AudioFeedback(settings.load()); + break; + case CONTROL_RESET: + if (draw) + Draw_Menu_Item(row, ICON_Temperature, F("Reset to Defaults")); + else { + settings.reset(); + AudioFeedback(); + } + break; + #endif + case CONTROL_INFO: + if (draw) + Draw_Menu_Item(row, ICON_Info, F("Info")); + else + Draw_Menu(Info); + break; + } + break; + + case TempMenu: + + #define TEMP_BACK 0 + #define TEMP_HOTEND (TEMP_BACK + ENABLED(HAS_HOTEND)) + #define TEMP_BED (TEMP_HOTEND + ENABLED(HAS_HEATED_BED)) + #define TEMP_FAN (TEMP_BED + ENABLED(HAS_FAN)) + #define TEMP_PID (TEMP_FAN + ANY(HAS_HOTEND, HAS_HEATED_BED)) + #define TEMP_PREHEAT1 (TEMP_PID + (PREHEAT_COUNT >= 1)) + #define TEMP_PREHEAT2 (TEMP_PREHEAT1 + (PREHEAT_COUNT >= 2)) + #define TEMP_PREHEAT3 (TEMP_PREHEAT2 + (PREHEAT_COUNT >= 3)) + #define TEMP_PREHEAT4 (TEMP_PREHEAT3 + (PREHEAT_COUNT >= 4)) + #define TEMP_PREHEAT5 (TEMP_PREHEAT4 + (PREHEAT_COUNT >= 5)) + #define TEMP_TOTAL TEMP_PREHEAT5 + + switch (item) { + case TEMP_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Control, CONTROL_TEMP); + break; + #if HAS_HOTEND + case TEMP_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); + Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_hotend[0].target, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + #if HAS_HEATED_BED + case TEMP_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); + Draw_Float(thermalManager.temp_bed.target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_bed.target, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + #if HAS_FAN + case TEMP_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); + Draw_Float(thermalManager.fan_speed[0], row, false, 1); + } + else + Modify_Value(thermalManager.fan_speed[0], MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + #if HAS_HOTEND || HAS_HEATED_BED + case TEMP_PID: + if (draw) + Draw_Menu_Item(row, ICON_Step, F("PID"), nullptr, true); + else + Draw_Menu(PID); + break; + #endif + + #define _TEMP_PREHEAT_CASE(N) \ + case TEMP_PREHEAT##N: { \ + if (draw) Draw_Menu_Item(row, ICON_Step, F(PREHEAT_## N ##_LABEL), nullptr, true); \ + else Draw_Menu(Preheat##N); \ + } break; + + REPEAT_1(PREHEAT_COUNT, _TEMP_PREHEAT_CASE) + } + break; + + #if HAS_HOTEND || HAS_HEATED_BED + case PID: + + #define PID_BACK 0 + #define PID_HOTEND (PID_BACK + ENABLED(HAS_HOTEND)) + #define PID_BED (PID_HOTEND + ENABLED(HAS_HEATED_BED)) + #define PID_CYCLES (PID_BED + 1) + #define PID_TOTAL PID_CYCLES + + static uint8_t PID_cycles = 5; + + switch (item) { + case PID_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(TempMenu, TEMP_PID); + break; + #if HAS_HOTEND + case PID_HOTEND: + if (draw) + Draw_Menu_Item(row, ICON_HotendTemp, F("Hotend"), nullptr, true); + else + Draw_Menu(HotendPID); + break; + #endif + #if HAS_HEATED_BED + case PID_BED: + if (draw) + Draw_Menu_Item(row, ICON_BedTemp, F("Bed"), nullptr, true); + else + Draw_Menu(BedPID); + break; + #endif + case PID_CYCLES: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, F("Cycles")); + Draw_Float(PID_cycles, row, false, 1); + } + else + Modify_Value(PID_cycles, 3, 50, 1); + break; + } + break; + #endif // HAS_HOTEND || HAS_HEATED_BED + + #if HAS_HOTEND + case HotendPID: + + #define HOTENDPID_BACK 0 + #define HOTENDPID_TUNE (HOTENDPID_BACK + 1) + #define HOTENDPID_TEMP (HOTENDPID_TUNE + 1) + #define HOTENDPID_KP (HOTENDPID_TEMP + 1) + #define HOTENDPID_KI (HOTENDPID_KP + 1) + #define HOTENDPID_KD (HOTENDPID_KI + 1) + #define HOTENDPID_TOTAL HOTENDPID_KD + + static uint16_t PID_e_temp = 180; + + switch (item) { + case HOTENDPID_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(PID, PID_HOTEND); + break; + case HOTENDPID_TUNE: + if (draw) + Draw_Menu_Item(row, ICON_HotendTemp, F("Autotune")); + else { + Popup_Handler(PIDWait); + sprintf_P(cmd, PSTR("M303 E0 C%i S%i U1"), PID_cycles, PID_e_temp); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Redraw_Menu(); + } + break; + case HOTENDPID_TEMP: + if (draw) { + Draw_Menu_Item(row, ICON_Temperature, F("Temperature")); + Draw_Float(PID_e_temp, row, false, 1); + } + else + Modify_Value(PID_e_temp, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + case HOTENDPID_KP: + if (draw) { + Draw_Menu_Item(row, ICON_Version, F("Kp Value")); + Draw_Float(thermalManager.temp_hotend[0].pid.Kp, row, false, 100); + } + else + Modify_Value(thermalManager.temp_hotend[0].pid.Kp, 0, 5000, 100, thermalManager.updatePID); + break; + case HOTENDPID_KI: + if (draw) { + Draw_Menu_Item(row, ICON_Version, F("Ki Value")); + Draw_Float(unscalePID_i(thermalManager.temp_hotend[0].pid.Ki), row, false, 100); + } + else + Modify_Value(thermalManager.temp_hotend[0].pid.Ki, 0, 5000, 100, thermalManager.updatePID); + break; + case HOTENDPID_KD: + if (draw) { + Draw_Menu_Item(row, ICON_Version, F("Kd Value")); + Draw_Float(unscalePID_d(thermalManager.temp_hotend[0].pid.Kd), row, false, 100); + } + else + Modify_Value(thermalManager.temp_hotend[0].pid.Kd, 0, 5000, 100, thermalManager.updatePID); + break; + } + break; + #endif // HAS_HOTEND + + #if HAS_HEATED_BED + case BedPID: + + #define BEDPID_BACK 0 + #define BEDPID_TUNE (BEDPID_BACK + 1) + #define BEDPID_TEMP (BEDPID_TUNE + 1) + #define BEDPID_KP (BEDPID_TEMP + 1) + #define BEDPID_KI (BEDPID_KP + 1) + #define BEDPID_KD (BEDPID_KI + 1) + #define BEDPID_TOTAL BEDPID_KD + + static uint16_t PID_bed_temp = 60; + + switch (item) { + case BEDPID_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(PID, PID_BED); + break; + case BEDPID_TUNE: + if (draw) + Draw_Menu_Item(row, ICON_HotendTemp, F("Autotune")); + else { + Popup_Handler(PIDWait); + sprintf_P(cmd, PSTR("M303 E-1 C%i S%i U1"), PID_cycles, PID_bed_temp); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + Redraw_Menu(); + } + break; + case BEDPID_TEMP: + if (draw) { + Draw_Menu_Item(row, ICON_Temperature, F("Temperature")); + Draw_Float(PID_bed_temp, row, false, 1); + } + else + Modify_Value(PID_bed_temp, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + case BEDPID_KP: + if (draw) { + Draw_Menu_Item(row, ICON_Version, F("Kp Value")); + Draw_Float(thermalManager.temp_bed.pid.Kp, row, false, 100); + } + else { + Modify_Value(thermalManager.temp_bed.pid.Kp, 0, 5000, 100, thermalManager.updatePID); + } + break; + case BEDPID_KI: + if (draw) { + Draw_Menu_Item(row, ICON_Version, F("Ki Value")); + Draw_Float(unscalePID_i(thermalManager.temp_bed.pid.Ki), row, false, 100); + } + else + Modify_Value(thermalManager.temp_bed.pid.Ki, 0, 5000, 100, thermalManager.updatePID); + break; + case BEDPID_KD: + if (draw) { + Draw_Menu_Item(row, ICON_Version, F("Kd Value")); + Draw_Float(unscalePID_d(thermalManager.temp_bed.pid.Kd), row, false, 100); + } + else + Modify_Value(thermalManager.temp_bed.pid.Kd, 0, 5000, 100, thermalManager.updatePID); + break; + } + break; + #endif // HAS_HEATED_BED + + #if HAS_PREHEAT + #define _PREHEAT_SUBMENU_CASE(N) case Preheat##N: preheat_submenu((N) - 1, item, TEMP_PREHEAT##N); break; + REPEAT_1(PREHEAT_COUNT, _PREHEAT_SUBMENU_CASE) + #endif + + case Motion: + + #define MOTION_BACK 0 + #define MOTION_HOMEOFFSETS (MOTION_BACK + 1) + #define MOTION_SPEED (MOTION_HOMEOFFSETS + 1) + #define MOTION_ACCEL (MOTION_SPEED + 1) + #define MOTION_JERK (MOTION_ACCEL + ENABLED(HAS_CLASSIC_JERK)) + #define MOTION_STEPS (MOTION_JERK + 1) + #define MOTION_FLOW (MOTION_STEPS + ENABLED(HAS_HOTEND)) + #define MOTION_TOTAL MOTION_FLOW + + switch (item) { + case MOTION_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Control, CONTROL_MOTION); + break; + case MOTION_HOMEOFFSETS: + if (draw) + Draw_Menu_Item(row, ICON_SetHome, F("Home Offsets"), nullptr, true); + else + Draw_Menu(HomeOffsets); + break; + case MOTION_SPEED: + if (draw) + Draw_Menu_Item(row, ICON_MaxSpeed, F("Max Speed"), nullptr, true); + else + Draw_Menu(MaxSpeed); + break; + case MOTION_ACCEL: + if (draw) + Draw_Menu_Item(row, ICON_MaxAccelerated, F("Max Acceleration"), nullptr, true); + else + Draw_Menu(MaxAcceleration); + break; + #if HAS_CLASSIC_JERK + case MOTION_JERK: + if (draw) + Draw_Menu_Item(row, ICON_MaxJerk, F("Max Jerk"), nullptr, true); + else + Draw_Menu(MaxJerk); + break; + #endif + case MOTION_STEPS: + if (draw) + Draw_Menu_Item(row, ICON_Step, F("Steps/mm"), nullptr, true); + else + Draw_Menu(Steps); + break; + #if HAS_HOTEND + case MOTION_FLOW: + if (draw) { + Draw_Menu_Item(row, ICON_Speed, F("Flow Rate")); + Draw_Float(planner.flow_percentage[0], row, false, 1); + } + else + Modify_Value(planner.flow_percentage[0], MIN_FLOW_RATE, MAX_FLOW_RATE, 1); + break; + #endif + } + break; + + case HomeOffsets: + + #define HOMEOFFSETS_BACK 0 + #define HOMEOFFSETS_XOFFSET (HOMEOFFSETS_BACK + 1) + #define HOMEOFFSETS_YOFFSET (HOMEOFFSETS_XOFFSET + 1) + #define HOMEOFFSETS_TOTAL HOMEOFFSETS_YOFFSET + + switch (item) { + case HOMEOFFSETS_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Motion, MOTION_HOMEOFFSETS); + break; + case HOMEOFFSETS_XOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_StepX, F("X Offset")); + Draw_Float(home_offset.x, row, false, 100); + } + else + Modify_Value(home_offset.x, -MAX_XY_OFFSET, MAX_XY_OFFSET, 100); + break; + case HOMEOFFSETS_YOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_StepY, F("Y Offset")); + Draw_Float(home_offset.y, row, false, 100); + } + else + Modify_Value(home_offset.y, -MAX_XY_OFFSET, MAX_XY_OFFSET, 100); + break; + } + break; + case MaxSpeed: + + #define SPEED_BACK 0 + #define SPEED_X (SPEED_BACK + 1) + #define SPEED_Y (SPEED_X + 1) + #define SPEED_Z (SPEED_Y + 1) + #define SPEED_E (SPEED_Z + ENABLED(HAS_HOTEND)) + #define SPEED_TOTAL SPEED_E + + switch (item) { + case SPEED_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Motion, MOTION_SPEED); + break; + case SPEED_X: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedX, F("X Axis")); + Draw_Float(planner.settings.max_feedrate_mm_s[X_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_feedrate_mm_s[X_AXIS], 0, default_max_feedrate[X_AXIS] * 2, 1); + break; + + #if HAS_Y_AXIS + case SPEED_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedY, F("Y Axis")); + Draw_Float(planner.settings.max_feedrate_mm_s[Y_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_feedrate_mm_s[Y_AXIS], 0, default_max_feedrate[Y_AXIS] * 2, 1); + break; + #endif + + #if HAS_Z_AXIS + case SPEED_Z: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedZ, F("Z Axis")); + Draw_Float(planner.settings.max_feedrate_mm_s[Z_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_feedrate_mm_s[Z_AXIS], 0, default_max_feedrate[Z_AXIS] * 2, 1); + break; + #endif + + #if HAS_HOTEND + case SPEED_E: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedE, F("Extruder")); + Draw_Float(planner.settings.max_feedrate_mm_s[E_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_feedrate_mm_s[E_AXIS], 0, default_max_feedrate[E_AXIS] * 2, 1); + break; + #endif + } + break; + + case MaxAcceleration: + + #define ACCEL_BACK 0 + #define ACCEL_X (ACCEL_BACK + 1) + #define ACCEL_Y (ACCEL_X + 1) + #define ACCEL_Z (ACCEL_Y + 1) + #define ACCEL_E (ACCEL_Z + ENABLED(HAS_HOTEND)) + #define ACCEL_TOTAL ACCEL_E + + switch (item) { + case ACCEL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Motion, MOTION_ACCEL); + break; + case ACCEL_X: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccX, F("X Axis")); + Draw_Float(planner.settings.max_acceleration_mm_per_s2[X_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_acceleration_mm_per_s2[X_AXIS], 0, default_max_acceleration[X_AXIS] * 2, 1); + break; + case ACCEL_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccY, F("Y Axis")); + Draw_Float(planner.settings.max_acceleration_mm_per_s2[Y_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_acceleration_mm_per_s2[Y_AXIS], 0, default_max_acceleration[Y_AXIS] * 2, 1); + break; + case ACCEL_Z: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccZ, F("Z Axis")); + Draw_Float(planner.settings.max_acceleration_mm_per_s2[Z_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_acceleration_mm_per_s2[Z_AXIS], 0, default_max_acceleration[Z_AXIS] * 2, 1); + break; + #if HAS_HOTEND + case ACCEL_E: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccE, F("Extruder")); + Draw_Float(planner.settings.max_acceleration_mm_per_s2[E_AXIS], row, false, 1); + } + else + Modify_Value(planner.settings.max_acceleration_mm_per_s2[E_AXIS], 0, default_max_acceleration[E_AXIS] * 2, 1); + break; + #endif + } + break; + #if HAS_CLASSIC_JERK + case MaxJerk: + + #define JERK_BACK 0 + #define JERK_X (JERK_BACK + 1) + #define JERK_Y (JERK_X + 1) + #define JERK_Z (JERK_Y + 1) + #define JERK_E (JERK_Z + ENABLED(HAS_HOTEND)) + #define JERK_TOTAL JERK_E + + switch (item) { + case JERK_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Motion, MOTION_JERK); + break; + case JERK_X: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedJerkX, F("X Axis")); + Draw_Float(planner.max_jerk[X_AXIS], row, false, 10); + } + else + Modify_Value(planner.max_jerk[X_AXIS], 0, default_max_jerk[X_AXIS] * 2, 10); + break; + case JERK_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedJerkY, F("Y Axis")); + Draw_Float(planner.max_jerk[Y_AXIS], row, false, 10); + } + else + Modify_Value(planner.max_jerk[Y_AXIS], 0, default_max_jerk[Y_AXIS] * 2, 10); + break; + case JERK_Z: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedJerkZ, F("Z Axis")); + Draw_Float(planner.max_jerk[Z_AXIS], row, false, 10); + } + else + Modify_Value(planner.max_jerk[Z_AXIS], 0, default_max_jerk[Z_AXIS] * 2, 10); + break; + #if HAS_HOTEND + case JERK_E: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeedJerkE, F("Extruder")); + Draw_Float(planner.max_jerk[E_AXIS], row, false, 10); + } + else + Modify_Value(planner.max_jerk[E_AXIS], 0, default_max_jerk[E_AXIS] * 2, 10); + break; + #endif + } + break; + #endif + case Steps: + + #define STEPS_BACK 0 + #define STEPS_X (STEPS_BACK + 1) + #define STEPS_Y (STEPS_X + 1) + #define STEPS_Z (STEPS_Y + 1) + #define STEPS_E (STEPS_Z + ENABLED(HAS_HOTEND)) + #define STEPS_TOTAL STEPS_E + + switch (item) { + case STEPS_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Motion, MOTION_STEPS); + break; + case STEPS_X: + if (draw) { + Draw_Menu_Item(row, ICON_StepX, F("X Axis")); + Draw_Float(planner.settings.axis_steps_per_mm[X_AXIS], row, false, 10); + } + else + Modify_Value(planner.settings.axis_steps_per_mm[X_AXIS], 0, default_steps[X_AXIS] * 2, 10); + break; + case STEPS_Y: + if (draw) { + Draw_Menu_Item(row, ICON_StepY, F("Y Axis")); + Draw_Float(planner.settings.axis_steps_per_mm[Y_AXIS], row, false, 10); + } + else + Modify_Value(planner.settings.axis_steps_per_mm[Y_AXIS], 0, default_steps[Y_AXIS] * 2, 10); + break; + case STEPS_Z: + if (draw) { + Draw_Menu_Item(row, ICON_StepZ, F("Z Axis")); + Draw_Float(planner.settings.axis_steps_per_mm[Z_AXIS], row, false, 10); + } + else + Modify_Value(planner.settings.axis_steps_per_mm[Z_AXIS], 0, default_steps[Z_AXIS] * 2, 10); + break; + #if HAS_HOTEND + case STEPS_E: + if (draw) { + Draw_Menu_Item(row, ICON_StepE, F("Extruder")); + Draw_Float(planner.settings.axis_steps_per_mm[E_AXIS], row, false, 10); + } + else + Modify_Value(planner.settings.axis_steps_per_mm[E_AXIS], 0, 1000, 10); + break; + #endif + } + break; + + case Visual: + + #define VISUAL_BACK 0 + #define VISUAL_BACKLIGHT (VISUAL_BACK + 1) + #define VISUAL_BRIGHTNESS (VISUAL_BACKLIGHT + 1) + #define VISUAL_TIME_FORMAT (VISUAL_BRIGHTNESS + 1) + #define VISUAL_COLOR_THEMES (VISUAL_TIME_FORMAT + 1) + #define VISUAL_TOTAL VISUAL_COLOR_THEMES + + switch (item) { + case VISUAL_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Control, CONTROL_VISUAL); + break; + case VISUAL_BACKLIGHT: + if (draw) + Draw_Menu_Item(row, ICON_Brightness, F("Display Off")); + else + ui.set_brightness(0); + break; + case VISUAL_BRIGHTNESS: + if (draw) { + Draw_Menu_Item(row, ICON_Brightness, F("LCD Brightness")); + Draw_Float(ui.brightness, row, false, 1); + } + else + Modify_Value(ui.brightness, LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, 1, ui.refresh_brightness); + break; + case VISUAL_TIME_FORMAT: + if (draw) { + Draw_Menu_Item(row, ICON_PrintTime, F("Progress as __h__m")); + Draw_Checkbox(row, eeprom_settings.time_format_textual); + } + else { + eeprom_settings.time_format_textual = !eeprom_settings.time_format_textual; + Draw_Checkbox(row, eeprom_settings.time_format_textual); + } + break; + case VISUAL_COLOR_THEMES: + if (draw) + Draw_Menu_Item(row, ICON_MaxSpeed, F("UI Color Settings"), nullptr, true); + else + Draw_Menu(ColorSettings); + break; + } + break; + + case ColorSettings: + + #define COLORSETTINGS_BACK 0 + #define COLORSETTINGS_CURSOR (COLORSETTINGS_BACK + 1) + #define COLORSETTINGS_SPLIT_LINE (COLORSETTINGS_CURSOR + 1) + #define COLORSETTINGS_MENU_TOP_TXT (COLORSETTINGS_SPLIT_LINE + 1) + #define COLORSETTINGS_MENU_TOP_BG (COLORSETTINGS_MENU_TOP_TXT + 1) + #define COLORSETTINGS_HIGHLIGHT_BORDER (COLORSETTINGS_MENU_TOP_BG + 1) + #define COLORSETTINGS_PROGRESS_PERCENT (COLORSETTINGS_HIGHLIGHT_BORDER + 1) + #define COLORSETTINGS_PROGRESS_TIME (COLORSETTINGS_PROGRESS_PERCENT + 1) + #define COLORSETTINGS_PROGRESS_STATUS_BAR (COLORSETTINGS_PROGRESS_TIME + 1) + #define COLORSETTINGS_PROGRESS_STATUS_AREA (COLORSETTINGS_PROGRESS_STATUS_BAR + 1) + #define COLORSETTINGS_PROGRESS_COORDINATES (COLORSETTINGS_PROGRESS_STATUS_AREA + 1) + #define COLORSETTINGS_PROGRESS_COORDINATES_LINE (COLORSETTINGS_PROGRESS_COORDINATES + 1) + #define COLORSETTINGS_TOTAL COLORSETTINGS_PROGRESS_COORDINATES_LINE + + switch (item) { + case COLORSETTINGS_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Visual, VISUAL_COLOR_THEMES); + break; + case COLORSETTINGS_CURSOR: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Cursor")); + Draw_Option(eeprom_settings.cursor_color, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.cursor_color, color_names, Custom_Colors); + break; + case COLORSETTINGS_SPLIT_LINE: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Menu Split Line")); + Draw_Option(eeprom_settings.menu_split_line, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.menu_split_line, color_names, Custom_Colors); + break; + case COLORSETTINGS_MENU_TOP_TXT: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Menu Header Text")); + Draw_Option(eeprom_settings.menu_top_txt, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.menu_top_txt, color_names, Custom_Colors); + break; + case COLORSETTINGS_MENU_TOP_BG: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Menu Header Bg")); + Draw_Option(eeprom_settings.menu_top_bg, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.menu_top_bg, color_names, Custom_Colors); + break; + case COLORSETTINGS_HIGHLIGHT_BORDER: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Highlight Box")); + Draw_Option(eeprom_settings.highlight_box, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.highlight_box, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_PERCENT: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Progress Percent")); + Draw_Option(eeprom_settings.progress_percent, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.progress_percent, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_TIME: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Progress Time")); + Draw_Option(eeprom_settings.progress_time, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.progress_time, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_STATUS_BAR: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Status Bar Text")); + Draw_Option(eeprom_settings.status_bar_text, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.status_bar_text, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_STATUS_AREA: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Status Area Text")); + Draw_Option(eeprom_settings.status_area_text, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.status_area_text, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_COORDINATES: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Coordinates Text")); + Draw_Option(eeprom_settings.coordinates_text, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.coordinates_text, color_names, Custom_Colors); + break; + case COLORSETTINGS_PROGRESS_COORDINATES_LINE: + if (draw) { + Draw_Menu_Item(row, ICON_MaxSpeed, F("Coordinates Line")); + Draw_Option(eeprom_settings.coordinates_split_line, color_names, row, false, true); + } + else + Modify_Option(eeprom_settings.coordinates_split_line, color_names, Custom_Colors); + break; + } // switch (item) + break; + + case Advanced: + + #define ADVANCED_BACK 0 + #define ADVANCED_BEEPER (ADVANCED_BACK + ENABLED(SOUND_MENU_ITEM)) + #define ADVANCED_PROBE (ADVANCED_BEEPER + ENABLED(HAS_BED_PROBE)) + #define ADVANCED_CORNER (ADVANCED_PROBE + 1) + #define ADVANCED_LA (ADVANCED_CORNER + ENABLED(LIN_ADVANCE)) + #define ADVANCED_LOAD (ADVANCED_LA + ENABLED(ADVANCED_PAUSE_FEATURE)) + #define ADVANCED_UNLOAD (ADVANCED_LOAD + ENABLED(ADVANCED_PAUSE_FEATURE)) + #define ADVANCED_COLD_EXTRUDE (ADVANCED_UNLOAD + ENABLED(PREVENT_COLD_EXTRUSION)) + #define ADVANCED_FILSENSORENABLED (ADVANCED_COLD_EXTRUDE + ENABLED(FILAMENT_RUNOUT_SENSOR)) + #define ADVANCED_FILSENSORDISTANCE (ADVANCED_FILSENSORENABLED + ENABLED(HAS_FILAMENT_RUNOUT_DISTANCE)) + #define ADVANCED_POWER_LOSS (ADVANCED_FILSENSORDISTANCE + ENABLED(POWER_LOSS_RECOVERY)) + #define ADVANCED_TOTAL ADVANCED_POWER_LOSS + + switch (item) { + case ADVANCED_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Control, CONTROL_ADVANCED); + break; + + #if ENABLED(SOUND_MENU_ITEM) + case ADVANCED_BEEPER: + if (draw) { + Draw_Menu_Item(row, ICON_Version, F("LCD Beeper")); + Draw_Checkbox(row, ui.sound_on); + } + else { + ui.sound_on = !ui.sound_on; + Draw_Checkbox(row, ui.sound_on); + } + break; + #endif + + #if HAS_BED_PROBE + case ADVANCED_PROBE: + if (draw) + Draw_Menu_Item(row, ICON_StepX, F("Probe"), nullptr, true); + else + Draw_Menu(ProbeMenu); + break; + #endif + + case ADVANCED_CORNER: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccelerated, F("Bed Screw Inset")); + Draw_Float(corner_pos, row, false, 10); + } + else + Modify_Value(corner_pos, 1, 100, 10); + break; + + #if ENABLED(LIN_ADVANCE) + case ADVANCED_LA: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccelerated, F("Lin Advance Kp")); + Draw_Float(planner.extruder_advance_K[0], row, false, 100); + } + else + Modify_Value(planner.extruder_advance_K[0], 0, 10, 100); + break; + #endif + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + case ADVANCED_LOAD: + if (draw) { + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Load Length")); + Draw_Float(fc_settings[0].load_length, row, false, 1); + } + else + Modify_Value(fc_settings[0].load_length, 0, EXTRUDE_MAXLENGTH, 1); + break; + case ADVANCED_UNLOAD: + if (draw) { + Draw_Menu_Item(row, ICON_ReadEEPROM, F("Unload Length")); + Draw_Float(fc_settings[0].unload_length, row, false, 1); + } + else + Modify_Value(fc_settings[0].unload_length, 0, EXTRUDE_MAXLENGTH, 1); + break; + #endif // ADVANCED_PAUSE_FEATURE + + #if ENABLED(PREVENT_COLD_EXTRUSION) + case ADVANCED_COLD_EXTRUDE: + if (draw) { + Draw_Menu_Item(row, ICON_Cool, F("Min Extrusion T")); + Draw_Float(thermalManager.extrude_min_temp, row, false, 1); + } + else { + Modify_Value(thermalManager.extrude_min_temp, 0, MAX_E_TEMP, 1); + thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0); + } + break; + #endif + + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + case ADVANCED_FILSENSORENABLED: + if (draw) { + Draw_Menu_Item(row, ICON_Extruder, F("Filament Sensor")); + Draw_Checkbox(row, runout.enabled); + } + else { + runout.enabled = !runout.enabled; + Draw_Checkbox(row, runout.enabled); + } + break; + + #if ENABLED(HAS_FILAMENT_RUNOUT_DISTANCE) + case ADVANCED_FILSENSORDISTANCE: + if (draw) { + Draw_Menu_Item(row, ICON_MaxAccE, F("Runout Distance")); + Draw_Float(runout.runout_distance(), row, false, 10); + } + else + Modify_Value(runout.runout_distance(), 0, 999, 10); + break; + #endif + #endif // FILAMENT_RUNOUT_SENSOR + + #if ENABLED(POWER_LOSS_RECOVERY) + case ADVANCED_POWER_LOSS: + if (draw) { + Draw_Menu_Item(row, ICON_Motion, F("Power-loss recovery")); + Draw_Checkbox(row, recovery.enabled); + } + else { + recovery.enable(!recovery.enabled); + Draw_Checkbox(row, recovery.enabled); + } + break; + #endif + } + break; + + #if HAS_BED_PROBE + case ProbeMenu: + + #define PROBE_BACK 0 + #define PROBE_XOFFSET (PROBE_BACK + 1) + #define PROBE_YOFFSET (PROBE_XOFFSET + 1) + #define PROBE_TEST (PROBE_YOFFSET + 1) + #define PROBE_TEST_COUNT (PROBE_TEST + 1) + #define PROBE_TOTAL PROBE_TEST_COUNT + + static uint8_t testcount = 4; + + switch (item) { + case PROBE_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Advanced, ADVANCED_PROBE); + break; + + case PROBE_XOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_StepX, F("Probe X Offset")); + Draw_Float(probe.offset.x, row, false, 10); + } + else + Modify_Value(probe.offset.x, -MAX_XY_OFFSET, MAX_XY_OFFSET, 10); + break; + case PROBE_YOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_StepY, F("Probe Y Offset")); + Draw_Float(probe.offset.y, row, false, 10); + } + else + Modify_Value(probe.offset.y, -MAX_XY_OFFSET, MAX_XY_OFFSET, 10); + break; + case PROBE_TEST: + if (draw) + Draw_Menu_Item(row, ICON_StepY, F("M48 Probe Test")); + else { + sprintf_P(cmd, PSTR("G28O\nM48 X%s Y%s P%i"), dtostrf((X_BED_SIZE + X_MIN_POS) / 2.0f, 1, 3, str_1), dtostrf((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 1, 3, str_2), testcount); + gcode.process_subcommands_now(cmd); + } + break; + case PROBE_TEST_COUNT: + if (draw) { + Draw_Menu_Item(row, ICON_StepY, F("Probe Test Count")); + Draw_Float(testcount, row, false, 1); + } + else + Modify_Value(testcount, 4, 50, 1); + break; + } + break; + #endif + + case InfoMain: + case Info: + + #define INFO_BACK 0 + #define INFO_PRINTCOUNT (INFO_BACK + ENABLED(PRINTCOUNTER)) + #define INFO_PRINTTIME (INFO_PRINTCOUNT + ENABLED(PRINTCOUNTER)) + #define INFO_SIZE (INFO_PRINTTIME + 1) + #define INFO_VERSION (INFO_SIZE + 1) + #define INFO_CONTACT (INFO_VERSION + 1) + #define INFO_TOTAL INFO_BACK + + switch (item) { + case INFO_BACK: + if (draw) { + Draw_Menu_Item(row, ICON_Back, F("Back")); + + #if ENABLED(PRINTCOUNTER) + char row1[50], row2[50], buf[32]; + printStatistics ps = print_job_timer.getStats(); + + sprintf_P(row1, PSTR("%i prints, %i finished"), ps.totalPrints, ps.finishedPrints); + sprintf_P(row2, PSTR("%s m filament used"), dtostrf(ps.filamentUsed / 1000, 1, 2, str_1)); + Draw_Menu_Item(INFO_PRINTCOUNT, ICON_HotendTemp, row1, row2, false, true); + + duration_t(print_job_timer.getStats().printTime).toString(buf); + sprintf_P(row1, PSTR("Printed: %s"), buf); + duration_t(print_job_timer.getStats().longestPrint).toString(buf); + sprintf_P(row2, PSTR("Longest: %s"), buf); + Draw_Menu_Item(INFO_PRINTTIME, ICON_PrintTime, row1, row2, false, true); + #endif + + Draw_Menu_Item(INFO_SIZE, ICON_PrintSize, F(MACHINE_SIZE), nullptr, false, true); + Draw_Menu_Item(INFO_VERSION, ICON_Version, F(SHORT_BUILD_VERSION), nullptr, false, true); + Draw_Menu_Item(INFO_CONTACT, ICON_Contact, F(CORP_WEBSITE), nullptr, false, true); + } + else { + if (menu == Info) + Draw_Menu(Control, CONTROL_INFO); + else + Draw_Main_Menu(3); + } + break; + } + break; + + #if HAS_MESH + case Leveling: + + #define LEVELING_BACK 0 + #define LEVELING_ACTIVE (LEVELING_BACK + 1) + #define LEVELING_GET_TILT (LEVELING_ACTIVE + BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL)) + #define LEVELING_GET_MESH (LEVELING_GET_TILT + 1) + #define LEVELING_MANUAL (LEVELING_GET_MESH + 1) + #define LEVELING_VIEW (LEVELING_MANUAL + 1) + #define LEVELING_SETTINGS (LEVELING_VIEW + 1) + #define LEVELING_SLOT (LEVELING_SETTINGS + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_LOAD (LEVELING_SLOT + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SAVE (LEVELING_LOAD + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_TOTAL LEVELING_SAVE + + switch (item) { + case LEVELING_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Main_Menu(3); + break; + case LEVELING_ACTIVE: + if (draw) { + Draw_Menu_Item(row, ICON_StockConfiguration, F("Leveling Active")); + Draw_Checkbox(row, planner.leveling_active); + } + else { + if (!planner.leveling_active) { + set_bed_leveling_enabled(!planner.leveling_active); + if (!planner.leveling_active) { + Confirm_Handler(LevelError); + break; + } + } + else + set_bed_leveling_enabled(!planner.leveling_active); + Draw_Checkbox(row, planner.leveling_active); + } + break; + #if BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL) + case LEVELING_GET_TILT: + if (draw) + Draw_Menu_Item(row, ICON_Tilt, F("Autotilt Current Mesh")); + else { + if (bedlevel.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + Popup_Handler(Home); + gcode.home_all_axes(true); + Popup_Handler(Level); + if (mesh_conf.tilt_grid > 1) { + sprintf_P(cmd, PSTR("G29 J%i"), mesh_conf.tilt_grid); + gcode.process_subcommands_now(cmd); + } + else + gcode.process_subcommands_now(F("G29 J")); + planner.synchronize(); + Redraw_Menu(); + } + break; + #endif + case LEVELING_GET_MESH: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, F("Create New Mesh")); + else { + Popup_Handler(Home); + gcode.home_all_axes(true); + #if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(PREHEAT_BEFORE_LEVELING) + Popup_Handler(Heating); + probe.preheat_for_probing(LEVELING_NOZZLE_TEMP, LEVELING_BED_TEMP); + #endif + #if HAS_BED_PROBE + Popup_Handler(Level); + gcode.process_subcommands_now(F("G29 P0\nG29 P1")); + gcode.process_subcommands_now(F("G29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nG29 P3\nM420 S1")); + planner.synchronize(); + Update_Status("Probed all reachable points"); + Popup_Handler(SaveLevel); + #else + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + mesh_conf.goto_mesh_value = true; + mesh_conf.mesh_x = mesh_conf.mesh_y = 0; + Popup_Handler(MoveWait); + mesh_conf.manual_mesh_move(); + Draw_Menu(UBLMesh); + #endif + #elif HAS_BED_PROBE + Popup_Handler(Level); + gcode.process_subcommands_now(F("G29")); + planner.synchronize(); + Popup_Handler(SaveLevel); + #else + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + gridpoint = 1; + Popup_Handler(MoveWait); + gcode.process_subcommands_now(F("G29")); + planner.synchronize(); + Draw_Menu(ManualMesh); + #endif + } + break; + case LEVELING_MANUAL: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, F("Manual Tuning"), nullptr, true); + else { + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + if (!leveling_is_valid()) { + Confirm_Handler(InvalidMesh); + break; + } + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) + if (bedlevel.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + #endif + if (axes_should_home()) { + Popup_Handler(Home); + gcode.home_all_axes(true); + } + level_state = planner.leveling_active; + set_bed_leveling_enabled(false); + mesh_conf.goto_mesh_value = false; + #if ENABLED(PREHEAT_BEFORE_LEVELING) + Popup_Handler(Heating); + #if HAS_HOTEND + if (thermalManager.degTargetHotend(0) < LEVELING_NOZZLE_TEMP) + thermalManager.setTargetHotend(LEVELING_NOZZLE_TEMP, 0); + #endif + #if HAS_HEATED_BED + if (thermalManager.degTargetBed() < LEVELING_BED_TEMP) + thermalManager.setTargetBed(LEVELING_BED_TEMP); + #endif + TERN_(HAS_HOTEND, thermalManager.wait_for_hotend(0)); + TERN_(HAS_HEATED_BED, thermalManager.wait_for_bed_heating()); + #endif + Popup_Handler(MoveWait); + mesh_conf.manual_mesh_move(); + Draw_Menu(LevelManual); + } + break; + case LEVELING_VIEW: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, GET_TEXT_F(MSG_MESH_VIEW), nullptr, true); + else { + #if ENABLED(AUTO_BED_LEVELING_UBL) + if (bedlevel.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + #endif + Draw_Menu(LevelView); + } + break; + case LEVELING_SETTINGS: + if (draw) + Draw_Menu_Item(row, ICON_Step, F("Leveling Settings"), nullptr, true); + else + Draw_Menu(LevelSettings); + break; + #if ENABLED(AUTO_BED_LEVELING_UBL) + case LEVELING_SLOT: + if (draw) { + Draw_Menu_Item(row, ICON_PrintSize, F("Mesh Slot")); + Draw_Float(bedlevel.storage_slot, row, false, 1); + } + else + Modify_Value(bedlevel.storage_slot, 0, settings.calc_num_meshes() - 1, 1); + break; + case LEVELING_LOAD: + if (draw) + Draw_Menu_Item(row, ICON_ReadEEPROM, F("Load Mesh")); + else { + if (bedlevel.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + gcode.process_subcommands_now(F("G29 L")); + planner.synchronize(); + AudioFeedback(true); + } + break; + case LEVELING_SAVE: + if (draw) + Draw_Menu_Item(row, ICON_WriteEEPROM, F("Save Mesh")); + else { + if (bedlevel.storage_slot < 0) { + Popup_Handler(MeshSlot); + break; + } + gcode.process_subcommands_now(F("G29 S")); + planner.synchronize(); + AudioFeedback(true); + } + break; + #endif + } + break; + + case LevelView: + + #define LEVELING_VIEW_BACK 0 + #define LEVELING_VIEW_MESH (LEVELING_VIEW_BACK + 1) + #define LEVELING_VIEW_TEXT (LEVELING_VIEW_MESH + 1) + #define LEVELING_VIEW_ASYMMETRIC (LEVELING_VIEW_TEXT + 1) + #define LEVELING_VIEW_TOTAL LEVELING_VIEW_ASYMMETRIC + + switch (item) { + case LEVELING_VIEW_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Leveling, LEVELING_VIEW); + break; + case LEVELING_VIEW_MESH: + if (draw) + Draw_Menu_Item(row, ICON_PrintSize, GET_TEXT_F(MSG_MESH_VIEW), nullptr, true); + else + Draw_Menu(MeshViewer); + break; + case LEVELING_VIEW_TEXT: + if (draw) { + Draw_Menu_Item(row, ICON_Contact, F("Viewer Show Values")); + Draw_Checkbox(row, mesh_conf.viewer_print_value); + } + else { + mesh_conf.viewer_print_value = !mesh_conf.viewer_print_value; + Draw_Checkbox(row, mesh_conf.viewer_print_value); + } + break; + case LEVELING_VIEW_ASYMMETRIC: + if (draw) { + Draw_Menu_Item(row, ICON_Axis, F("Viewer Asymmetric")); + Draw_Checkbox(row, mesh_conf.viewer_asymmetric_range); + } + else { + mesh_conf.viewer_asymmetric_range = !mesh_conf.viewer_asymmetric_range; + Draw_Checkbox(row, mesh_conf.viewer_asymmetric_range); + } + break; + } + break; + + case LevelSettings: + + #define LEVELING_SETTINGS_BACK 0 + #define LEVELING_SETTINGS_FADE (LEVELING_SETTINGS_BACK + 1) + #define LEVELING_SETTINGS_TILT (LEVELING_SETTINGS_FADE + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SETTINGS_PLANE (LEVELING_SETTINGS_TILT + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SETTINGS_ZERO (LEVELING_SETTINGS_PLANE + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SETTINGS_UNDEF (LEVELING_SETTINGS_ZERO + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_SETTINGS_TOTAL LEVELING_SETTINGS_UNDEF + + switch (item) { + case LEVELING_SETTINGS_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Menu(Leveling, LEVELING_SETTINGS); + break; + case LEVELING_SETTINGS_FADE: + if (draw) { + Draw_Menu_Item(row, ICON_Fade, F("Fade Mesh within")); + Draw_Float(planner.z_fade_height, row, false, 1); + } + else { + Modify_Value(planner.z_fade_height, 0, Z_MAX_POS, 1); + planner.z_fade_height = -1; + set_z_fade_height(planner.z_fade_height); + } + break; + + #if ENABLED(AUTO_BED_LEVELING_UBL) + case LEVELING_SETTINGS_TILT: + if (draw) { + Draw_Menu_Item(row, ICON_Tilt, F("Tilting Grid Size")); + Draw_Float(mesh_conf.tilt_grid, row, false, 1); + } + else + Modify_Value(mesh_conf.tilt_grid, 1, 8, 1); + break; + case LEVELING_SETTINGS_PLANE: + if (draw) + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Convert Mesh to Plane")); + else { + if (mesh_conf.create_plane_from_mesh()) break; + gcode.process_subcommands_now(F("M420 S1")); + planner.synchronize(); + AudioFeedback(true); + } + break; + case LEVELING_SETTINGS_ZERO: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, F("Zero Current Mesh")); + else + ZERO(bedlevel.z_values); + break; + case LEVELING_SETTINGS_UNDEF: + if (draw) + Draw_Menu_Item(row, ICON_Mesh, F("Clear Current Mesh")); + else + bedlevel.invalidate(); + break; + #endif // AUTO_BED_LEVELING_UBL + } + break; + + case MeshViewer: + #define MESHVIEW_BACK 0 + #define MESHVIEW_TOTAL MESHVIEW_BACK + + if (item == MESHVIEW_BACK) { + if (draw) { + Draw_Menu_Item(0, ICON_Back, F("Back")); + mesh_conf.Draw_Bed_Mesh(); + mesh_conf.Set_Mesh_Viewer_Status(); + } + else if (!mesh_conf.drawing_mesh) { + Draw_Menu(LevelView, LEVELING_VIEW_MESH); + Update_Status(""); + } + } + break; + + case LevelManual: + + #define LEVELING_M_BACK 0 + #define LEVELING_M_X (LEVELING_M_BACK + 1) + #define LEVELING_M_Y (LEVELING_M_X + 1) + #define LEVELING_M_NEXT (LEVELING_M_Y + 1) + #define LEVELING_M_OFFSET (LEVELING_M_NEXT + 1) + #define LEVELING_M_UP (LEVELING_M_OFFSET + 1) + #define LEVELING_M_DOWN (LEVELING_M_UP + 1) + #define LEVELING_M_GOTO_VALUE (LEVELING_M_DOWN + 1) + #define LEVELING_M_UNDEF (LEVELING_M_GOTO_VALUE + ENABLED(AUTO_BED_LEVELING_UBL)) + #define LEVELING_M_TOTAL LEVELING_M_UNDEF + + switch (item) { + case LEVELING_M_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else { + set_bed_leveling_enabled(level_state); + TERN_(AUTO_BED_LEVELING_BILINEAR, bedlevel.refresh_bed_level()); + Draw_Menu(Leveling, LEVELING_MANUAL); + } + break; + case LEVELING_M_X: + if (draw) { + Draw_Menu_Item(row, ICON_MoveX, F("Mesh Point X")); + Draw_Float(mesh_conf.mesh_x, row, 0, 1); + } + else + Modify_Value(mesh_conf.mesh_x, 0, GRID_MAX_POINTS_X - 1, 1); + break; + case LEVELING_M_Y: + if (draw) { + Draw_Menu_Item(row, ICON_MoveY, F("Mesh Point Y")); + Draw_Float(mesh_conf.mesh_y, row, 0, 1); + } + else + Modify_Value(mesh_conf.mesh_y, 0, GRID_MAX_POINTS_Y - 1, 1); + break; + case LEVELING_M_NEXT: + if (draw) + Draw_Menu_Item(row, ICON_More, F("Next Point")); + else { + if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) { + if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 0) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 1)) + mesh_conf.mesh_y++; + else if (mesh_conf.mesh_y % 2 == 0) + mesh_conf.mesh_x++; + else + mesh_conf.mesh_x--; + mesh_conf.manual_mesh_move(); + } + } + break; + case LEVELING_M_OFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, F("Point Z Offset")); + Draw_Float(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); + } + else { + if (isnan(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y])) + bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; + Modify_Value(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + } + break; + case LEVELING_M_UP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); + else if (bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { + bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; + gcode.process_subcommands_now(F("M290 Z0.01")); + planner.synchronize(); + current_position.z += 0.01f; + sync_plan_position(); + Draw_Float(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); + } + break; + case LEVELING_M_DOWN: + if (draw) + Draw_Menu_Item(row, ICON_AxisD, F("Microstep Down")); + else if (bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { + bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; + gcode.process_subcommands_now(F("M290 Z-0.01")); + planner.synchronize(); + current_position.z -= 0.01f; + sync_plan_position(); + Draw_Float(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); + } + break; + case LEVELING_M_GOTO_VALUE: + if (draw) { + Draw_Menu_Item(row, ICON_StockConfiguration, F("Go to Mesh Z Value")); + Draw_Checkbox(row, mesh_conf.goto_mesh_value); + } + else { + mesh_conf.goto_mesh_value = !mesh_conf.goto_mesh_value; + current_position.z = 0; + mesh_conf.manual_mesh_move(true); + Draw_Checkbox(row, mesh_conf.goto_mesh_value); + } + break; + #if ENABLED(AUTO_BED_LEVELING_UBL) + case LEVELING_M_UNDEF: + if (draw) + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Clear Point Value")); + else { + mesh_conf.manual_value_update(true); + Redraw_Menu(false); + } + break; + #endif + } + break; + #endif // HAS_MESH + + #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE + case UBLMesh: + + #define UBL_M_BACK 0 + #define UBL_M_NEXT (UBL_M_BACK + 1) + #define UBL_M_PREV (UBL_M_NEXT + 1) + #define UBL_M_OFFSET (UBL_M_PREV + 1) + #define UBL_M_UP (UBL_M_OFFSET + 1) + #define UBL_M_DOWN (UBL_M_UP + 1) + #define UBL_M_TOTAL UBL_M_DOWN + + switch (item) { + case UBL_M_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else { + set_bed_leveling_enabled(level_state); + Draw_Menu(Leveling, LEVELING_GET_MESH); + } + break; + case UBL_M_NEXT: + if (draw) { + if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) + Draw_Menu_Item(row, ICON_More, F("Next Point")); + else + Draw_Menu_Item(row, ICON_More, F("Save Mesh")); + } + else { + if (mesh_conf.mesh_x != (GRID_MAX_POINTS_X - 1) || mesh_conf.mesh_y != (GRID_MAX_POINTS_Y - 1)) { + if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 0) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 1)) + mesh_conf.mesh_y++; + else if (mesh_conf.mesh_y % 2 == 0) + mesh_conf.mesh_x++; + else + mesh_conf.mesh_x--; + mesh_conf.manual_mesh_move(); + } + else { + gcode.process_subcommands_now(F("G29 S")); + planner.synchronize(); + AudioFeedback(true); + Draw_Menu(Leveling, LEVELING_GET_MESH); + } + } + break; + case UBL_M_PREV: + if (draw) + Draw_Menu_Item(row, ICON_More, F("Previous Point")); + else { + if (mesh_conf.mesh_x != 0 || mesh_conf.mesh_y != 0) { + if ((mesh_conf.mesh_x == (GRID_MAX_POINTS_X - 1) && mesh_conf.mesh_y % 2 == 1) || (mesh_conf.mesh_x == 0 && mesh_conf.mesh_y % 2 == 0)) + mesh_conf.mesh_y--; + else if (mesh_conf.mesh_y % 2 == 0) + mesh_conf.mesh_x--; + else + mesh_conf.mesh_x++; + mesh_conf.manual_mesh_move(); + } + } + break; + case UBL_M_OFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, F("Point Z Offset")); + Draw_Float(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row, false, 100); + } + else { + if (isnan(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y])) + bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] = 0; + Modify_Value(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + } + break; + case UBL_M_UP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); + else if (bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { + bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; + gcode.process_subcommands_now(F("M290 Z0.01")); + planner.synchronize(); + current_position.z += 0.01f; + sync_plan_position(); + Draw_Float(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 1, false, 100); + } + break; + case UBL_M_DOWN: + if (draw) + Draw_Menu_Item(row, ICON_Axis, F("Microstep Down")); + else if (bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { + bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; + gcode.process_subcommands_now(F("M290 Z-0.01")); + planner.synchronize(); + current_position.z -= 0.01f; + sync_plan_position(); + Draw_Float(bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y], row - 2, false, 100); + } + break; + } + break; + #endif // AUTO_BED_LEVELING_UBL && !HAS_BED_PROBE + + #if ENABLED(PROBE_MANUALLY) + case ManualMesh: + + #define MMESH_BACK 0 + #define MMESH_NEXT (MMESH_BACK + 1) + #define MMESH_OFFSET (MMESH_NEXT + 1) + #define MMESH_UP (MMESH_OFFSET + 1) + #define MMESH_DOWN (MMESH_UP + 1) + #define MMESH_OLD (MMESH_DOWN + 1) + #define MMESH_TOTAL MMESH_OLD + + switch (item) { + case MMESH_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Cancel")); + else { + gcode.process_subcommands_now(F("G29 A")); + planner.synchronize(); + set_bed_leveling_enabled(level_state); + Draw_Menu(Leveling, LEVELING_GET_MESH); + } + break; + case MMESH_NEXT: + if (draw) { + if (gridpoint < GRID_MAX_POINTS) + Draw_Menu_Item(row, ICON_More, F("Next Point")); + else + Draw_Menu_Item(row, ICON_More, F("Save Mesh")); + } + else if (gridpoint < GRID_MAX_POINTS) { + Popup_Handler(MoveWait); + gcode.process_subcommands_now(F("G29")); + planner.synchronize(); + gridpoint++; + Redraw_Menu(); + } + else { + gcode.process_subcommands_now(F("G29")); + planner.synchronize(); + AudioFeedback(settings.save()); + Draw_Menu(Leveling, LEVELING_GET_MESH); + } + break; + case MMESH_OFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_SetZOffset, F("Z Position")); + current_position.z = MANUAL_PROBE_START_Z; + Draw_Float(current_position.z, row, false, 100); + } + else + Modify_Value(current_position.z, MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + break; + case MMESH_UP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, F("Microstep Up")); + else if (current_position.z < MAX_Z_OFFSET) { + gcode.process_subcommands_now(F("M290 Z0.01")); + planner.synchronize(); + current_position.z += 0.01f; + sync_plan_position(); + Draw_Float(current_position.z, row - 1, false, 100); + } + break; + case MMESH_DOWN: + if (draw) + Draw_Menu_Item(row, ICON_AxisD, F("Microstep Down")); + else if (current_position.z > MIN_Z_OFFSET) { + gcode.process_subcommands_now(F("M290 Z-0.01")); + planner.synchronize(); + current_position.z -= 0.01f; + sync_plan_position(); + Draw_Float(current_position.z, row - 2, false, 100); + } + break; + case MMESH_OLD: + uint8_t mesh_x, mesh_y; + // 0,0 -> 1,0 -> 2,0 -> 2,1 -> 1,1 -> 0,1 -> 0,2 -> 1,2 -> 2,2 + mesh_y = (gridpoint - 1) / (GRID_MAX_POINTS_Y); + mesh_x = (gridpoint - 1) % (GRID_MAX_POINTS_X); + + if (mesh_y % 2 == 1) + mesh_x = (GRID_MAX_POINTS_X) - mesh_x - 1; + + const float currval = bedlevel.z_values[mesh_x][mesh_y]; + + if (draw) { + Draw_Menu_Item(row, ICON_Zoffset, F("Goto Mesh Value")); + Draw_Float(currval, row, false, 100); + } + else if (!isnan(currval)) { + current_position.z = currval; + planner.synchronize(); + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + Draw_Float(current_position.z, row - 3, false, 100); + } + break; + } + break; + #endif // PROBE_MANUALLY + + case Tune: + + #define TUNE_BACK 0 + #define TUNE_SPEED (TUNE_BACK + 1) + #define TUNE_FLOW (TUNE_SPEED + ENABLED(HAS_HOTEND)) + #define TUNE_HOTEND (TUNE_FLOW + ENABLED(HAS_HOTEND)) + #define TUNE_BED (TUNE_HOTEND + ENABLED(HAS_HEATED_BED)) + #define TUNE_FAN (TUNE_BED + ENABLED(HAS_FAN)) + #define TUNE_ZOFFSET (TUNE_FAN + ENABLED(HAS_ZOFFSET_ITEM)) + #define TUNE_ZUP (TUNE_ZOFFSET + ENABLED(HAS_ZOFFSET_ITEM)) + #define TUNE_ZDOWN (TUNE_ZUP + ENABLED(HAS_ZOFFSET_ITEM)) + #define TUNE_CHANGEFIL (TUNE_ZDOWN + ENABLED(FILAMENT_LOAD_UNLOAD_GCODES)) + #define TUNE_FILSENSORENABLED (TUNE_CHANGEFIL + ENABLED(FILAMENT_RUNOUT_SENSOR)) + #define TUNE_BACKLIGHT_OFF (TUNE_FILSENSORENABLED + 1) + #define TUNE_BACKLIGHT (TUNE_BACKLIGHT_OFF + 1) + #define TUNE_TOTAL TUNE_BACKLIGHT + + switch (item) { + case TUNE_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Back")); + else + Draw_Print_Screen(); + break; + case TUNE_SPEED: + if (draw) { + Draw_Menu_Item(row, ICON_Speed, F("Print Speed")); + Draw_Float(feedrate_percentage, row, false, 1); + } + else + Modify_Value(feedrate_percentage, MIN_PRINT_SPEED, MAX_PRINT_SPEED, 1); + break; + + #if HAS_HOTEND + case TUNE_FLOW: + if (draw) { + Draw_Menu_Item(row, ICON_Speed, F("Flow Rate")); + Draw_Float(planner.flow_percentage[0], row, false, 1); + } + else + Modify_Value(planner.flow_percentage[0], MIN_FLOW_RATE, MAX_FLOW_RATE, 1); + break; + case TUNE_HOTEND: + if (draw) { + Draw_Menu_Item(row, ICON_SetEndTemp, F("Hotend")); + Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_hotend[0].target, MIN_E_TEMP, MAX_E_TEMP, 1); + break; + #endif + + #if HAS_HEATED_BED + case TUNE_BED: + if (draw) { + Draw_Menu_Item(row, ICON_SetBedTemp, F("Bed")); + Draw_Float(thermalManager.temp_bed.target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_bed.target, MIN_BED_TEMP, MAX_BED_TEMP, 1); + break; + #endif + + #if HAS_FAN + case TUNE_FAN: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, F("Fan")); + Draw_Float(thermalManager.fan_speed[0], row, false, 1); + } + else + Modify_Value(thermalManager.fan_speed[0], MIN_FAN_SPEED, MAX_FAN_SPEED, 1); + break; + #endif + + #if HAS_ZOFFSET_ITEM + case TUNE_ZOFFSET: + if (draw) { + Draw_Menu_Item(row, ICON_FanSpeed, F("Z-Offset")); + Draw_Float(zoffsetvalue, row, false, 100); + } + else + Modify_Value(zoffsetvalue, MIN_Z_OFFSET, MAX_Z_OFFSET, 100); + break; + case TUNE_ZUP: + if (draw) + Draw_Menu_Item(row, ICON_Axis, F("Z-Offset Up")); + else if (zoffsetvalue < MAX_Z_OFFSET) { + gcode.process_subcommands_now(F("M290 Z0.01")); + zoffsetvalue += 0.01; + Draw_Float(zoffsetvalue, row - 1, false, 100); + } + break; + case TUNE_ZDOWN: + if (draw) + Draw_Menu_Item(row, ICON_AxisD, F("Z-Offset Down")); + else if (zoffsetvalue > MIN_Z_OFFSET) { + gcode.process_subcommands_now(F("M290 Z-0.01")); + zoffsetvalue -= 0.01; + Draw_Float(zoffsetvalue, row - 2, false, 100); + } + break; + #endif + + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case TUNE_CHANGEFIL: + if (draw) + Draw_Menu_Item(row, ICON_ResumeEEPROM, F("Change Filament")); + else + Popup_Handler(ConfFilChange); + break; + #endif + + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + case TUNE_FILSENSORENABLED: + if (draw) { + Draw_Menu_Item(row, ICON_Extruder, F("Filament Sensor")); + Draw_Checkbox(row, runout.enabled); + } + else { + runout.enabled = !runout.enabled; + Draw_Checkbox(row, runout.enabled); + } + break; + #endif + + case TUNE_BACKLIGHT_OFF: + if (draw) + Draw_Menu_Item(row, ICON_Brightness, F("Display Off")); + else + ui.set_brightness(0); + break; + case TUNE_BACKLIGHT: + if (draw) { + Draw_Menu_Item(row, ICON_Brightness, F("LCD Brightness")); + Draw_Float(ui.brightness, row, false, 1); + } + else + Modify_Value(ui.brightness, LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, 1, ui.refresh_brightness); + break; + } + break; + + #if HAS_PREHEAT && HAS_HOTEND + + case PreheatHotend: + + #define PREHEATHOTEND_BACK 0 + #define PREHEATHOTEND_CONTINUE (PREHEATHOTEND_BACK + 1) + #define PREHEATHOTEND_1 (PREHEATHOTEND_CONTINUE + (PREHEAT_COUNT >= 1)) + #define PREHEATHOTEND_2 (PREHEATHOTEND_1 + (PREHEAT_COUNT >= 2)) + #define PREHEATHOTEND_3 (PREHEATHOTEND_2 + (PREHEAT_COUNT >= 3)) + #define PREHEATHOTEND_4 (PREHEATHOTEND_3 + (PREHEAT_COUNT >= 4)) + #define PREHEATHOTEND_5 (PREHEATHOTEND_4 + (PREHEAT_COUNT >= 5)) + #define PREHEATHOTEND_CUSTOM (PREHEATHOTEND_5 + 1) + #define PREHEATHOTEND_TOTAL PREHEATHOTEND_CUSTOM + + switch (item) { + case PREHEATHOTEND_BACK: + if (draw) + Draw_Menu_Item(row, ICON_Back, F("Cancel")); + else { + thermalManager.setTargetHotend(0, 0); + thermalManager.set_fan_speed(0, 0); + Redraw_Menu(false, true, true); + } + break; + case PREHEATHOTEND_CONTINUE: + if (draw) + Draw_Menu_Item(row, ICON_SetEndTemp, F("Continue")); + else { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + switch (last_menu) { + case Prepare: + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now(cmd); + break; + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case ChangeFilament: + switch (last_selection) { + case CHANGEFIL_LOAD: + Popup_Handler(FilLoad); + gcode.process_subcommands_now(F("M701")); + planner.synchronize(); + Redraw_Menu(true, true, true); + break; + case CHANGEFIL_UNLOAD: + Popup_Handler(FilLoad, true); + gcode.process_subcommands_now(F("M702")); + planner.synchronize(); + Redraw_Menu(true, true, true); + break; + case CHANGEFIL_CHANGE: + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now(cmd); + break; + } + break; + #endif + default: + Redraw_Menu(true, true, true); + break; + } + } + break; + + + #define _PREHEAT_HOTEND_CASE(N) \ + case PREHEATHOTEND_##N: \ + if (draw) Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_## N ##_LABEL)); \ + else ui.preheat_hotend_and_fan((N) - 1); \ + break; + + REPEAT_1(PREHEAT_COUNT, _PREHEAT_HOTEND_CASE) + + case PREHEATHOTEND_CUSTOM: + if (draw) { + Draw_Menu_Item(row, ICON_Temperature, F("Custom")); + Draw_Float(thermalManager.temp_hotend[0].target, row, false, 1); + } + else + Modify_Value(thermalManager.temp_hotend[0].target, EXTRUDE_MINTEMP, MAX_E_TEMP, 1); + break; + } + break; + + #endif // HAS_PREHEAT && HAS_HOTEND + } +} + +FSTR_P CrealityDWINClass::Get_Menu_Title(uint8_t menu) { + switch (menu) { + case MainMenu: return F("Main Menu"); + case Prepare: return F("Prepare"); + case HomeMenu: return F("Homing Menu"); + case Move: return F("Move"); + case ManualLevel: return F("Manual Leveling"); + #if HAS_ZOFFSET_ITEM + case ZOffset: return F("Z Offset"); + #endif + #if HAS_PREHEAT + case Preheat: return F("Preheat"); + #endif + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case ChangeFilament: return F("Change Filament"); + #endif + #if HAS_CUSTOM_MENU + case MenuCustom: + #ifdef CUSTOM_MENU_CONFIG_TITLE + return F(CUSTOM_MENU_CONFIG_TITLE); + #else + return F("Custom Commands"); + #endif + #endif + case Control: return F("Control"); + case TempMenu: return F("Temperature"); + #if HAS_HOTEND || HAS_HEATED_BED + case PID: return F("PID Menu"); + #endif + #if HAS_HOTEND + case HotendPID: return F("Hotend PID Settings"); + #endif + #if HAS_HEATED_BED + case BedPID: return F("Bed PID Settings"); + #endif + #if HAS_PREHEAT + #define _PREHEAT_TITLE_CASE(N) case Preheat##N: return F(PREHEAT_## N ##_LABEL " Settings"); + REPEAT_1(PREHEAT_COUNT, _PREHEAT_TITLE_CASE) + #endif + case Motion: return F("Motion Settings"); + case HomeOffsets: return F("Home Offsets"); + case MaxSpeed: return F("Max Speed"); + case MaxAcceleration: return F("Max Acceleration"); + #if HAS_CLASSIC_JERK + case MaxJerk: return F("Max Jerk"); + #endif + case Steps: return F("Steps/mm"); + case Visual: return F("Visual Settings"); + case Advanced: return F("Advanced Settings"); + #if HAS_BED_PROBE + case ProbeMenu: return F("Probe Menu"); + #endif + case ColorSettings: return F("UI Color Settings"); + case Info: return F("Info"); + case InfoMain: return F("Info"); + #if HAS_MESH + case Leveling: return F("Leveling"); + case LevelView: return GET_TEXT_F(MSG_MESH_VIEW); + case LevelSettings: return F("Leveling Settings"); + case MeshViewer: return GET_TEXT_F(MSG_MESH_VIEW); + case LevelManual: return F("Manual Tuning"); + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE + case UBLMesh: return F("UBL Bed Leveling"); + #endif + #if ENABLED(PROBE_MANUALLY) + case ManualMesh: return F("Mesh Bed Leveling"); + #endif + case Tune: return F("Tune"); + case PreheatHotend: return F("Preheat Hotend"); + } + return F(""); +} + +uint8_t CrealityDWINClass::Get_Menu_Size(uint8_t menu) { + switch (menu) { + case Prepare: return PREPARE_TOTAL; + case HomeMenu: return HOME_TOTAL; + case Move: return MOVE_TOTAL; + case ManualLevel: return MLEVEL_TOTAL; + #if HAS_ZOFFSET_ITEM + case ZOffset: return ZOFFSET_TOTAL; + #endif + #if HAS_PREHEAT + case Preheat: return PREHEAT_TOTAL; + #endif + #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) + case ChangeFilament: return CHANGEFIL_TOTAL; + #endif + #if HAS_CUSTOM_MENU + case MenuCustom: return CUSTOM_MENU_TOTAL; + #endif + case Control: return CONTROL_TOTAL; + case TempMenu: return TEMP_TOTAL; + #if HAS_HOTEND || HAS_HEATED_BED + case PID: return PID_TOTAL; + #endif + #if HAS_HOTEND + case HotendPID: return HOTENDPID_TOTAL; + #endif + #if HAS_HEATED_BED + case BedPID: return BEDPID_TOTAL; + #endif + #if HAS_PREHEAT + case Preheat1 ... CAT(Preheat, PREHEAT_COUNT): + return PREHEAT_SUBMENU_TOTAL; + #endif + case Motion: return MOTION_TOTAL; + case HomeOffsets: return HOMEOFFSETS_TOTAL; + case MaxSpeed: return SPEED_TOTAL; + case MaxAcceleration: return ACCEL_TOTAL; + #if HAS_CLASSIC_JERK + case MaxJerk: return JERK_TOTAL; + #endif + case Steps: return STEPS_TOTAL; + case Visual: return VISUAL_TOTAL; + case Advanced: return ADVANCED_TOTAL; + #if HAS_BED_PROBE + case ProbeMenu: return PROBE_TOTAL; + #endif + case Info: return INFO_TOTAL; + case InfoMain: return INFO_TOTAL; + #if ENABLED(AUTO_BED_LEVELING_UBL) && !HAS_BED_PROBE + case UBLMesh: return UBL_M_TOTAL; + #endif + #if ENABLED(PROBE_MANUALLY) + case ManualMesh: return MMESH_TOTAL; + #endif + #if HAS_MESH + case Leveling: return LEVELING_TOTAL; + case LevelView: return LEVELING_VIEW_TOTAL; + case LevelSettings: return LEVELING_SETTINGS_TOTAL; + case MeshViewer: return MESHVIEW_TOTAL; + case LevelManual: return LEVELING_M_TOTAL; + #endif + case Tune: return TUNE_TOTAL; + + #if HAS_PREHEAT && HAS_HOTEND + case PreheatHotend: return PREHEATHOTEND_TOTAL; + #endif + + case ColorSettings: return COLORSETTINGS_TOTAL; + } + return 0; +} + +/* Popup Config */ + +void CrealityDWINClass::Popup_Handler(PopupID popupid, bool option/*=false*/) { + popup = last_popup = popupid; + switch (popupid) { + case Pause: Draw_Popup(F("Pause Print"), F(""), F(""), Popup); break; + case Stop: Draw_Popup(F("Stop Print"), F(""), F(""), Popup); break; + case Resume: Draw_Popup(F("Resume Print?"), F("Looks Like the last"), F("print was interrupted."), Popup); break; + case ConfFilChange: Draw_Popup(F("Confirm Filament Change"), F(""), F(""), Popup); break; + case PurgeMore: Draw_Popup(F("Purge more filament?"), F("(Cancel to finish process)"), F(""), Popup); break; + case SaveLevel: Draw_Popup(F("Leveling Complete"), F("Save to EEPROM?"), F(""), Popup); break; + case MeshSlot: Draw_Popup(F("Mesh slot not selected"), F("(Confirm to select slot 0)"), F(""), Popup); break; + case ETemp: Draw_Popup(F("Nozzle is too cold"), F("Open Preheat Menu?"), F(""), Popup); break; + case ManualProbing: Draw_Popup(F("Manual Probing"), F("(Confirm to probe)"), F("(cancel to exit)"), Popup); break; + case Level: Draw_Popup(F("Auto Bed Leveling"), F("Please wait until done."), F(""), Wait, ICON_AutoLeveling); break; + case Home: Draw_Popup(option ? F("Parking") : F("Homing"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + case MoveWait: Draw_Popup(F("Moving to Point"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + case Heating: Draw_Popup(F("Heating"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + case FilLoad: Draw_Popup(option ? F("Unloading Filament") : F("Loading Filament"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + case FilChange: Draw_Popup(F("Filament Change"), F("Please wait for prompt."), F(""), Wait, ICON_BLTouch); break; + case TempWarn: Draw_Popup(option ? F("Nozzle temp too low!") : F("Nozzle temp too high!"), F(""), F(""), Wait, option ? ICON_TempTooLow : ICON_TempTooHigh); break; + case Runout: Draw_Popup(F("Filament Runout"), F(""), F(""), Wait, ICON_BLTouch); break; + case PIDWait: Draw_Popup(F("PID Autotune"), F("in process"), F("Please wait until done."), Wait, ICON_BLTouch); break; + case Resuming: Draw_Popup(F("Resuming Print"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + case Custom: Draw_Popup(F("Running Custom GCode"), F("Please wait until done."), F(""), Wait, ICON_BLTouch); break; + default: break; + } +} + +void CrealityDWINClass::Confirm_Handler(PopupID popupid) { + popup = popupid; + switch (popupid) { + case FilInsert: Draw_Popup(F("Insert Filament"), F("Press to Continue"), F(""), Confirm); break; + case HeaterTime: Draw_Popup(F("Heater Timed Out"), F("Press to Reheat"), F(""), Confirm); break; + case UserInput: Draw_Popup(F("Waiting for Input"), F("Press to Continue"), F(""), Confirm); break; + case LevelError: Draw_Popup(F("Couldn't enable Leveling"), F("(Valid mesh must exist)"), F(""), Confirm); break; + case InvalidMesh: Draw_Popup(F("Valid mesh must exist"), F("before tuning can be"), F("performed"), Confirm); break; + default: break; + } +} + +/* Navigation and Control */ + +void CrealityDWINClass::Main_Menu_Control() { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW && selection < PAGE_COUNT - 1) { + selection++; // Select Down + Main_Menu_Icons(); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + selection--; // Select Up + Main_Menu_Icons(); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) + switch (selection) { + case PAGE_PRINT: card.mount(); Draw_SD_List(); break; + case PAGE_PREPARE: Draw_Menu(Prepare); break; + case PAGE_CONTROL: Draw_Menu(Control); break; + case PAGE_INFO_LEVELING: Draw_Menu(TERN(HAS_MESH, Leveling, InfoMain)); break; + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Menu_Control() { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW && selection < Get_Menu_Size(active_menu)) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + selection++; // Select Down + if (selection > scrollpos+MROWS) { + scrollpos++; + DWIN_Frame_AreaMove(1, 2, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + Menu_Item_Handler(active_menu, selection); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + selection--; // Select Up + if (selection < scrollpos) { + scrollpos--; + DWIN_Frame_AreaMove(1, 3, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + Menu_Item_Handler(active_menu, selection); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) + Menu_Item_Handler(active_menu, selection, false); + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Value_Control() { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW) + tempvalue += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + tempvalue -= EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + process = Menu; + EncoderRate.enabled = false; + Draw_Float(tempvalue / valueunit, selection - scrollpos, false, valueunit); + DWIN_UpdateLCD(); + if (active_menu == ZOffset && liveadjust) { + planner.synchronize(); + current_position.z += (tempvalue / valueunit - zoffsetvalue); + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + current_position.z = 0; + sync_plan_position(); + } + else if (active_menu == Tune && selection == TUNE_ZOFFSET) { + sprintf_P(cmd, PSTR("M290 Z%s"), dtostrf((tempvalue / valueunit - zoffsetvalue), 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + } + if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Ki) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Ki)) + tempvalue = scalePID_i(tempvalue); + if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Kd) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Kd)) + tempvalue = scalePID_d(tempvalue); + switch (valuetype) { + case 0: *(float*)valuepointer = tempvalue / valueunit; break; + case 1: *(uint8_t*)valuepointer = tempvalue / valueunit; break; + case 2: *(uint16_t*)valuepointer = tempvalue / valueunit; break; + case 3: *(int16_t*)valuepointer = tempvalue / valueunit; break; + case 4: *(uint32_t*)valuepointer = tempvalue / valueunit; break; + case 5: *(int8_t*)valuepointer = tempvalue / valueunit; break; + } + switch (active_menu) { + case Move: + planner.synchronize(); + planner.buffer_line(current_position, manual_feedrate_mm_s[selection - 1], active_extruder); + break; + #if HAS_MESH + case ManualMesh: + planner.synchronize(); + planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder); + planner.synchronize(); + break; + case UBLMesh: mesh_conf.manual_mesh_move(true); break; + case LevelManual: mesh_conf.manual_mesh_move(selection == LEVELING_M_OFFSET); break; + #endif + } + if (valuepointer == &planner.flow_percentage[0]) + planner.refresh_e_factor(0); + if (funcpointer) funcpointer(); + return; + } + NOLESS(tempvalue, (valuemin * valueunit)); + NOMORE(tempvalue, (valuemax * valueunit)); + Draw_Float(tempvalue / valueunit, selection - scrollpos, true, valueunit); + DWIN_UpdateLCD(); + if (active_menu == Move && livemove) { + *(float*)valuepointer = tempvalue / valueunit; + planner.buffer_line(current_position, manual_feedrate_mm_s[selection - 1], active_extruder); + } +} + +void CrealityDWINClass::Option_Control() { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW) + tempvalue += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + tempvalue -= EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + process = Menu; + EncoderRate.enabled = false; + if (valuepointer == &color_names) { + switch (selection) { + case COLORSETTINGS_CURSOR: eeprom_settings.cursor_color = tempvalue; break; + case COLORSETTINGS_SPLIT_LINE: eeprom_settings.menu_split_line = tempvalue; break; + case COLORSETTINGS_MENU_TOP_BG: eeprom_settings.menu_top_bg = tempvalue; break; + case COLORSETTINGS_MENU_TOP_TXT: eeprom_settings.menu_top_txt = tempvalue; break; + case COLORSETTINGS_HIGHLIGHT_BORDER: eeprom_settings.highlight_box = tempvalue; break; + case COLORSETTINGS_PROGRESS_PERCENT: eeprom_settings.progress_percent = tempvalue; break; + case COLORSETTINGS_PROGRESS_TIME: eeprom_settings.progress_time = tempvalue; break; + case COLORSETTINGS_PROGRESS_STATUS_BAR: eeprom_settings.status_bar_text = tempvalue; break; + case COLORSETTINGS_PROGRESS_STATUS_AREA: eeprom_settings.status_area_text = tempvalue; break; + case COLORSETTINGS_PROGRESS_COORDINATES: eeprom_settings.coordinates_text = tempvalue; break; + case COLORSETTINGS_PROGRESS_COORDINATES_LINE: eeprom_settings.coordinates_split_line = tempvalue; break; + } + Redraw_Screen(); + } + else if (valuepointer == &preheat_modes) + preheatmode = tempvalue; + + Draw_Option(tempvalue, static_cast(valuepointer), selection - scrollpos, false, (valuepointer == &color_names)); + DWIN_UpdateLCD(); + return; + } + NOLESS(tempvalue, valuemin); + NOMORE(tempvalue, valuemax); + Draw_Option(tempvalue, static_cast(valuepointer), selection - scrollpos, true); + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::File_Control() { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + static uint8_t filescrl = 0; + if (encoder_diffState == ENCODER_DIFF_NO) { + if (selection > 0) { + card.getfilename_sorted(SD_ORDER(selection - 1, card.get_num_Files())); + char * const filename = card.longest_filename(); + size_t len = strlen(filename); + int8_t pos = len; + if (!card.flag.filenameIsDir) + while (pos && filename[pos] != '.') pos--; + if (pos > MENU_CHAR_LIMIT) { + static millis_t time = 0; + if (PENDING(millis(), time)) return; + time = millis() + 200; + pos -= filescrl; + len = _MIN(pos, MENU_CHAR_LIMIT); + char name[len + 1]; + if (pos >= 0) { + LOOP_L_N(i, len) name[i] = filename[i + filescrl]; + } + else { + LOOP_L_N(i, MENU_CHAR_LIMIT + pos) name[i] = ' '; + LOOP_S_L_N(i, MENU_CHAR_LIMIT + pos, MENU_CHAR_LIMIT) name[i] = filename[i - (MENU_CHAR_LIMIT + pos)]; + } + name[len] = '\0'; + DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); + Draw_Menu_Item(selection - scrollpos, card.flag.filenameIsDir ? ICON_More : ICON_File, name); + if (-pos >= MENU_CHAR_LIMIT) filescrl = 0; + filescrl++; + DWIN_UpdateLCD(); + } + } + return; + } + if (encoder_diffState == ENCODER_DIFF_CW && selection < card.get_num_Files()) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + if (selection > 0) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); + Draw_SD_Item(selection, selection - scrollpos); + } + filescrl = 0; + selection++; // Select Down + if (selection > scrollpos + MROWS) { + scrollpos++; + DWIN_Frame_AreaMove(1, 2, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + Draw_SD_Item(selection, selection - scrollpos); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); + Draw_SD_Item(selection, selection - scrollpos); + filescrl = 0; + selection--; // Select Up + if (selection < scrollpos) { + scrollpos--; + DWIN_Frame_AreaMove(1, 3, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + Draw_SD_Item(selection, selection - scrollpos); + } + DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (selection == 0) { + if (card.flag.workDirIsRoot) { + process = Main; + Draw_Main_Menu(); + } + else { + card.cdup(); + Draw_SD_List(); + } + } + else { + card.getfilename_sorted(SD_ORDER(selection - 1, card.get_num_Files())); + if (card.flag.filenameIsDir) { + card.cd(card.filename); + Draw_SD_List(); + } + else { + card.openAndPrintFile(card.filename); + } + } + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Print_Screen_Control() { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW && selection < PRINT_COUNT - 1) { + selection++; // Select Down + Print_Screen_Icons(); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + selection--; // Select Up + Print_Screen_Icons(); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (selection) { + case PRINT_SETUP: + Draw_Menu(Tune); + Update_Status_Bar(true); + break; + case PRINT_PAUSE_RESUME: + if (paused) { + if (sdprint) { + wait_for_user = false; + #if ENABLED(PARK_HEAD_ON_PAUSE) + card.startOrResumeFilePrinting(); + TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); + #else + char cmd[20]; + #if HAS_HEATED_BED + sprintf_P(cmd, PSTR("M140 S%i"), pausebed); + gcode.process_subcommands_now(cmd); + #endif + #if HAS_EXTRUDERS + sprintf_P(cmd, PSTR("M109 S%i"), pausetemp); + gcode.process_subcommands_now(cmd); + #endif + TERN_(HAS_FAN, thermalManager.fan_speed[0] = pausefan); + planner.synchronize(); + TERN_(SDSUPPORT, queue.inject(F("M24"))); + #endif + } + else { + TERN_(HOST_ACTION_COMMANDS, hostui.resume()); + } + Draw_Print_Screen(); + } + else + Popup_Handler(Pause); + break; + case PRINT_STOP: Popup_Handler(Stop); break; + } + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Popup_Control() { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_CW && selection < 1) { + selection++; + Popup_Select(); + } + else if (encoder_diffState == ENCODER_DIFF_CCW && selection > 0) { + selection--; + Popup_Select(); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (popup) { + case Pause: + if (selection == 0) { + if (sdprint) { + #if ENABLED(POWER_LOSS_RECOVERY) + if (recovery.enabled) recovery.save(true); + #endif + #if ENABLED(PARK_HEAD_ON_PAUSE) + Popup_Handler(Home, true); + #if ENABLED(SDSUPPORT) + if (IS_SD_PRINTING()) card.pauseSDPrint(); + #endif + planner.synchronize(); + queue.inject(F("M125")); + planner.synchronize(); + #else + queue.inject(F("M25")); + TERN_(HAS_HOTEND, pausetemp = thermalManager.temp_hotend[0].target); + TERN_(HAS_HEATED_BED, pausebed = thermalManager.temp_bed.target); + TERN_(HAS_FAN, pausefan = thermalManager.fan_speed[0]); + thermalManager.cooldown(); + #endif + } + else { + TERN_(HOST_ACTION_COMMANDS, hostui.pause()); + } + } + Draw_Print_Screen(); + break; + case Stop: + if (selection == 0) { + if (sdprint) { + ui.abort_print(); + thermalManager.cooldown(); + } + else { + TERN_(HOST_ACTION_COMMANDS, hostui.cancel()); + } + } + else + Draw_Print_Screen(); + break; + case Resume: + if (selection == 0) + queue.inject(F("M1000")); + else { + queue.inject(F("M1000 C")); + Draw_Main_Menu(); + } + break; + + #if HAS_HOTEND + case ETemp: + if (selection == 0) { + thermalManager.setTargetHotend(EXTRUDE_MINTEMP, 0); + thermalManager.set_fan_speed(0, MAX_FAN_SPEED); + Draw_Menu(PreheatHotend); + } + else + Redraw_Menu(true, true, false); + break; + #endif + + #if HAS_BED_PROBE + case ManualProbing: + if (selection == 0) { + char buf[80]; + const float dif = probe.probe_at_point(current_position.x, current_position.y, PROBE_PT_STOW, 0, false) - corner_avg; + sprintf_P(buf, dif > 0 ? PSTR("Corner is %smm high") : PSTR("Corner is %smm low"), dtostrf(abs(dif), 1, 3, str_1)); + Update_Status(buf); + } + else { + Redraw_Menu(true, true, false); + Update_Status(""); + } + break; + #endif + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + case ConfFilChange: + if (selection == 0) { + if (thermalManager.temp_hotend[0].target < thermalManager.extrude_min_temp) + Popup_Handler(ETemp); + else { + if (thermalManager.temp_hotend[0].is_below_target(-2)) { + Popup_Handler(Heating); + thermalManager.wait_for_hotend(0); + } + Popup_Handler(FilChange); + sprintf_P(cmd, PSTR("M600 B1 R%i"), thermalManager.temp_hotend[0].target); + gcode.process_subcommands_now(cmd); + } + } + else + Redraw_Menu(true, true, false); + break; + case PurgeMore: + if (selection == 0) { + pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; + Popup_Handler(FilChange); + } + else { + pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; + if (printing) Popup_Handler(Resuming); + else Redraw_Menu(true, true, (active_menu==PreheatHotend)); + } + break; + #endif // ADVANCED_PAUSE_FEATURE + + #if HAS_MESH + case SaveLevel: + if (selection == 0) { + #if ENABLED(AUTO_BED_LEVELING_UBL) + gcode.process_subcommands_now(F("G29 S")); + planner.synchronize(); + AudioFeedback(true); + #else + AudioFeedback(settings.save()); + #endif + } + Draw_Menu(Leveling, LEVELING_GET_MESH); + break; + #endif + + #if ENABLED(AUTO_BED_LEVELING_UBL) + case MeshSlot: + if (selection == 0) bedlevel.storage_slot = 0; + Redraw_Menu(true, true); + break; + #endif + default: break; + } + } + DWIN_UpdateLCD(); +} + +void CrealityDWINClass::Confirm_Control() { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (popup) { + case Complete: + Draw_Main_Menu(); + break; + case FilInsert: + Popup_Handler(FilChange); + wait_for_user = false; + break; + case HeaterTime: + Popup_Handler(Heating); + wait_for_user = false; + break; + default: + Redraw_Menu(true, true, false); + wait_for_user = false; + break; + } + } + DWIN_UpdateLCD(); +} + +/* In-Menu Value Modification */ + +void CrealityDWINClass::Setup_Value(float value, float min, float max, float unit, uint8_t type) { + if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Ki) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Ki)) + tempvalue = unscalePID_i(value) * unit; + else if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Kd) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Kd)) + tempvalue = unscalePID_d(value) * unit; + else + tempvalue = value * unit; + valuemin = min; + valuemax = max; + valueunit = unit; + valuetype = type; + process = Value; + EncoderRate.enabled = true; + Draw_Float(tempvalue / unit, selection - scrollpos, true, valueunit); +} + +void CrealityDWINClass::Modify_Value(float &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 0); +} +void CrealityDWINClass::Modify_Value(uint8_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 1); +} +void CrealityDWINClass::Modify_Value(uint16_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 2); +} +void CrealityDWINClass::Modify_Value(int16_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 3); +} +void CrealityDWINClass::Modify_Value(uint32_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 4); +} +void CrealityDWINClass::Modify_Value(int8_t &value, float min, float max, float unit, void (*f)()/*=nullptr*/) { + valuepointer = &value; + funcpointer = f; + Setup_Value((float)value, min, max, unit, 5); +} + +void CrealityDWINClass::Modify_Option(uint8_t value, const char * const * options, uint8_t max) { + tempvalue = value; + valuepointer = const_cast(options); + valuemin = 0; + valuemax = max; + process = Option; + EncoderRate.enabled = true; + Draw_Option(value, options, selection - scrollpos, true); +} + +/* Main Functions */ + +void CrealityDWINClass::Update_Status(const char * const text) { + if (strncmp_P(text, PSTR(""), 3) == 0) { + LOOP_L_N(i, _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text))) filename[i] = text[i + 3]; + filename[_MIN((size_t)LONG_FILENAME_LENGTH - 1, strlen(text))] = '\0'; + Draw_Print_Filename(true); + } + else { + LOOP_L_N(i, _MIN((size_t)64, strlen(text))) statusmsg[i] = text[i]; + statusmsg[_MIN((size_t)64, strlen(text))] = '\0'; + } +} + +void CrealityDWINClass::Start_Print(bool sd) { + sdprint = sd; + if (!printing) { + printing = true; + statusmsg[0] = '\0'; + if (sd) { + #if ENABLED(POWER_LOSS_RECOVERY) + if (recovery.valid()) { + SdFile *diveDir = nullptr; + const char * const fname = card.diveToFile(true, diveDir, recovery.info.sd_filename); + card.selectFileByName(fname); + } + #endif + strcpy(filename, card.longest_filename()); + } + else + strcpy_P(filename, PSTR("Host Print")); + TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress(0)); + TERN_(USE_M73_REMAINING_TIME, ui.set_remaining_time(0)); + Draw_Print_Screen(); + } +} + +void CrealityDWINClass::Stop_Print() { + printing = false; + sdprint = false; + thermalManager.cooldown(); + TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress(100 * (PROGRESS_SCALE))); + TERN_(USE_M73_REMAINING_TIME, ui.set_remaining_time(0)); + Draw_Print_confirm(); +} + +void CrealityDWINClass::Update() { + State_Update(); + Screen_Update(); + switch (process) { + case Main: Main_Menu_Control(); break; + case Menu: Menu_Control(); break; + case Value: Value_Control(); break; + case Option: Option_Control(); break; + case File: File_Control(); break; + case Print: Print_Screen_Control(); break; + case Popup: Popup_Control(); break; + case Confirm: Confirm_Control(); break; + } +} + +void MarlinUI::update() { CrealityDWIN.Update(); } + +#if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { DWIN_LCD_Brightness(backlight ? brightness : 0); } +#endif + +void CrealityDWINClass::State_Update() { + if ((print_job_timer.isRunning() || print_job_timer.isPaused()) != printing) { + if (!printing) Start_Print(card.isFileOpen() || TERN0(POWER_LOSS_RECOVERY, recovery.valid())); + else Stop_Print(); + } + if (print_job_timer.isPaused() != paused) { + paused = print_job_timer.isPaused(); + if (process == Print) Print_Screen_Icons(); + if (process == Wait && !paused) Redraw_Menu(true, true); + } + if (wait_for_user && !(process == Confirm) && !print_job_timer.isPaused()) + Confirm_Handler(UserInput); + #if ENABLED(ADVANCED_PAUSE_FEATURE) + if (process == Popup && popup == PurgeMore) { + if (pause_menu_response == PAUSE_RESPONSE_EXTRUDE_MORE) + Popup_Handler(FilChange); + else if (pause_menu_response == PAUSE_RESPONSE_RESUME_PRINT) { + if (printing) Popup_Handler(Resuming); + else Redraw_Menu(true, true, (active_menu==PreheatHotend)); + } + } + #endif + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + static bool ranout = false; + if (runout.filament_ran_out != ranout) { + ranout = runout.filament_ran_out; + if (ranout) Popup_Handler(Runout); + } + #endif +} + +void CrealityDWINClass::Screen_Update() { + const millis_t ms = millis(); + static millis_t scrltime = 0; + if (ELAPSED(ms, scrltime)) { + scrltime = ms + 200; + Update_Status_Bar(); + if (process == Print) Draw_Print_Filename(); + } + + static millis_t statustime = 0; + if (ELAPSED(ms, statustime)) { + statustime = ms + 500; + Draw_Status_Area(); + } + + static millis_t printtime = 0; + if (ELAPSED(ms, printtime)) { + printtime = ms + 1000; + if (process == Print) { + Draw_Print_ProgressBar(); + Draw_Print_ProgressElapsed(); + TERN_(USE_M73_REMAINING_TIME, Draw_Print_ProgressRemain()); + } + } + + static bool mounted = card.isMounted(); + if (mounted != card.isMounted()) { + mounted = card.isMounted(); + if (process == File) + Draw_SD_List(); + } + + #if HAS_HOTEND + static int16_t hotendtarget = -1; + #endif + #if HAS_HEATED_BED + static int16_t bedtarget = -1; + #endif + #if HAS_FAN + static int16_t fanspeed = -1; + #endif + + #if HAS_ZOFFSET_ITEM + static float lastzoffset = zoffsetvalue; + if (zoffsetvalue != lastzoffset) { + lastzoffset = zoffsetvalue; + #if HAS_BED_PROBE + probe.offset.z = zoffsetvalue; + #else + set_home_offset(Z_AXIS, -zoffsetvalue); + #endif + } + + #if HAS_BED_PROBE + if (probe.offset.z != lastzoffset) + zoffsetvalue = lastzoffset = probe.offset.z; + #else + if (-home_offset.z != lastzoffset) + zoffsetvalue = lastzoffset = -home_offset.z; + #endif + #endif // HAS_ZOFFSET_ITEM + + if (process == Menu || process == Value) { + switch (active_menu) { + case TempMenu: + #if HAS_HOTEND + if (thermalManager.temp_hotend[0].target != hotendtarget) { + hotendtarget = thermalManager.temp_hotend[0].target; + if (scrollpos <= TEMP_HOTEND && TEMP_HOTEND <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.temp_hotend[0].target, TEMP_HOTEND - scrollpos, false, 1); + } + } + #endif + #if HAS_HEATED_BED + if (thermalManager.temp_bed.target != bedtarget) { + bedtarget = thermalManager.temp_bed.target; + if (scrollpos <= TEMP_BED && TEMP_BED <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.temp_bed.target, TEMP_BED - scrollpos, false, 1); + } + } + #endif + #if HAS_FAN + if (thermalManager.fan_speed[0] != fanspeed) { + fanspeed = thermalManager.fan_speed[0]; + if (scrollpos <= TEMP_FAN && TEMP_FAN <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.fan_speed[0], TEMP_FAN - scrollpos, false, 1); + } + } + #endif + break; + case Tune: + #if HAS_HOTEND + if (thermalManager.temp_hotend[0].target != hotendtarget) { + hotendtarget = thermalManager.temp_hotend[0].target; + if (scrollpos <= TUNE_HOTEND && TUNE_HOTEND <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.temp_hotend[0].target, TUNE_HOTEND - scrollpos, false, 1); + } + } + #endif + #if HAS_HEATED_BED + if (thermalManager.temp_bed.target != bedtarget) { + bedtarget = thermalManager.temp_bed.target; + if (scrollpos <= TUNE_BED && TUNE_BED <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.temp_bed.target, TUNE_BED - scrollpos, false, 1); + } + } + #endif + #if HAS_FAN + if (thermalManager.fan_speed[0] != fanspeed) { + fanspeed = thermalManager.fan_speed[0]; + if (scrollpos <= TUNE_FAN && TUNE_FAN <= scrollpos + MROWS) { + if (process != Value || selection != TEMP_HOTEND - scrollpos) + Draw_Float(thermalManager.fan_speed[0], TUNE_FAN - scrollpos, false, 1); + } + } + #endif + break; + } + } +} + +void CrealityDWINClass::AudioFeedback(const bool success/*=true*/) { + if (ui.sound_on) + DONE_BUZZ(success); + else + Update_Status(success ? "Success" : "Failed"); +} + +void CrealityDWINClass::Save_Settings(char *buff) { + TERN_(AUTO_BED_LEVELING_UBL, eeprom_settings.tilt_grid_size = mesh_conf.tilt_grid - 1); + eeprom_settings.corner_pos = corner_pos * 10; + memcpy(buff, &eeprom_settings, _MIN(sizeof(eeprom_settings), eeprom_data_size)); +} + +void CrealityDWINClass::Load_Settings(const char *buff) { + memcpy(&eeprom_settings, buff, _MIN(sizeof(eeprom_settings), eeprom_data_size)); + TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); + if (eeprom_settings.corner_pos == 0) eeprom_settings.corner_pos = 325; + corner_pos = eeprom_settings.corner_pos / 10.0f; + Redraw_Screen(); + #if ENABLED(POWER_LOSS_RECOVERY) + static bool init = true; + if (init) { + init = false; + queue.inject(F("M1000 S")); + } + #endif +} + +void CrealityDWINClass::Reset_Settings() { + eeprom_settings.time_format_textual = false; + TERN_(AUTO_BED_LEVELING_UBL, eeprom_settings.tilt_grid_size = 0); + eeprom_settings.corner_pos = 325; + eeprom_settings.cursor_color = 0; + eeprom_settings.menu_split_line = 0; + eeprom_settings.menu_top_bg = 0; + eeprom_settings.menu_top_txt = 0; + eeprom_settings.highlight_box = 0; + eeprom_settings.progress_percent = 0; + eeprom_settings.progress_time = 0; + eeprom_settings.status_bar_text = 0; + eeprom_settings.status_area_text = 0; + eeprom_settings.coordinates_text = 0; + eeprom_settings.coordinates_split_line = 0; + TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); + corner_pos = eeprom_settings.corner_pos / 10.0f; + TERN_(SOUND_MENU_ITEM, ui.sound_on = ENABLED(SOUND_ON_DEFAULT)); + Redraw_Screen(); +} + +void MarlinUI::init_lcd() { + delay(800); + SERIAL_ECHOPGM("\nDWIN handshake "); + if (DWIN_Handshake()) SERIAL_ECHOLNPGM("ok."); else SERIAL_ECHOLNPGM("error."); + DWIN_Frame_SetDir(1); // Orientation 90° + DWIN_UpdateLCD(); // Show bootscreen (first image) + Encoder_Configuration(); + for (uint16_t t = 0; t <= 100; t += 2) { + DWIN_ICON_Show(ICON, ICON_Bar, 15, 260); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 15 + t * 242 / 100, 260, 257, 280); + DWIN_UpdateLCD(); + delay(20); + } + + DWIN_JPG_ShowAndCache(3); + DWIN_JPG_CacheTo1(Language_English); + CrealityDWIN.Redraw_Screen(); +} + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + void MarlinUI::pause_show_message(const PauseMessage message, const PauseMode mode/*=PAUSE_MODE_SAME*/, const uint8_t extruder/*=active_extruder*/) { + switch (message) { + case PAUSE_MESSAGE_INSERT: CrealityDWIN.Confirm_Handler(FilInsert); break; + case PAUSE_MESSAGE_PURGE: + case PAUSE_MESSAGE_OPTION: CrealityDWIN.Popup_Handler(PurgeMore); break; + case PAUSE_MESSAGE_HEAT: CrealityDWIN.Confirm_Handler(HeaterTime); break; + case PAUSE_MESSAGE_WAITING: CrealityDWIN.Draw_Print_Screen(); break; + default: break; + } + } +#endif + +#endif // DWIN_CREALITY_LCD_JYERSUI diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h new file mode 100644 index 0000000000..8985647cd1 --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.h @@ -0,0 +1,245 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ +#pragma once + +/** + * lcd/e3v2/jyersui/dwin.h + */ + +#include "dwin_lcd.h" +#include "../common/dwin_set.h" +#include "../common/dwin_font.h" +#include "../common/dwin_color.h" +#include "../common/encoder.h" +#include "../../../libs/BL24CXX.h" + +#include "../../../inc/MarlinConfigPre.h" + +//#define DWIN_CREALITY_LCD_CUSTOM_ICONS + +enum processID : uint8_t { + Main, Print, Menu, Value, Option, File, Popup, Confirm, Wait +}; + +enum PopupID : uint8_t { + Pause, Stop, Resume, SaveLevel, ETemp, ConfFilChange, PurgeMore, MeshSlot, + Level, Home, MoveWait, Heating, FilLoad, FilChange, TempWarn, Runout, PIDWait, Resuming, ManualProbing, + FilInsert, HeaterTime, UserInput, LevelError, InvalidMesh, UI, Complete, Custom +}; + +enum menuID : uint8_t { + MainMenu, + Prepare, + Move, + HomeMenu, + ManualLevel, + ZOffset, + Preheat, + ChangeFilament, + MenuCustom, + Control, + TempMenu, + PID, + HotendPID, + BedPID, + #if HAS_PREHEAT + #define _PREHEAT_ID(N) Preheat##N, + REPEAT_1(PREHEAT_COUNT, _PREHEAT_ID) + #endif + Motion, + HomeOffsets, + MaxSpeed, + MaxAcceleration, + MaxJerk, + Steps, + Visual, + ColorSettings, + Advanced, + ProbeMenu, + Info, + Leveling, + LevelManual, + LevelView, + MeshViewer, + LevelSettings, + ManualMesh, + UBLMesh, + InfoMain, + Tune, + PreheatHotend +}; + +// Custom icons +#if ENABLED(DWIN_CREALITY_LCD_CUSTOM_ICONS) + // index of every custom icon should be >= CUSTOM_ICON_START + #define CUSTOM_ICON_START ICON_Checkbox_F + #define ICON_Checkbox_F 200 + #define ICON_Checkbox_T 201 + #define ICON_Fade 202 + #define ICON_Mesh 203 + #define ICON_Tilt 204 + #define ICON_Brightness 205 + #define ICON_AxisD 249 + #define ICON_AxisBR 250 + #define ICON_AxisTR 251 + #define ICON_AxisBL 252 + #define ICON_AxisTL 253 + #define ICON_AxisC 254 +#else + #define ICON_Fade ICON_Version + #define ICON_Mesh ICON_Version + #define ICON_Tilt ICON_Version + #define ICON_Brightness ICON_Version + #define ICON_AxisD ICON_Axis + #define ICON_AxisBR ICON_Axis + #define ICON_AxisTR ICON_Axis + #define ICON_AxisBL ICON_Axis + #define ICON_AxisTL ICON_Axis + #define ICON_AxisC ICON_Axis +#endif + +enum colorID : uint8_t { + Default, White, Green, Cyan, Blue, Magenta, Red, Orange, Yellow, Brown, Black +}; + +#define Custom_Colors 10 +#define Color_Aqua RGB(0x00,0x3F,0x1F) +#define Color_Light_White 0xBDD7 +#define Color_Green RGB(0x00,0x3F,0x00) +#define Color_Light_Green 0x3460 +#define Color_Cyan 0x07FF +#define Color_Light_Cyan 0x04F3 +#define Color_Blue 0x015F +#define Color_Light_Blue 0x3A6A +#define Color_Magenta 0xF81F +#define Color_Light_Magenta 0x9813 +#define Color_Light_Red 0x8800 +#define Color_Orange 0xFA20 +#define Color_Light_Orange 0xFBC0 +#define Color_Light_Yellow 0x8BE0 +#define Color_Brown 0xCC27 +#define Color_Light_Brown 0x6204 +#define Color_Black 0x0000 +#define Color_Grey 0x18E3 +#define Check_Color 0x4E5C // Check-box check color +#define Confirm_Color 0x34B9 +#define Cancel_Color 0x3186 + +class CrealityDWINClass { +public: + static constexpr size_t eeprom_data_size = 48; + static struct EEPROM_Settings { // use bit fields to save space, max 48 bytes + bool time_format_textual : 1; + #if ENABLED(AUTO_BED_LEVELING_UBL) + uint8_t tilt_grid_size : 3; + #endif + uint16_t corner_pos : 10; + uint8_t cursor_color : 4; + uint8_t menu_split_line : 4; + uint8_t menu_top_bg : 4; + uint8_t menu_top_txt : 4; + uint8_t highlight_box : 4; + uint8_t progress_percent : 4; + uint8_t progress_time : 4; + uint8_t status_bar_text : 4; + uint8_t status_area_text : 4; + uint8_t coordinates_text : 4; + uint8_t coordinates_split_line : 4; + } eeprom_settings; + + static constexpr const char * const color_names[11] = { "Default", "White", "Green", "Cyan", "Blue", "Magenta", "Red", "Orange", "Yellow", "Brown", "Black" }; + static constexpr const char * const preheat_modes[3] = { "Both", "Hotend", "Bed" }; + + static void Clear_Screen(uint8_t e=3); + static void Draw_Float(float value, uint8_t row, bool selected=false, uint8_t minunit=10); + static void Draw_Option(uint8_t value, const char * const * options, uint8_t row, bool selected=false, bool color=false); + static uint16_t GetColor(uint8_t color, uint16_t original, bool light=false); + static void Draw_Checkbox(uint8_t row, bool value); + static void Draw_Title(const char * title); + static void Draw_Title(FSTR_P const title); + static void Draw_Menu_Item(uint8_t row, uint8_t icon=0, const char * const label1=nullptr, const char * const label2=nullptr, bool more=false, bool centered=false); + static void Draw_Menu_Item(uint8_t row, uint8_t icon=0, FSTR_P const flabel1=nullptr, FSTR_P const flabel2=nullptr, bool more=false, bool centered=false); + static void Draw_Menu(uint8_t menu, uint8_t select=0, uint8_t scroll=0); + static void Redraw_Menu(bool lastprocess=true, bool lastselection=false, bool lastmenu=false); + static void Redraw_Screen(); + + static void Main_Menu_Icons(); + static void Draw_Main_Menu(uint8_t select=0); + static void Print_Screen_Icons(); + static void Draw_Print_Screen(); + static void Draw_Print_Filename(const bool reset=false); + static void Draw_Print_ProgressBar(); + #if ENABLED(USE_M73_REMAINING_TIME) + static void Draw_Print_ProgressRemain(); + #endif + static void Draw_Print_ProgressElapsed(); + static void Draw_Print_confirm(); + static void Draw_SD_Item(uint8_t item, uint8_t row); + static void Draw_SD_List(bool removed=false); + static void Draw_Status_Area(bool icons=false); + static void Draw_Popup(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, uint8_t mode, uint8_t icon=0); + static void Popup_Select(); + static void Update_Status_Bar(bool refresh=false); + + #if ENABLED(AUTO_BED_LEVELING_UBL) + static void Draw_Bed_Mesh(int16_t selected = -1, uint8_t gridline_width = 1, uint16_t padding_x = 8, uint16_t padding_y_top = 40 + 53 - 7); + static void Set_Mesh_Viewer_Status(); + #endif + + static FSTR_P Get_Menu_Title(uint8_t menu); + static uint8_t Get_Menu_Size(uint8_t menu); + static void Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw=true); + + static void Popup_Handler(PopupID popupid, bool option = false); + static void Confirm_Handler(PopupID popupid); + + static void Main_Menu_Control(); + static void Menu_Control(); + static void Value_Control(); + static void Option_Control(); + static void File_Control(); + static void Print_Screen_Control(); + static void Popup_Control(); + static void Confirm_Control(); + + static void Setup_Value(float value, float min, float max, float unit, uint8_t type); + static void Modify_Value(float &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(uint8_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(uint16_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(int16_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(uint32_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Value(int8_t &value, float min, float max, float unit, void (*f)()=nullptr); + static void Modify_Option(uint8_t value, const char * const * options, uint8_t max); + + static void Update_Status(const char * const text); + static void Start_Print(bool sd); + static void Stop_Print(); + static void Update(); + static void State_Update(); + static void Screen_Update(); + static void AudioFeedback(const bool success=true); + static void Save_Settings(char *buff); + static void Load_Settings(const char *buff); + static void Reset_Settings(); +}; + +extern CrealityDWINClass CrealityDWIN; diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp new file mode 100644 index 0000000000..04889e92b0 --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp @@ -0,0 +1,64 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +/******************************************************************************** + * @file lcd/e3v2/jyersui/dwin_lcd.cpp + * @brief DWIN screen control functions + ********************************************************************************/ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + +#include "dwin_lcd.h" + +/*-------------------------------------- System variable function --------------------------------------*/ + +void DWIN_Startup() {} + +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Draw the degree (°) symbol +// Color: color +// x/y: Upper-left coordinate of the first pixel +void DWIN_Draw_DegreeSymbol(uint16_t Color, uint16_t x, uint16_t y) { + DWIN_Draw_Point(Color, 1, 1, x + 1, y); + DWIN_Draw_Point(Color, 1, 1, x + 2, y); + DWIN_Draw_Point(Color, 1, 1, x, y + 1); + DWIN_Draw_Point(Color, 1, 1, x + 3, y + 1); + DWIN_Draw_Point(Color, 1, 1, x, y + 2); + DWIN_Draw_Point(Color, 1, 1, x + 3, y + 2); + DWIN_Draw_Point(Color, 1, 1, x + 1, y + 3); + DWIN_Draw_Point(Color, 1, 1, x + 2, y + 3); +} + +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point +void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { + DWIN_ICON_Show(true, false, false, libID, picID, x, y); +} + +#endif // DWIN_CREALITY_LCD_JYERSUI diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h new file mode 100644 index 0000000000..f76cfb5d3e --- /dev/null +++ b/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h @@ -0,0 +1,34 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ +#pragma once + +/******************************************************************************** + * @file lcd/e3v2/jyersui/dwin_lcd.h + * @brief DWIN screen control functions + ********************************************************************************/ + +#include "../common/dwin_api.h" + +// Draw the degree (°) symbol +// Color: color +// x/y: Upper-left coordinate of the first pixel +void DWIN_Draw_DegreeSymbol(uint16_t Color, uint16_t x, uint16_t y); diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 933f6a568e..8455518767 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -199,7 +199,7 @@ namespace ExtUI { #endif inline void simulateUserClick() { - #if EITHER(HAS_MARLINUI_MENU, EXTENSIBLE_UI) + #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) ui.lcd_clicked = true; #endif } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 5b17b0b975..e03e80ed3c 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -49,6 +49,8 @@ MarlinUI ui; #include "e3v2/creality/dwin.h" #elif ENABLED(DWIN_LCD_PROUI) #include "e3v2/proui/dwin.h" +#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #include "e3v2/jyersui/dwin.h" #endif #if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL @@ -151,7 +153,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; bool MarlinUI::lcd_clicked; #endif -#if HAS_WIRED_LCD +#if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) bool MarlinUI::get_blink() { static uint8_t blink = 0; @@ -1566,6 +1568,7 @@ void MarlinUI::init() { TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); TERN_(DWIN_CREALITY_LCD, DWIN_StatusChanged(status_message)); TERN_(DWIN_LCD_PROUI, DWIN_CheckStatusMessage()); + TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Update_Status(status_message)); } #if ENABLED(STATUS_MESSAGE_SCROLLING) diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index a4166c4100..6bd9ec8737 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -83,10 +83,12 @@ typedef bool (*statusResetFunc_t)(); #endif // HAS_MARLINUI_MENU - #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_BUTTONS, 50, 100) - #endif // HAS_WIRED_LCD +#if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) + #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_BUTTONS, 50, 100) +#endif + #if HAS_MARLINUI_U8GLIB enum MarlinFont : uint8_t { FONT_STATUSMENU = 1, @@ -389,7 +391,7 @@ public: static void poweroff(); #endif - #if HAS_WIRED_LCD + #if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) static bool get_blink(); #endif @@ -626,7 +628,7 @@ public: static bool use_click() { return false; } #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI) + #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else static void _pause_show_message() {} diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index a37dfc0257..b40690e22c 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -77,6 +77,8 @@ #elif ENABLED(DWIN_LCD_PROUI) #include "../lcd/e3v2/proui/dwin.h" #include "../lcd/e3v2/proui/bedlevel_tools.h" +#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #include "../lcd/e3v2/jyersui/dwin.h" #endif #if ENABLED(HOST_PROMPT_SUPPORT) @@ -501,6 +503,8 @@ typedef struct SettingsDataStruct { // #if ENABLED(DWIN_LCD_PROUI) uint8_t dwin_data[eeprom_data_size]; + #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + uint8_t dwin_settings[CrealityDWIN.eeprom_data_size]; #endif // @@ -1519,6 +1523,15 @@ void MarlinSettings::postprocess() { } #endif + #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) + { + _FIELD_TEST(dwin_settings); + char dwin_settings[CrealityDWIN.eeprom_data_size] = { 0 }; + CrealityDWIN.Save_Settings(dwin_settings); + EEPROM_WRITE(dwin_settings); + } + #endif + // // Case Light Brightness // @@ -2483,6 +2496,13 @@ void MarlinSettings::postprocess() { EEPROM_READ(dwin_data); if (!validating) DWIN_CopySettingsFrom(dwin_data); } + #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + { + const char dwin_settings[CrealityDWIN.eeprom_data_size] = { 0 }; + _FIELD_TEST(dwin_settings); + EEPROM_READ(dwin_settings); + if (!validating) CrealityDWIN.Load_Settings(dwin_settings); + } #endif // @@ -2920,6 +2940,8 @@ void MarlinSettings::reset() { #endif #endif + TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Reset_Settings()); + // // Case Light Brightness // diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index bf16345449..f1478bc2c4 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -13,6 +13,11 @@ use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING BLTOUCH AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING exec_test $1 $2 "Ender 3 v2 with CrealityUI" "$3" +use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" +opt_disable DWIN_CREALITY_LCD +opt_enable DWIN_CREALITY_LCD_JYERSUI AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY +exec_test $1 $2 "Ender 3 v2 with JyersUI" "$3" + use_example_configs "Creality/Ender-3 S1/STM32F1" opt_disable DWIN_CREALITY_LCD Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN AUTO_BED_LEVELING_BILINEAR CONFIGURATION_EMBEDDING CANCEL_OBJECTS FWRETRACT opt_enable DWIN_LCD_PROUI INDIVIDUAL_AXIS_HOMING_SUBMENU LCD_SET_PROGRESS_MANUALLY STATUS_MESSAGE_SCROLLING \ diff --git a/ini/features.ini b/ini/features.ini index a763213299..ee065cb9b9 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -47,6 +47,7 @@ SPI_EEPROM = src_filter=+ DWIN_CREALITY_LCD = src_filter=+ DWIN_LCD_PROUI = src_filter=+ +DWIN_CREALITY_LCD_JYERSUI = src_filter=+ IS_DWIN_MARLINUI = src_filter=+ HAS_GRAPHICAL_TFT = src_filter=+ IS_TFTGLCD_PANEL = src_filter=+ From 0ca76bf9ed4a5386b49943bd9c9bbf9951db4ff8 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 25 Jul 2022 11:47:07 -0700 Subject: [PATCH 20/54] =?UTF-8?q?=F0=9F=93=9D=20Update=20MPCTEMP=20G-Code?= =?UTF-8?q?=20M306=20T=20(#24535)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit M306 simply reports current values. M306 T starts autotune process. --- Marlin/Configuration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 233da942a7..2f34ebb7e8 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -653,7 +653,7 @@ * * Use a physical model of the hotend to control temperature. When configured correctly * this gives better responsiveness and stability than PID and it also removes the need - * for PID_EXTRUSION_SCALING and PID_FAN_SCALING. Use M306 to autotune the model. + * for PID_EXTRUSION_SCALING and PID_FAN_SCALING. Use M306 T to autotune the model. */ #if ENABLED(MPCTEMP) //#define MPC_EDIT_MENU // Add MPC editing to the "Advanced Settings" menu. (~1300 bytes of flash) From 66369f8236c843bc933d42fc84d057bbbfe876e9 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 25 Jul 2022 11:48:59 -0700 Subject: [PATCH 21/54] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20JyersUI=20include=20?= =?UTF-8?q?(#24540)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/probe/G30.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index 01e8a51f35..e474ffe9d6 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -37,7 +37,7 @@ #include "../../module/tool_change.h" #endif -#if ENABLED(DWIN_LCD_PROUI) +#if EITHER(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) #include "../../lcd/marlinui.h" #endif From 1e9232723d71ea6383969151809af3df9aea3571 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 25 Jul 2022 12:02:37 -0700 Subject: [PATCH 22/54] =?UTF-8?q?=F0=9F=93=BA=20Fix=20TFT=20Classic=20UI?= =?UTF-8?q?=20non-Touchscreen=201024x600=20(#24541)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 9 +++++++-- Marlin/src/inc/SanityCheck.h | 4 ++-- Marlin/src/lcd/tft/ui_1024x600.cpp | 2 +- Marlin/src/lcd/tft/ui_320x240.cpp | 2 +- Marlin/src/lcd/tft/ui_480x320.cpp | 2 +- 5 files changed, 12 insertions(+), 7 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 95deed7b3f..0873c1f525 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1469,8 +1469,13 @@ #elif ENABLED(TFT_RES_1024x600) #define TFT_WIDTH 1024 #define TFT_HEIGHT 600 - #define GRAPHICAL_TFT_UPSCALE 6 - #define TFT_PIXEL_OFFSET_X 120 + #if ENABLED(TOUCH_SCREEN) + #define GRAPHICAL_TFT_UPSCALE 6 + #define TFT_PIXEL_OFFSET_X 120 + #else + #define GRAPHICAL_TFT_UPSCALE 8 + #define TFT_PIXEL_OFFSET_X 0 + #endif #endif // FSMC/SPI TFT Panels using standard HAL/tft/tft_(fsmc|spi|ltdc).h diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ef9f3cfead..5286b9e61c 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2971,8 +2971,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif -#if defined(GRAPHICAL_TFT_UPSCALE) && !WITHIN(GRAPHICAL_TFT_UPSCALE, 2, 6) - #error "GRAPHICAL_TFT_UPSCALE must be between 2 and 6." +#if defined(GRAPHICAL_TFT_UPSCALE) && !WITHIN(GRAPHICAL_TFT_UPSCALE, 2, 8) + #error "GRAPHICAL_TFT_UPSCALE must be between 2 and 8." #endif #if BOTH(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW) diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index ad9f811181..2cce95c8df 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -791,7 +791,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } } #endif -#if HAS_BED_PROBE +#if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) static void z_select() { motionAxisState.z_selection *= -1; quick_feedback(); diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 56887478f0..19cc4590aa 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -771,7 +771,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } } #endif -#if HAS_BED_PROBE +#if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) static void z_select() { motionAxisState.z_selection *= -1; quick_feedback(); diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index d4a04d6900..04a121a0e0 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -772,7 +772,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } } #endif -#if HAS_BED_PROBE +#if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) static void z_select() { motionAxisState.z_selection *= -1; quick_feedback(); From a24b9e16ff372a7b777fd72aad8c3d567ca07018 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 24 Jul 2022 13:51:43 -0500 Subject: [PATCH 23/54] =?UTF-8?q?=F0=9F=8E=A8=20PIO=20scripts=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../ftdi_eve_lib/scripts/svg2cpp.py | 18 +++---- .../PlatformIO/scripts/common-dependencies.py | 6 +-- .../share/PlatformIO/scripts/signature.py | 53 ++++++++++--------- 3 files changed, 41 insertions(+), 36 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py index cfc2625453..f6e4a3e39a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py @@ -112,10 +112,10 @@ class ComputeBoundingBox: if s: m = re.search('viewBox="([0-9-.]+) ([0-9-.]+) ([0-9-.]+) ([0-9-.]+)"', svg) if m: - self.x_min = float(m.group(1)) - self.y_min = float(m.group(2)) - self.x_max = float(m.group(3)) - self.y_max = float(m.group(4)) + self.x_min = float(m[1]) + self.y_min = float(m[2]) + self.x_max = float(m[3]) + self.y_max = float(m[4]) return True return False @@ -205,18 +205,18 @@ class Parser: pass # Just eat the spaces elif self.eat_token('([LMHVZlmhvz])'): - cmd = self.m.group(1) + cmd = self.m[1] # The following commands take no arguments if cmd == "Z" or cmd == "z": self.process_svg_path_data_cmd(id, cmd, 0, 0) elif self.eat_token('([CScsQqTtAa])'): - print("Unsupported path data command:", self.m.group(1), "in path", id, "\n", file=sys.stderr) + print("Unsupported path data command:", self.m[1], "in path", id, "\n", file=sys.stderr) quit() elif self.eat_token('([ ,]*[-0-9e.]+)+'): # Process list of coordinates following command - coords = re.split('[ ,]+', self.m.group(0)) + coords = re.split('[ ,]+', self.m[0]) # The following commands take two arguments if cmd == "L" or cmd == "l": while coords: @@ -245,7 +245,7 @@ class Parser: id = "" m = re.search(' id="(.*)"', path) if m: - id = m.group(1) + id = m[1] m = re.search(' transform="(.*)"', path) if m: @@ -254,7 +254,7 @@ class Parser: m = re.search(' d="(.*)"', path) if m: - self.process_svg_path_data(id, m.group(1)) + self.process_svg_path_data(id, m[1]) self.op.path_finished(id) self.reset() diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.py b/buildroot/share/PlatformIO/scripts/common-dependencies.py index e8219503bd..4b986274ee 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.py +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.py @@ -56,7 +56,7 @@ if pioutil.is_pio_build(): # Split up passed lines on commas or newlines and iterate # Add common options to the features config under construction # For lib_deps replace a previous instance of the same library - atoms = re.sub(r',\\s*', '\n', flines).strip().split('\n') + atoms = re.sub(r',\s*', '\n', flines).strip().split('\n') for line in atoms: parts = line.split('=') name = parts.pop(0) @@ -64,7 +64,7 @@ if pioutil.is_pio_build(): feat[name] = '='.join(parts) blab("[%s] %s=%s" % (feature, name, feat[name]), 3) else: - for dep in re.split(r",\s*", line): + for dep in re.split(r',\s*', line): lib_name = re.sub(r'@([~^]|[<>]=?)?[\d.]+', '', dep.strip()).split('=').pop(0) lib_re = re.compile('(?!^' + lib_name + '\\b)') feat['lib_deps'] = list(filter(lib_re.match, feat['lib_deps'])) + [dep] @@ -89,7 +89,7 @@ if pioutil.is_pio_build(): except: val = None if val: - opt = mat.group(1).upper() + opt = mat[1].upper() blab("%s.custom_marlin.%s = '%s'" % ( env['PIOENV'], opt, val )) add_to_feat_cnf(opt, val) diff --git a/buildroot/share/PlatformIO/scripts/signature.py b/buildroot/share/PlatformIO/scripts/signature.py index 593f9580b3..f1c86bb839 100644 --- a/buildroot/share/PlatformIO/scripts/signature.py +++ b/buildroot/share/PlatformIO/scripts/signature.py @@ -4,21 +4,21 @@ import os,subprocess,re,json,hashlib # -# The dumbest preprocessor in the world -# Extract macro name from an header file and store them in an array -# No processing is done here, so they are raw values here and it does not match what actually enabled -# in the file (since you can have #if SOMETHING_UNDEFINED / #define BOB / #endif) -# But it's useful to filter the useful macro spit out by the preprocessor from noise from the system -# headers. +# Return all macro names in a header as an array, so we can take +# the intersection with the preprocessor output, giving a decent +# reflection of all enabled options that (probably) came from the +# configuration files. We end up with the actual configured state, +# better than what the config files say. You can then use the +# resulting config.ini to produce more exact configuration files. # def extract_defines(filepath): f = open(filepath, encoding="utf8").read().split("\n") a = [] for line in f: - sline = line.strip(" \t\n\r") + sline = line.strip() if sline[:7] == "#define": # Extract the key here (we don't care about the value) - kv = sline[8:].strip().split(' ') + kv = sline[8:].strip().split() a.append(kv[0]) return a @@ -51,7 +51,7 @@ def compute_build_signature(env): # Definitions from these files will be kept files_to_keep = [ 'Marlin/Configuration.h', 'Marlin/Configuration_adv.h' ] - build_dir=os.path.join(env['PROJECT_BUILD_DIR'], env['PIOENV']) + build_dir = os.path.join(env['PROJECT_BUILD_DIR'], env['PIOENV']) # Check if we can skip processing hashes = '' @@ -77,14 +77,14 @@ def compute_build_signature(env): complete_cfg = run_preprocessor(env) # Dumb #define extraction from the configuration files - real_defines = {} + conf_defines = {} all_defines = [] for header in files_to_keep: defines = extract_defines(header) # To filter only the define we want - all_defines = all_defines + defines + all_defines += defines # To remember from which file it cames from - real_defines[header.split('/')[-1]] = defines + conf_defines[header.split('/')[-1]] = defines r = re.compile(r"\(+(\s*-*\s*_.*)\)+") @@ -116,16 +116,16 @@ def compute_build_signature(env): resolved_defines = {} for key in defines: # Remove all boards now - if key[0:6] == "BOARD_" and key != "BOARD_INFO_NAME": + if key.startswith("BOARD_") and key != "BOARD_INFO_NAME": continue # Remove all keys ending by "_NAME" as it does not make a difference to the configuration - if key[-5:] == "_NAME" and key != "CUSTOM_MACHINE_NAME": + if key.endswith("_NAME") and key != "CUSTOM_MACHINE_NAME": continue - # Remove all keys ending by "_T_DECLARED" as it's a copy of not important system stuff - if key[-11:] == "_T_DECLARED": + # Remove all keys ending by "_T_DECLARED" as it's a copy of extraneous system stuff + if key.endswith("_T_DECLARED"): continue # Remove keys that are not in the #define list in the Configuration list - if not (key in all_defines) and key != "DETAILED_BUILD_VERSION" and key != "STRING_DISTRIBUTION_DATE": + if key not in all_defines + [ 'DETAILED_BUILD_VERSION', 'STRING_DISTRIBUTION_DATE' ]: continue # Don't be that smart guy here @@ -136,13 +136,13 @@ def compute_build_signature(env): data = {} data['__INITIAL_HASH'] = hashes # First create a key for each header here - for header in real_defines: + for header in conf_defines: data[header] = {} # Then populate the object where each key is going to (that's a O(N^2) algorithm here...) for key in resolved_defines: - for header in real_defines: - if key in real_defines[header]: + for header in conf_defines: + if key in conf_defines[header]: data[header][key] = resolved_defines[key] # Append the source code version and date @@ -155,6 +155,9 @@ def compute_build_signature(env): except: pass + # + # Produce a JSON file for CONFIGURATION_EMBEDDING or CONFIG_DUMP > 0 + # with open(marlin_json, 'w') as outfile: json.dump(data, outfile, separators=(',', ':')) @@ -163,10 +166,12 @@ def compute_build_signature(env): # Generate a C source file for storing this array with open('Marlin/src/mczip.h','wb') as result_file: - result_file.write(b'#ifndef NO_CONFIGURATION_EMBEDDING_WARNING\n') - result_file.write(b' #warning "Generated file \'mc.zip\' is embedded (Define NO_CONFIGURATION_EMBEDDING_WARNING to suppress this warning.)"\n') - result_file.write(b'#endif\n') - result_file.write(b'const unsigned char mc_zip[] PROGMEM = {\n ') + result_file.write( + b'#ifndef NO_CONFIGURATION_EMBEDDING_WARNING\n' + + b' #warning "Generated file \'mc.zip\' is embedded (Define NO_CONFIGURATION_EMBEDDING_WARNING to suppress this warning.)"\n' + + b'#endif\n' + + b'const unsigned char mc_zip[] PROGMEM = {\n ' + ) count = 0 for b in open(os.path.join(build_dir, 'mc.zip'), 'rb').read(): result_file.write(b' 0x%02X,' % b) From cee9da6132f9a02eea55522ad0342359f6cec26f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 26 Jul 2022 14:54:54 -0500 Subject: [PATCH 24/54] =?UTF-8?q?=F0=9F=94=A8=20Update=20build/CI=20script?= =?UTF-8?q?s?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/build_all_examples | 46 ++++++++++++++++--------------- buildroot/bin/restore_configs | 11 ++++++-- buildroot/bin/use_example_configs | 1 + 3 files changed, 33 insertions(+), 25 deletions(-) diff --git a/buildroot/bin/build_all_examples b/buildroot/bin/build_all_examples index 73619ab472..a6d6ede47d 100755 --- a/buildroot/bin/build_all_examples +++ b/buildroot/bin/build_all_examples @@ -2,14 +2,14 @@ # # Usage: # -# build_all_examples [-b|--branch=] -# [-c|--continue] -# [-d|--debug] -# [-i|--ini] -# [-l|--limit=#] -# [-n|--nobuild] -# [-r|--resume=] -# [-s|--skip] +# build_all_examples [-b|--branch=] - Branch to fetch from Configurations repo +# [-c|--continue] - Continue the paused build +# [-d|--debug] - Print extra debug output +# [-i|--ini] - Archive ini/json/yml files in the temp config folder +# [-l|--limit=#] - Limit the number of builds in this run +# [-n|--nobuild] - Don't actually build anything. +# [-r|--resume=] - Start at some config in the filesystem order +# [-s|--skip] - Do the thing # # build_all_examples [...] branch [resume-from] # @@ -40,7 +40,7 @@ while getopts 'b:cdhil:nqr:sv-:' OFLAG; do r) FIRST_CONF="$OPTARG" ; bugout "Resume: $FIRST_CONF" ;; c) CONTINUE=1 ; bugout "Continue" ;; s) CONTSKIP=1 ; bugout "Continue, skipping" ;; - i) CREATE_INI=1 ; bugout "Generate an INI file" ;; + i) COPY_INI=1 ; bugout "Archive INI/JSON/YML files" ;; h) EXIT_USAGE=1 ; break ;; l) LIMIT=$OPTARG ; bugout "Limit to $LIMIT build(s)" ;; d|v) DEBUG=1 ; bugout "Debug ON" ;; @@ -52,7 +52,7 @@ while getopts 'b:cdhil:nqr:sv-:' OFLAG; do continue) CONTINUE=1 ; bugout "Continue" ;; skip) CONTSKIP=2 ; bugout "Continue, skipping" ;; limit) LIMIT=$OVAL ; bugout "Limit to $LIMIT build(s)" ;; - ini) CREATE_INI=1 ; bugout "Generate an INI file" ;; + ini) COPY_INI=1 ; bugout "Archive INI/JSON/YML files" ;; help) [[ -z "$OVAL" ]] || perror "option can't take value $OVAL" $ONAM ; EXIT_USAGE=1 ;; debug) DEBUG=1 ; bugout "Debug ON" ;; nobuild) DRYRUN=1 ; bugout "Dry Run" ;; @@ -136,19 +136,21 @@ for CONF in $CONF_TREE ; do # ...if skipping, don't build this one compgen -G "${CONF}Con*.h" > /dev/null || continue - # Remember where we are in case of failure - echo "${BRANCH}*${DIR}" >"$STAT_FILE" - - # Build or pretend to build + # Build or print build command for --nobuild if [[ $DRYRUN ]]; then - echo "[DRYRUN] build_example internal \"$TMP\" \"$DIR\"" + echo -e "\033[0;32m[DRYRUN] build_example internal \"$TMP\" \"$DIR\"\033[0m" else - # Build folder is unknown so delete all "config.ini" files - [[ $CREATE_INI ]] && find ./.pio/build/ -name "config.ini" -exec rm "{}" \; - ((DEBUG)) && echo "\"$HERE/build_example\" \"internal\" \"$TMP\" \"$DIR\"" - "$HERE/build_example" "internal" "$TMP" "$DIR" || { echo "Failed to build $DIR"; exit ; } - # Build folder is unknown so copy any "config.ini" - [[ $CREATE_INI ]] && find ./.pio/build/ -name "config.ini" -exec cp "{}" "$CONF" \; + # Remember where we are in case of failure + echo "${BRANCH}*${DIR}" >"$STAT_FILE" + # Build folder is unknown so delete all report files + if [[ $COPY_INI ]]; then + IFIND='find ./.pio/build/ -name "config.ini" -o -name "schema.json" -o -name "schema.yml"' + $IFIND -exec rm "{}" \; + fi + ((DEBUG)) && echo "\"$HERE/build_example\" internal \"$TMP\" \"$DIR\"" + "$HERE/build_example" internal "$TMP" "$DIR" || { echo "Failed to build $DIR"; exit ; } + # Build folder is unknown so copy all report files + [[ $COPY_INI ]] && $IFIND -exec cp "{}" "$CONF" \; fi ((--LIMIT)) || { echo "Limit reached" ; PAUSE=1 ; break ; } @@ -160,7 +162,7 @@ done # Delete the temp folder if not preserving generated INI files if [[ -e "$TMP/config/examples" ]]; then - if [[ $CREATE_INI ]]; then + if [[ $COPY_INI ]]; then OPEN=$( which gnome-open xdg-open open | head -n1 ) $OPEN "$TMP" elif [[ ! $PAUSE ]]; then diff --git a/buildroot/bin/restore_configs b/buildroot/bin/restore_configs index 04df695a00..ea998484c2 100755 --- a/buildroot/bin/restore_configs +++ b/buildroot/bin/restore_configs @@ -1,6 +1,11 @@ #!/usr/bin/env bash -git checkout Marlin/Configuration.h 2>/dev/null -git checkout Marlin/Configuration_adv.h 2>/dev/null -git checkout Marlin/src/pins/ramps/pins_RAMPS.h 2>/dev/null rm -f Marlin/_Bootscreen.h Marlin/_Statusscreen.h marlin_config.json .pio/build/mc.zip + +if [[ $1 == '-d' || $1 == '--default' ]]; then + use_example_configs +else + git checkout Marlin/Configuration.h 2>/dev/null + git checkout Marlin/Configuration_adv.h 2>/dev/null + git checkout Marlin/src/pins/ramps/pins_RAMPS.h 2>/dev/null +fi diff --git a/buildroot/bin/use_example_configs b/buildroot/bin/use_example_configs index de2edc2468..1fdab1de6c 100755 --- a/buildroot/bin/use_example_configs +++ b/buildroot/bin/use_example_configs @@ -3,6 +3,7 @@ # use_example_configs [repo:]configpath # # Examples: +# use_example_configs # use_example_configs Creality/CR-10/CrealityV1 # use_example_configs release-2.0.9.4:Creality/CR-10/CrealityV1 # From e7c262dc30cd921d6dc1da7ec494adacb43ed5f8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 26 Jul 2022 21:15:44 -0500 Subject: [PATCH 25/54] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20lcd=5Fpreheat=20comp?= =?UTF-8?q?ile?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 4 ++ .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 8 ++-- Marlin/src/lcd/extui/ui_api.cpp | 2 +- Marlin/src/lcd/menu/menu_filament.cpp | 8 ++-- Marlin/src/lcd/menu/menu_temperature.cpp | 44 +++++++++---------- Marlin/src/module/temperature.h | 2 +- 6 files changed, 38 insertions(+), 30 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 5286b9e61c..ed223cb6ec 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -913,6 +913,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "SD_REPRINT_LAST_SELECTED_FILE currently requires a Marlin-native LCD menu." #endif +#if ANY(HAS_MARLINUI_MENU, TOUCH_UI_FTDI_EVE, EXTENSIBLE_UI) && !defined(MANUAL_FEEDRATE) + #error "MANUAL_FEEDRATE is required for MarlinUI, ExtUI, or FTDI EVE Touch UI." +#endif + /** * Custom Boot and Status screens */ diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 88326466c0..0f34d76cfa 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -606,9 +606,11 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr break; #endif - case VP_BED_CONTROL: - preheat_temp = PREHEAT_1_TEMP_BED; - break; + #if HAS_HEATED_BED + case VP_BED_CONTROL: + preheat_temp = PREHEAT_1_TEMP_BED; + break; + #endif } *(int16_t*)var.memadr = *(int16_t*)var.memadr > 0 ? 0 : preheat_temp; diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 57822279c5..a711e6dd57 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1076,7 +1076,7 @@ namespace ExtUI { void coolDown() { thermalManager.cooldown(); } bool awaitingUserConfirm() { - return TERN0(HAS_RESUME_CONTINUE, wait_for_user) || getHostKeepaliveIsPaused(); + return TERN0(HAS_RESUME_CONTINUE, wait_for_user) || TERN0(HOST_KEEPALIVE_FEATURE, getHostKeepaliveIsPaused()); } void setUserConfirmed() { TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); } diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 5902a2f63f..122f0c4050 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -65,9 +65,11 @@ static void _change_filament_with_temp(const uint16_t celsius) { queue.inject(cmd); } -static void _change_filament_with_preset() { - _change_filament_with_temp(ui.material_preset[MenuItemBase::itemIndex].hotend_temp); -} +#if HAS_PREHEAT + static void _change_filament_with_preset() { + _change_filament_with_temp(ui.material_preset[MenuItemBase::itemIndex].hotend_temp); + } +#endif static void _change_filament_with_custom() { _change_filament_with_temp(thermalManager.degTargetHotend(MenuItemBase::itemIndex)); diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index e493972a97..2e5b8f1e54 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -47,30 +47,30 @@ // "Temperature" submenu items // -void Temperature::lcd_preheat(const uint8_t e, const int8_t indh, const int8_t indb) { - UNUSED(e); UNUSED(indh); UNUSED(indb); - #if HAS_HOTEND - if (indh >= 0 && ui.material_preset[indh].hotend_temp > 0) - setTargetHotend(_MIN(thermalManager.hotend_max_target(e), ui.material_preset[indh].hotend_temp), e); - #endif - #if HAS_HEATED_BED - if (indb >= 0 && ui.material_preset[indb].bed_temp > 0) setTargetBed(ui.material_preset[indb].bed_temp); - #endif - #if HAS_FAN - if (indh >= 0) { - const uint8_t fan_index = active_extruder < (FAN_COUNT) ? active_extruder : 0; - if (true - #if REDUNDANT_PART_COOLING_FAN - && fan_index != REDUNDANT_PART_COOLING_FAN - #endif - ) set_fan_speed(fan_index, ui.material_preset[indh].fan_speed); - } - #endif - ui.return_to_status(); -} - #if HAS_PREHEAT + void Temperature::lcd_preheat(const uint8_t e, const int8_t indh, const int8_t indb) { + UNUSED(e); UNUSED(indh); UNUSED(indb); + #if HAS_HOTEND + if (indh >= 0 && ui.material_preset[indh].hotend_temp > 0) + setTargetHotend(_MIN(thermalManager.hotend_max_target(e), ui.material_preset[indh].hotend_temp), e); + #endif + #if HAS_HEATED_BED + if (indb >= 0 && ui.material_preset[indb].bed_temp > 0) setTargetBed(ui.material_preset[indb].bed_temp); + #endif + #if HAS_FAN + if (indh >= 0) { + const uint8_t fan_index = active_extruder < (FAN_COUNT) ? active_extruder : 0; + if (true + #if REDUNDANT_PART_COOLING_FAN + && fan_index != REDUNDANT_PART_COOLING_FAN + #endif + ) set_fan_speed(fan_index, ui.material_preset[indh].fan_speed); + } + #endif + ui.return_to_status(); + } + #if HAS_TEMP_HOTEND inline void _preheat_end(const uint8_t m, const uint8_t e) { thermalManager.lcd_preheat(e, m, -1); } void do_preheat_end_m() { _preheat_end(editable.int8, 0); } diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 80d15ce39e..feec318050 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -1016,7 +1016,7 @@ class Temperature { static void set_heating_message(const uint8_t, const bool=false) {} #endif - #if HAS_MARLINUI_MENU && HAS_TEMPERATURE + #if HAS_MARLINUI_MENU && HAS_TEMPERATURE && HAS_PREHEAT static void lcd_preheat(const uint8_t e, const int8_t indh, const int8_t indb); #endif From d8db00e31febec6fa1a71e5ead6f0bff849fe15a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 27 Jul 2022 04:24:50 -0500 Subject: [PATCH 26/54] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20=20Up?= =?UTF-8?q?date=20planner/stepper=20includes?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/utility.cpp | 2 +- Marlin/src/core/utility.h | 5 +++++ Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 1 - Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp | 1 - Marlin/src/feature/dac/dac_dac084s085.cpp | 1 - Marlin/src/feature/fwretract.cpp | 1 - Marlin/src/feature/max7219.cpp | 1 - Marlin/src/feature/pause.cpp | 5 ++++- Marlin/src/feature/power.cpp | 3 ++- Marlin/src/feature/tmc_util.cpp | 5 ----- Marlin/src/gcode/bedlevel/G26.cpp | 1 - Marlin/src/gcode/bedlevel/abl/G29.cpp | 1 - Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- Marlin/src/gcode/calibrate/G28.cpp | 3 ++- Marlin/src/gcode/calibrate/G33.cpp | 2 +- Marlin/src/gcode/calibrate/G34.cpp | 5 ++++- Marlin/src/gcode/config/M540.cpp | 2 +- Marlin/src/gcode/control/M17_M18_M84.cpp | 1 + Marlin/src/gcode/control/M226.cpp | 2 +- Marlin/src/gcode/control/M3-M5.cpp | 2 +- Marlin/src/gcode/control/M400.cpp | 2 +- Marlin/src/gcode/control/M605.cpp | 1 - Marlin/src/gcode/feature/advance/M900.cpp | 1 - Marlin/src/gcode/feature/trinamic/M122.cpp | 2 +- Marlin/src/gcode/geometry/G53-G59.cpp | 2 -- Marlin/src/gcode/geometry/G92.cpp | 1 - Marlin/src/gcode/motion/G0_G1.cpp | 2 +- Marlin/src/gcode/motion/G4.cpp | 2 +- Marlin/src/gcode/probe/G38.cpp | 2 +- Marlin/src/module/stepper.cpp | 6 +++--- 30 files changed, 32 insertions(+), 35 deletions(-) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 9cdf8dec7b..e4fd525924 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -51,7 +51,7 @@ void safe_delay(millis_t ms) { #include "../module/probe.h" #include "../module/motion.h" - #include "../module/stepper.h" + #include "../module/planner.h" #include "../libs/numtostr.h" #include "../feature/bedlevel/bedlevel.h" diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index 10c8201610..2731e62b67 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -59,6 +59,11 @@ void safe_delay(millis_t ms); // Delay ensuring that temperatures are #define log_machine_info() NOOP #endif +/** + * A restorer instance remembers a variable's value before setting a + * new value, then restores the old value when it goes out of scope. + * Put operator= on your type to get extended behavior on value change. + */ template class restorer { T& ref_; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index a02918ff29..f1e88006ff 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -31,7 +31,6 @@ #include "../../../libs/hex_print.h" #include "../../../module/settings.h" #include "../../../lcd/marlinui.h" -#include "../../../module/stepper.h" #include "../../../module/planner.h" #include "../../../module/motion.h" #include "../../../module/probe.h" diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 8121a0b9b5..18110c67fa 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -26,7 +26,6 @@ #include "../bedlevel.h" #include "../../../module/planner.h" -#include "../../../module/stepper.h" #include "../../../module/motion.h" #if ENABLED(DELTA) diff --git a/Marlin/src/feature/dac/dac_dac084s085.cpp b/Marlin/src/feature/dac/dac_dac084s085.cpp index b88aaf802b..772bb68de4 100644 --- a/Marlin/src/feature/dac/dac_dac084s085.cpp +++ b/Marlin/src/feature/dac/dac_dac084s085.cpp @@ -11,7 +11,6 @@ #include "dac_dac084s085.h" #include "../../MarlinCore.h" -#include "../../module/stepper.h" #include "../../HAL/shared/Delay.h" dac084s085::dac084s085() { } diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 172c97accd..28355640d2 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -34,7 +34,6 @@ FWRetract fwretract; // Single instance - this calls the constructor #include "../module/motion.h" #include "../module/planner.h" -#include "../module/stepper.h" #include "../gcode/gcode.h" diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index 285a86ca63..2fdfcba32d 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -44,7 +44,6 @@ #include "max7219.h" #include "../module/planner.h" -#include "../module/stepper.h" #include "../MarlinCore.h" #include "../HAL/shared/Delay.h" diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 78572b0795..1c2ea59d4d 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -35,10 +35,13 @@ #include "../gcode/gcode.h" #include "../module/motion.h" #include "../module/planner.h" -#include "../module/stepper.h" #include "../module/printcounter.h" #include "../module/temperature.h" +#if HAS_EXTRUDERS + #include "../module/stepper.h" +#endif + #if ENABLED(AUTO_BED_LEVELING_UBL) #include "bedlevel/bedlevel.h" #endif diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index c2ed169aa8..8a16628bac 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -30,7 +30,7 @@ #include "power.h" #include "../module/planner.h" -#include "../module/stepper.h" +#include "../module/stepper/indirection.h" // for restore_stepper_drivers #include "../module/temperature.h" #include "../MarlinCore.h" @@ -46,6 +46,7 @@ Power powerManager; bool Power::psu_on; #if ENABLED(AUTO_POWER_CONTROL) + #include "../module/stepper.h" #include "../module/temperature.h" #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index cb970c7ebc..0867686363 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -33,17 +33,12 @@ #include "../gcode/gcode.h" #if ENABLED(TMC_DEBUG) - #include "../module/planner.h" #include "../libs/hex_print.h" #if ENABLED(MONITOR_DRIVER_STATUS) static uint16_t report_tmc_status_interval; // = 0 #endif #endif -#if HAS_MARLINUI_MENU - #include "../module/stepper.h" -#endif - /** * Check for over temperature or short to ground error flags. * Report and log warning of overtemperature condition. diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 1e436ffd96..aa6e0c1f0c 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -107,7 +107,6 @@ #include "../../MarlinCore.h" #include "../../module/planner.h" -#include "../../module/stepper.h" #include "../../module/motion.h" #include "../../module/tool_change.h" #include "../../module/temperature.h" diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index a2c53b5ab2..0fef5ad683 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -32,7 +32,6 @@ #include "../../../feature/bedlevel/bedlevel.h" #include "../../../module/motion.h" #include "../../../module/planner.h" -#include "../../../module/stepper.h" #include "../../../module/probe.h" #include "../../queue.h" diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index b9440f78b2..e98f3d5ee3 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -36,7 +36,7 @@ #include "../../../libs/buzzer.h" #include "../../../lcd/marlinui.h" #include "../../../module/motion.h" -#include "../../../module/stepper.h" +#include "../../../module/planner.h" #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index e312bf07b5..e22e3cb5f8 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -24,8 +24,9 @@ #include "../gcode.h" -#include "../../module/stepper.h" #include "../../module/endstops.h" +#include "../../module/planner.h" +#include "../../module/stepper.h" // for various #if HAS_MULTI_HOTEND #include "../../module/tool_change.h" diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index ffe53b63fb..656c23cb78 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -27,7 +27,7 @@ #include "../gcode.h" #include "../../module/delta.h" #include "../../module/motion.h" -#include "../../module/stepper.h" +#include "../../module/planner.h" #include "../../module/endstops.h" #include "../../lcd/marlinui.h" diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index 6fdebb69b0..1be3952ffe 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -26,9 +26,12 @@ #include "../gcode.h" #include "../../module/motion.h" -#include "../../module/stepper.h" #include "../../module/endstops.h" +#if ANY(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_PWM, HAS_TRINAMIC_CONFIG) + #include "../../module/stepper.h" +#endif + #if HAS_LEVELING #include "../../feature/bedlevel/bedlevel.h" #endif diff --git a/Marlin/src/gcode/config/M540.cpp b/Marlin/src/gcode/config/M540.cpp index 54d52f3a31..e751248dd6 100644 --- a/Marlin/src/gcode/config/M540.cpp +++ b/Marlin/src/gcode/config/M540.cpp @@ -25,7 +25,7 @@ #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) #include "../gcode.h" -#include "../../module/stepper.h" +#include "../../module/planner.h" /** * M540: Set whether SD card print should abort on endstop hit (M540 S<0|1>) diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index c2c8a702a1..4ff48568fa 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -24,6 +24,7 @@ #include "../../MarlinCore.h" // for stepper_inactive_time, disable_e_steppers #include "../../lcd/marlinui.h" #include "../../module/motion.h" // for e_axis_mask +#include "../../module/planner.h" #include "../../module/stepper.h" #if ENABLED(AUTO_BED_LEVELING_UBL) diff --git a/Marlin/src/gcode/control/M226.cpp b/Marlin/src/gcode/control/M226.cpp index 63f022e82b..4eb3db4bc3 100644 --- a/Marlin/src/gcode/control/M226.cpp +++ b/Marlin/src/gcode/control/M226.cpp @@ -26,7 +26,7 @@ #include "../gcode.h" #include "../../MarlinCore.h" // for pin_is_protected and idle() -#include "../../module/stepper.h" +#include "../../module/planner.h" void protected_pin_err(); diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index 3c51de6f6f..5d5d44e8bf 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -26,7 +26,7 @@ #include "../gcode.h" #include "../../feature/spindle_laser.h" -#include "../../module/stepper.h" +#include "../../module/planner.h" /** * Laser: diff --git a/Marlin/src/gcode/control/M400.cpp b/Marlin/src/gcode/control/M400.cpp index 9a5ad4e9df..6058fb894e 100644 --- a/Marlin/src/gcode/control/M400.cpp +++ b/Marlin/src/gcode/control/M400.cpp @@ -21,7 +21,7 @@ */ #include "../gcode.h" -#include "../../module/stepper.h" +#include "../../module/planner.h" /** * M400: Finish all moves diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index 06d92c8448..e3ca43e17f 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -28,7 +28,6 @@ #include "../gcode.h" #include "../../module/motion.h" -#include "../../module/stepper.h" #include "../../module/tool_change.h" #include "../../module/planner.h" diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index 8b59e88fb1..db09faa883 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -26,7 +26,6 @@ #include "../../gcode.h" #include "../../../module/planner.h" -#include "../../../module/stepper.h" #if ENABLED(EXTRA_LIN_ADVANCE_K) float other_extruder_advance_K[EXTRUDERS]; diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 2941632406..07fe9e5bd8 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -26,7 +26,7 @@ #include "../../gcode.h" #include "../../../feature/tmc_util.h" -#include "../../../module/stepper/indirection.h" +#include "../../../module/stepper/indirection.h" // for restore_stepper_drivers /** * M122: Debug TMC drivers diff --git a/Marlin/src/gcode/geometry/G53-G59.cpp b/Marlin/src/gcode/geometry/G53-G59.cpp index 092c141228..c51c29f423 100644 --- a/Marlin/src/gcode/geometry/G53-G59.cpp +++ b/Marlin/src/gcode/geometry/G53-G59.cpp @@ -25,8 +25,6 @@ #if ENABLED(CNC_COORDINATE_SYSTEMS) -#include "../../module/stepper.h" - //#define DEBUG_M53 /** diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index 58ed26a15a..b36f21d3c0 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -22,7 +22,6 @@ #include "../gcode.h" #include "../../module/motion.h" -#include "../../module/stepper.h" #if ENABLED(I2C_POSITION_ENCODERS) #include "../../feature/encoder_i2c.h" diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 933bf3d5d9..cee2f05080 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -32,7 +32,7 @@ #include "../../sd/cardreader.h" #if ENABLED(NANODLP_Z_SYNC) - #include "../../module/stepper.h" + #include "../../module/planner.h" #endif extern xyze_pos_t destination; diff --git a/Marlin/src/gcode/motion/G4.cpp b/Marlin/src/gcode/motion/G4.cpp index df3f5b010e..ebaa6aabc0 100644 --- a/Marlin/src/gcode/motion/G4.cpp +++ b/Marlin/src/gcode/motion/G4.cpp @@ -21,7 +21,7 @@ */ #include "../gcode.h" -#include "../../module/stepper.h" +#include "../../module/planner.h" #include "../../lcd/marlinui.h" /** diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index ed24ce3258..1b2da756b1 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -28,7 +28,7 @@ #include "../../module/endstops.h" #include "../../module/motion.h" -#include "../../module/stepper.h" +#include "../../module/planner.h" #include "../../module/probe.h" inline void G38_single_probe(const uint8_t move_value) { diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 593c8f7c6f..b7fd918561 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1467,14 +1467,14 @@ void Stepper::isr() { // Enable ISRs to reduce USART processing latency hal.isr_on(); - if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses + if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses #if ENABLED(LIN_ADVANCE) - if (!nextAdvanceISR) nextAdvanceISR = advance_isr(); // 0 = Do Linear Advance E Stepper pulses + if (!nextAdvanceISR) nextAdvanceISR = advance_isr(); // 0 = Do Linear Advance E Stepper pulses #endif #if ENABLED(INTEGRATED_BABYSTEPPING) - const bool is_babystep = (nextBabystepISR == 0); // 0 = Do Babystepping (XY)Z pulses + const bool is_babystep = (nextBabystepISR == 0); // 0 = Do Babystepping (XY)Z pulses if (is_babystep) nextBabystepISR = babystepping_isr(); #endif From ec9a2ee55711555bb1489e492120398a34ed52c5 Mon Sep 17 00:00:00 2001 From: Ludy Date: Thu, 28 Jul 2022 04:44:21 +0200 Subject: [PATCH 27/54] =?UTF-8?q?=F0=9F=8C=90=20Update=20German=20language?= =?UTF-8?q?=20(#24555)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_de.h | 107 +++++++++++++++++++------- 1 file changed, 80 insertions(+), 27 deletions(-) diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index a9fa16c77c..5708221e9c 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -37,7 +37,10 @@ namespace Language_de { LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" bereit"); LSTR MSG_YES = _UxGT("JA"); LSTR MSG_NO = _UxGT("NEIN"); + LSTR MSG_HIGH = _UxGT("HOCH"); + 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"); @@ -51,6 +54,8 @@ namespace Language_de { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Software-Endstopp"); LSTR MSG_MAIN = _UxGT("Hauptmenü"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Erw. Einstellungen"); + LSTR MSG_TOOLBAR_SETUP = _UxGT("Toolbar Einstellung"); + LSTR MSG_OPTION_DISABLED = _UxGT("Option Deaktiviert"); LSTR MSG_CONFIGURATION = _UxGT("Konfiguration"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Motoren deaktivieren"); // M84 :: Max length 19 characters @@ -64,6 +69,7 @@ namespace Language_de { LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); LSTR MSG_FILAMENT_SET = _UxGT("Fila. Einstellungen"); LSTR MSG_FILAMENT_MAN = _UxGT("Filament Management"); + LSTR MSG_MANUAL_LEVELING = _UxGT("Manuell Nivellierung"); LSTR MSG_LEVBED_FL = _UxGT("Vorne Links"); LSTR MSG_LEVBED_FR = _UxGT("Vorne Rechts"); LSTR MSG_LEVBED_C = _UxGT("Mitte"); @@ -96,7 +102,14 @@ namespace Language_de { LSTR MSG_PREHEAT_1_ALL = PREHEAT_1_LABEL _UxGT(" Alles Vorwärmen"); LSTR MSG_PREHEAT_1_BEDONLY = PREHEAT_1_LABEL _UxGT(" Bett Vorwärmen"); LSTR MSG_PREHEAT_1_SETTINGS = PREHEAT_1_LABEL _UxGT(" Einstellungen"); - + #ifdef PREHEAT_2_LABEL + LSTR MSG_PREHEAT_2 = PREHEAT_2_LABEL _UxGT(" Vorwärmen"); + LSTR MSG_PREHEAT_2_SETTINGS = PREHEAT_2_LABEL _UxGT(" Vorwärmen Konf"); + #endif + #ifdef PREHEAT_3_LABEL + LSTR MSG_PREHEAT_3 = PREHEAT_3_LABEL _UxGT(" Vorwärmen"); + LSTR MSG_PREHEAT_3_SETTINGS = PREHEAT_3_LABEL _UxGT(" Vorwärmen Konf"); + #endif LSTR MSG_PREHEAT_M = _UxGT("$ Vorwärmen"); LSTR MSG_PREHEAT_M_H = _UxGT("$ Vorwärmen") " ~"; LSTR MSG_PREHEAT_M_END = _UxGT("$ Extr. Vorwärmen"); @@ -143,10 +156,19 @@ namespace Language_de { LSTR MSG_MESH_VIEW = _UxGT("Netz ansehen"); LSTR MSG_EDITING_STOPPED = _UxGT("Netzbearb. angeh."); LSTR MSG_NO_VALID_MESH = _UxGT("Kein gültiges Netz"); + LSTR MSG_ACTIVATE_MESH = _UxGT("Nivellierung aktiv."); LSTR MSG_PROBING_POINT = _UxGT("Messpunkt"); LSTR MSG_MESH_X = _UxGT("Index X"); LSTR MSG_MESH_Y = _UxGT("Index Y"); + LSTR MSG_MESH_INSET = _UxGT("Mesh-Einsatz"); + LSTR MSG_MESH_MIN_X = _UxGT("Mesh X Minimum"); + LSTR MSG_MESH_MAX_X = _UxGT("Mesh X Maximum"); + LSTR MSG_MESH_MIN_Y = _UxGT("Mesh Y Minimum"); + LSTR MSG_MESH_MAX_Y = _UxGT("Mesh Y Maximum"); + LSTR MSG_MESH_AMAX = _UxGT("Bereich maximieren"); + LSTR MSG_MESH_CENTER = _UxGT("Center Area"); LSTR MSG_MESH_EDIT_Z = _UxGT("Z-Wert"); + LSTR MSG_MESH_CANCEL = _UxGT("Mesh abgebrochen"); LSTR MSG_CUSTOM_COMMANDS = _UxGT("Benutzer-Menü"); LSTR MSG_M48_TEST = _UxGT("M48 Sondentest"); LSTR MSG_M48_POINT = _UxGT("M48 Punkt"); @@ -165,6 +187,9 @@ namespace Language_de { LSTR MSG_UBL_TOOLS = _UxGT("UBL-Werkzeuge"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); LSTR MSG_LCD_TILTING_MESH = _UxGT("Berührungspunkt"); + LSTR MSG_UBL_TILT_MESH = _UxGT("Tilt Mesh"); + LSTR MSG_UBL_TILTING_GRID = _UxGT("Tilting Grid Size"); + LSTR MSG_UBL_MESH_TILTED = _UxGT("Mesh Tilted"); LSTR MSG_UBL_MANUAL_MESH = _UxGT("Netz manuell erst."); LSTR MSG_UBL_MESH_WIZARD = _UxGT("UBL Netz Assistent"); LSTR MSG_UBL_BC_INSERT = _UxGT("Unterlegen & messen"); @@ -183,14 +208,12 @@ namespace Language_de { LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Bearbeitung beendet"); LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Eigenes Netz erst."); LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Netz erstellen"); - #if HAS_PREHEAT - LSTR MSG_UBL_BUILD_MESH_M = _UxGT("$ Netz erstellen"); - LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("$ Netz validieren"); - #endif + LSTR MSG_UBL_BUILD_MESH_M = _UxGT("$ Netz erstellen"); LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Netz erstellen kalt"); LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Netzhöhe einst."); LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Höhe"); LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Netz validieren"); + LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("$ Netz validieren"); LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Eig. Netz validieren"); LSTR MSG_G26_HEATING_BED = _UxGT("G26 heizt Bett"); LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Düse aufheizen"); @@ -215,6 +238,8 @@ namespace Language_de { LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Manuelles Füllen"); LSTR MSG_UBL_SMART_FILLIN = _UxGT("Cleveres Füllen"); LSTR MSG_UBL_FILLIN_MESH = _UxGT("Netz Füllen"); + LSTR MSG_UBL_MESH_FILLED = _UxGT("Fehlende Punkte erg."); + LSTR MSG_UBL_MESH_INVALID = _UxGT("Ungültiges Netz"); LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Alles annullieren"); LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Nächstlieg. ann."); LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Feineinst. Alles"); @@ -223,6 +248,7 @@ namespace Language_de { LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Speicherort"); LSTR MSG_UBL_LOAD_MESH = _UxGT("Bettnetz laden"); LSTR MSG_UBL_SAVE_MESH = _UxGT("Bettnetz speichern"); + LSTR MSG_UBL_INVALID_SLOT = _UxGT("Wähle einen Mesh-Slot"); LSTR MSG_MESH_LOADED = _UxGT("Netz %i geladen"); LSTR MSG_MESH_SAVED = _UxGT("Netz %i gespeichert"); LSTR MSG_UBL_NO_STORAGE = _UxGT("Kein Speicher"); @@ -231,12 +257,12 @@ namespace Language_de { LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Versatz: "); LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Versatz angehalten"); LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Schrittweises UBL"); - LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Netz erstellen kalt"); - LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Cleveres Füllen"); + LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1.Netz kalt erstellen"); + LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2.Intelligent Füllen"); LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3.Netz validieren"); - LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Feineinst. Alles"); + LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4.Alles Feineinst."); LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5.Netz validieren"); - LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Feineinst. Alles"); + LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6.Alles Feineinst."); LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7.Bettnetz speichern"); LSTR MSG_LED_CONTROL = _UxGT("Licht-Steuerung"); @@ -315,7 +341,11 @@ namespace Language_de { LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); LSTR MSG_PID_CYCLE = _UxGT("PID Zyklus"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID Tuning fertig"); - LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune fehlge.! Falscher Extruder"); + LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("PID Autotune fehlge.!"); + LSTR MSG_BAD_EXTRUDER_NUM = _UxGT("ungültiger Extruder."); + LSTR MSG_TEMP_TOO_HIGH = _UxGT("Temperatur zu hoch."); + LSTR MSG_TIMEOUT = _UxGT("Timeout."); + LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune fehlge.! Ungültiger Extruder"); LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune fehlge.! Temperatur zu hoch."); LSTR MSG_PID_TIMEOUT = _UxGT("Autotune fehlge.! Timeout."); LSTR MSG_MPC_MEASURING_AMBIENT = _UxGT("teste Wärmeverlust"); @@ -334,14 +364,14 @@ namespace Language_de { LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); LSTR MSG_VN_JERK = _UxGT("Max @ Jerk"); - LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); + LSTR MSG_VE_JERK = _UxGT("Max ") STR_E _UxGT(" Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); LSTR MSG_MAX_SPEED = _UxGT("Max Geschw. (mm/s)"); LSTR MSG_VMAX_A = _UxGT("V max ") STR_A; LSTR MSG_VMAX_B = _UxGT("V max ") STR_B; LSTR MSG_VMAX_C = _UxGT("V max ") STR_C; LSTR MSG_VMAX_N = _UxGT("V max @"); - LSTR MSG_VMAX_E = _UxGT("V max E"); + LSTR MSG_VMAX_E = _UxGT("V max ") STR_E; LSTR MSG_VMAX_EN = _UxGT("V max *"); LSTR MSG_VMIN = _UxGT("V min "); LSTR MSG_VTRAV_MIN = _UxGT("V min Leerfahrt"); @@ -350,7 +380,7 @@ namespace Language_de { LSTR MSG_AMAX_B = _UxGT("A max ") STR_B; LSTR MSG_AMAX_C = _UxGT("A max ") STR_C; LSTR MSG_AMAX_N = _UxGT("A max @"); - LSTR MSG_AMAX_E = _UxGT("A max E"); + LSTR MSG_AMAX_E = _UxGT("A max ") STR_E; LSTR MSG_AMAX_EN = _UxGT("A max *"); LSTR MSG_A_RETRACT = _UxGT("A Einzug"); LSTR MSG_A_TRAVEL = _UxGT("A Leerfahrt"); @@ -378,6 +408,7 @@ namespace Language_de { LSTR MSG_CONTRAST = _UxGT("LCD-Kontrast"); LSTR MSG_BRIGHTNESS = _UxGT("LCD-Helligkeit"); LSTR MSG_LCD_TIMEOUT_SEC = _UxGT("LCD-Ruhezustand (s)"); + LSTR MSG_SCREEN_TIMEOUT = _UxGT("LCD Timeout (m)"); LSTR MSG_BRIGHTNESS_OFF = _UxGT("LCD ausschalten"); LSTR MSG_STORE_EEPROM = _UxGT("Konfig. speichern"); LSTR MSG_LOAD_EEPROM = _UxGT("Konfig. laden"); @@ -391,6 +422,10 @@ namespace Language_de { LSTR MSG_RESET_PRINTER = _UxGT("Drucker neustarten"); LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aktualisieren"); LSTR MSG_INFO_SCREEN = _UxGT("Info"); + LSTR MSG_INFO_MACHINENAME = _UxGT("Machine Name"); + LSTR MSG_INFO_SIZE = _UxGT("Größe"); + LSTR MSG_INFO_FWVERSION = _UxGT("Firmware Version"); + LSTR MSG_INFO_BUILD = _UxGT("Build Datum"); LSTR MSG_PREPARE = _UxGT("Vorbereitung"); LSTR MSG_TUNE = _UxGT("Justierung"); LSTR MSG_POWER_MONITOR = _UxGT("Power Monitor"); @@ -417,6 +452,7 @@ namespace Language_de { LSTR MSG_BUTTON_RESUME = _UxGT("Fortsetzen"); LSTR MSG_BUTTON_ADVANCED = _UxGT("Erweitert"); LSTR MSG_BUTTON_SAVE = _UxGT("Speichern"); + LSTR MSG_BUTTON_PURGE = _UxGT("Reinigen"); LSTR MSG_PAUSING = _UxGT("Pause..."); LSTR MSG_PAUSE_PRINT = _UxGT("SD-Druck pausieren"); LSTR MSG_ADVANCED_PAUSE = _UxGT("Erweiterte Pause"); @@ -439,9 +475,12 @@ namespace Language_de { LSTR MSG_REMAINING_TIME = _UxGT("Verbleiben"); LSTR MSG_PRINT_ABORTED = _UxGT("Druck abgebrochen"); LSTR MSG_PRINT_DONE = _UxGT("Druck fertig"); + LSTR MSG_PRINTER_KILLED = _UxGT("Drucker killed!"); + LSTR MSG_TURN_OFF = _UxGT("Drucker ausschalten"); LSTR MSG_NO_MOVE = _UxGT("Motoren angeschaltet"); LSTR MSG_KILLED = _UxGT("ABGEBROCHEN"); LSTR MSG_STOPPED = _UxGT("ANGEHALTEN"); + LSTR MSG_FWRETRACT = _UxGT("Firmware Retract"); LSTR MSG_CONTROL_RETRACT = _UxGT("Einzug mm"); LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Wechs. Einzug mm"); LSTR MSG_CONTROL_RETRACTF = _UxGT("V Einzug"); @@ -507,6 +546,9 @@ namespace Language_de { LSTR MSG_ZPROBE_XOFFSET = _UxGT("Sondenversatz X"); LSTR MSG_ZPROBE_YOFFSET = _UxGT("Sondenversatz Y"); LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Sondenversatz Z"); + LSTR MSG_ZPROBE_MARGIN = _UxGT("Sondenrand"); + LSTR MSG_Z_FEED_RATE = _UxGT("Z-Vorschub"); + LSTR MSG_ENABLE_HS_MODE = _UxGT("HS-Modus aktivieren"); LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Bewege Düse zum Bett"); LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); @@ -570,33 +612,37 @@ namespace Language_de { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Helligkeit"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Falscher Drucker"); + LSTR MSG_COLORS_GET = _UxGT("Farbe"); + LSTR MSG_COLORS_SELECT = _UxGT("Farben auswählen"); + LSTR MSG_COLORS_APPLIED = _UxGT("Farben verwenden"); + LSTR MSG_COLORS_RED = _UxGT("Rot"); + LSTR MSG_COLORS_GREEN = _UxGT("Grün"); + LSTR MSG_COLORS_BLUE = _UxGT("Blau"); + LSTR MSG_COLORS_WHITE = _UxGT("Weiß"); + LSTR MSG_UI_LANGUAGE = _UxGT("UI Sprache"); + LSTR MSG_SOUND_ENABLE = _UxGT("Ton aktivieren"); + LSTR MSG_LOCKSCREEN = _UxGT("Bildschirm sperren"); + LSTR MSG_LOCKSCREEN_LOCKED = _UxGT("Drucker ist gesperrt,"); + LSTR MSG_LOCKSCREEN_UNLOCK = _UxGT("Scrollen zum Entsper."); + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Kein Medium eingelegt."); - LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Bitte auf Neustart warten. "); - LSTR MSG_PLEASE_PREHEAT = _UxGT("Bitte das Hot-End vorheizen."); + LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Bitte auf Neustart warten."); + LSTR MSG_PLEASE_PREHEAT = _UxGT("Bitte das Hotend vorheizen."); LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Druckzähler zurücksetzen"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Gesamte Drucke"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Komplette Drucke"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Gesamte Druckzeit"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längste Druckzeit"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Gesamt Extrudiert"); - LSTR MSG_COLORS_GET = _UxGT("Farbe"); - LSTR MSG_COLORS_SELECT = _UxGT("Farben auswählen"); - LSTR MSG_COLORS_APPLIED = _UxGT("Farben verwenden"); - LSTR MSG_COLORS_RED = _UxGT("Rot"); - LSTR MSG_COLORS_GREEN = _UxGT("Grün"); - LSTR MSG_COLORS_BLUE = _UxGT("Blau"); - LSTR MSG_COLORS_WHITE = _UxGT("Weiß"); - LSTR MSG_UI_LANGUAGE = _UxGT("UI Sprache"); - LSTR MSG_SOUND_ENABLE = _UxGT("Ton aktivieren"); - LSTR MSG_LOCKSCREEN = _UxGT("Bildschirm sperren"); #else + LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Auf Neustart warten"); + LSTR MSG_PLEASE_PREHEAT = _UxGT("Bitte vorheizen"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Drucke"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Komplette"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Gesamte"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längste"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extrud."); - LSTR MSG_PLEASE_PREHEAT = _UxGT("Bitte vorheizen"); #endif LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); @@ -613,10 +659,14 @@ namespace Language_de { LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("FORTS. OPTIONEN:"); LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Mehr entladen"); LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Druck weiter"); + LSTR MSG_FILAMENT_CHANGE_PURGE_CONTINUE = _UxGT("Löschen o. fortfah.?"); LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Düse: "); LSTR MSG_RUNOUT_SENSOR = _UxGT("Runout-Sensor"); LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout-Weg mm"); LSTR MSG_RUNOUT_ENABLE = _UxGT("Runout aktivieren"); + LSTR MSG_RUNOUT_ACTIVE = _UxGT("Runout aktiv"); + LSTR MSG_INVERT_EXTRUDER = _UxGT("Invert Extruder"); + LSTR MSG_EXTRUDER_MIN_TEMP = _UxGT("Extruder Min Temp."); LSTR MSG_FANCHECK = _UxGT("Lüftergeschw. prüfen"); LSTR MSG_KILL_HOMING_FAILED = _UxGT("Homing gescheitert"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probing gescheitert"); @@ -660,6 +710,7 @@ namespace Language_de { LSTR MSG_VTOOLS_RESET = _UxGT("V-Tools ist resetet"); LSTR MSG_START_Z = _UxGT("Z Start:"); LSTR MSG_END_Z = _UxGT("Z Ende:"); + LSTR MSG_GAMES = _UxGT("Spiele"); LSTR MSG_BRICKOUT = _UxGT("Brickout"); LSTR MSG_INVADERS = _UxGT("Invaders"); @@ -683,6 +734,7 @@ namespace Language_de { // // Die Filament-Change-Bildschirme können bis zu 3 Zeilen auf einem 4-Zeilen-Display anzeigen // ...oder 2 Zeilen auf einem 3-Zeilen-Display. + #if LCD_HEIGHT >= 4 LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Knopf drücken um", "Druck fortzusetzen")); LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_2_LINE("Druck ist", "pausiert...")); @@ -720,10 +772,11 @@ namespace Language_de { LSTR MSG_BACKLASH = _UxGT("Spiel"); LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korrektur"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Glätten"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("X Achse leveln"); LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto. Kalibiren"); #if ENABLED(TOUCH_UI_FTDI_EVE) - LSTR MSG_HEATER_TIMEOUT = _UxGT("Idle Timeout, Temperatur fällt. Drücke Okay, um erneut aufzuheizen und fortzufahren."); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Idle Timeout, Temperatur gefallen. Drücke Okay, um erneut aufzuheizen und fortzufahren."); #else LSTR MSG_HEATER_TIMEOUT = _UxGT("Heizungs Timeout"); #endif From 9534c6e9033256f5d6de2b920124acf1fa829548 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 28 Jul 2022 20:52:33 -0500 Subject: [PATCH 28/54] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20'else'=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/tft/tft_ltdc.cpp | 4 +- Marlin/src/feature/direct_stepping.cpp | 19 +++---- .../generic/change_filament_screen.cpp | 4 +- .../generic/files_screen.cpp | 11 ++-- .../src/lcd/extui/mks_ui/wifiSerial_STM32.cpp | 53 ++++++++++--------- 5 files changed, 48 insertions(+), 43 deletions(-) diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp index 66cfd65995..95871bf41f 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.cpp @@ -372,9 +372,9 @@ void TFT_LTDC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Cou if (MemoryIncrease == DMA_PINC_ENABLE) { DrawImage(x_min, y_cur, x_min + width, y_cur + height, Data); Data += width * height; - } else { - DrawRect(x_min, y_cur, x_min + width, y_cur + height, *Data); } + else + DrawRect(x_min, y_cur, x_min + width, y_cur + height, *Data); y_cur += height; } diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp index 052e79de41..13cf71e076 100644 --- a/Marlin/src/feature/direct_stepping.cpp +++ b/Marlin/src/feature/direct_stepping.cpp @@ -143,14 +143,16 @@ namespace DirectStepping { // special case for 8-bit, check if rolled back to 0 if (Cfg::DIRECTIONAL || !write_page_size) { // full 256 bytes if (write_byte_idx) return true; - } else { - if (write_byte_idx < write_page_size) return true; } - } else if (Cfg::DIRECTIONAL) { - if (write_byte_idx != Cfg::PAGE_SIZE) return true; - } else { - if (write_byte_idx < write_page_size) return true; + else if (write_byte_idx < write_page_size) + return true; + } + else if (Cfg::DIRECTIONAL) { + if (write_byte_idx != Cfg::PAGE_SIZE) + return true; } + else if (write_byte_idx < write_page_size) + return true; state = State::CHECKSUM; return true; @@ -161,11 +163,10 @@ namespace DirectStepping { return true; } case State::UNFAIL: - if (c == 0) { + if (c == 0) set_page_state(write_page_idx, PageState::FREE); - } else { + else fatal_error = true; - } state = State::MONITOR; return true; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp index fa0748c17b..17ec975692 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp @@ -171,9 +171,9 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { const bool t_ok = getActualTemp_celsius(e) > getSoftenTemp() - 10; - if (mydata.t_tag && !t_ok) { + if (mydata.t_tag && !t_ok) cmd.text(HEATING_LBL_POS, GET_TEXT_F(MSG_HEATING)); - } else if (getActualTemp_celsius(e) > 100) { + else if (getActualTemp_celsius(e) > 100) { cmd.cmd(COLOR_RGB(0xFF0000)) .text(CAUTION_LBL_POS, GET_TEXT_F(MSG_CAUTION)) .colors(normal_btn) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp index 00768dbaf7..290c20f43e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp @@ -111,16 +111,17 @@ void FilesScreen::drawFileButton(int x, int y, int w, int h, const char *filenam cmd.cmd(COLOR_RGB(is_highlighted ? fg_action : bg_color)); cmd.font(font_medium).rectangle(bx, by, bw, bh); cmd.cmd(COLOR_RGB(is_highlighted ? normal_btn.rgb : bg_text_enabled)); - #if ENABLED(SCROLL_LONG_FILENAMES) - if (is_highlighted) { + if (TERN0(SCROLL_LONG_FILENAMES, is_highlighted)) { + #if ENABLED(SCROLL_LONG_FILENAMES) cmd.cmd(SAVE_CONTEXT()); cmd.cmd(SCISSOR_XY(x,y)); cmd.cmd(SCISSOR_SIZE(w,h)); cmd.cmd(MACRO(0)); cmd.text(bx, by, bw, bh, filename, OPT_CENTERY | OPT_NOFIT); - } else - #endif - draw_text_with_ellipsis(cmd, bx,by, bw - (is_dir ? 20 : 0), bh, filename, OPT_CENTERY, font_medium); + #endif + } + else + draw_text_with_ellipsis(cmd, bx,by, bw - (is_dir ? 20 : 0), bh, filename, OPT_CENTERY, font_medium); if (is_dir && !is_highlighted) cmd.text(bx, by, bw, bh, F("> "), OPT_CENTERY | OPT_RIGHTX); #if ENABLED(SCROLL_LONG_FILENAMES) if (is_highlighted) cmd.cmd(RESTORE_CONTEXT()); diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp index 6607e7531f..0e55b3448b 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp @@ -53,42 +53,45 @@ void WifiSerial::init(PinName _rx, PinName _tx) { WifiSerial::WifiSerial(void *peripheral) { // If PIN_SERIALy_RX is not defined assume half-duplex _serial.pin_rx = NC; + if (false) { + // for else if / else below... + } // If Serial is defined in variant set // the Rx/Tx pins for com port if defined #if defined(Serial) && defined(PIN_SERIAL_TX) - if ((void *)this == (void *)&Serial) { + else if ((void *)this == (void *)&Serial) { #ifdef PIN_SERIAL_RX setRx(PIN_SERIAL_RX); #endif setTx(PIN_SERIAL_TX); - } else + } #endif #if defined(PIN_SERIAL1_TX) && defined(USART1_BASE) - if (peripheral == USART1) { + else if (peripheral == USART1) { #ifdef PIN_SERIAL1_RX setRx(PIN_SERIAL1_RX); #endif setTx(PIN_SERIAL1_TX); - } else + } #endif #if defined(PIN_SERIAL2_TX) && defined(USART2_BASE) - if (peripheral == USART2) { + else if (peripheral == USART2) { #ifdef PIN_SERIAL2_RX setRx(PIN_SERIAL2_RX); #endif setTx(PIN_SERIAL2_TX); - } else + } #endif #if defined(PIN_SERIAL3_TX) && defined(USART3_BASE) - if (peripheral == USART3) { + else if (peripheral == USART3) { #ifdef PIN_SERIAL3_RX setRx(PIN_SERIAL3_RX); #endif setTx(PIN_SERIAL3_TX); - } else + } #endif #ifdef PIN_SERIAL4_TX - if (false + else if (false #ifdef USART4_BASE || peripheral == USART4 #elif defined(UART4_BASE) @@ -99,10 +102,10 @@ WifiSerial::WifiSerial(void *peripheral) { setRx(PIN_SERIAL4_RX); #endif setTx(PIN_SERIAL4_TX); - } else + } #endif #ifdef PIN_SERIAL5_TX - if (false + else if (false #ifdef USART5_BASE || peripheral == USART5 #elif defined(UART5_BASE) @@ -113,18 +116,18 @@ WifiSerial::WifiSerial(void *peripheral) { setRx(PIN_SERIAL5_RX); #endif setTx(PIN_SERIAL5_TX); - } else + } #endif #if defined(PIN_SERIAL6_TX) && defined(USART6_BASE) - if (peripheral == USART6) { + else if (peripheral == USART6) { #ifdef PIN_SERIAL6_RX setRx(PIN_SERIAL6_RX); #endif setTx(PIN_SERIAL6_TX); - } else + } #endif #ifdef PIN_SERIAL7_TX - if (false + else if (false #ifdef USART7_BASE || peripheral == USART7 #elif defined(UART7_BASE) @@ -135,10 +138,10 @@ WifiSerial::WifiSerial(void *peripheral) { setRx(PIN_SERIAL7_RX); #endif setTx(PIN_SERIAL7_TX); - } else + } #endif #ifdef PIN_SERIAL8_TX - if (false + else if (false #ifdef USART8_BASE || peripheral == USART8 #elif defined(UART8_BASE) @@ -149,18 +152,18 @@ WifiSerial::WifiSerial(void *peripheral) { setRx(PIN_SERIAL8_RX); #endif setTx(PIN_SERIAL8_TX); - } else + } #endif #if defined(PIN_SERIAL9_TX) && defined(UART9_BASE) - if (peripheral == UART9) { + else if (peripheral == UART9) { #ifdef PIN_SERIAL9_RX setRx(PIN_SERIAL9_RX); #endif setTx(PIN_SERIAL9_TX); - } else + } #endif #ifdef PIN_SERIAL10_TX - if (false + else if (false #ifdef USART10_BASE || peripheral == USART10 #elif defined(UART10_BASE) @@ -171,18 +174,18 @@ WifiSerial::WifiSerial(void *peripheral) { setRx(PIN_SERIAL10_RX); #endif setTx(PIN_SERIAL10_TX); - } else + } #endif #if defined(PIN_SERIALLP1_TX) && defined(LPUART1_BASE) - if (peripheral == LPUART1) { + else if (peripheral == LPUART1) { #ifdef PIN_SERIALLP1_RX setRx(PIN_SERIALLP1_RX); #endif setTx(PIN_SERIALLP1_TX); - } else + } #endif // else get the pins of the first peripheral occurrence in PinMap - { + else { _serial.pin_rx = pinmap_pin(peripheral, PinMap_UART_RX); _serial.pin_tx = pinmap_pin(peripheral, PinMap_UART_TX); } From 5f105e254dfa6c4280f2a3c276bdb8587cc4c152 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 29 Jul 2022 02:14:14 -0500 Subject: [PATCH 29/54] =?UTF-8?q?=F0=9F=90=9B=20Fix=20M125=20for=209=20Axi?= =?UTF-8?q?s?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/pause/M125.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index ae450cc5e9..9b18eda4fb 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -71,12 +71,12 @@ void GcodeSuite::M125() { if (parser.seenval('X')) park_point.x = RAW_X_POSITION(parser.linearval('X')), if (parser.seenval('Y')) park_point.y = RAW_Y_POSITION(parser.linearval('Y')), NOOP, - if (parser.seenval(AXIS4_NAME)) park_point.i = RAW_X_POSITION(parser.linearval(AXIS4_NAME)), - if (parser.seenval(AXIS5_NAME)) park_point.j = RAW_X_POSITION(parser.linearval(AXIS5_NAME)), - if (parser.seenval(AXIS6_NAME)) park_point.k = RAW_X_POSITION(parser.linearval(AXIS6_NAME)), - if (parser.seenval(AXIS7_NAME)) park_point.u = RAW_X_POSITION(parser.linearval(AXIS7_NAME)), - if (parser.seenval(AXIS8_NAME)) park_point.v = RAW_X_POSITION(parser.linearval(AXIS8_NAME)), - if (parser.seenval(AXIS9_NAME)) park_point.w = RAW_X_POSITION(parser.linearval(AXIS9_NAME)) + if (parser.seenval(AXIS4_NAME)) park_point.i = RAW_I_POSITION(parser.linearval(AXIS4_NAME)), + if (parser.seenval(AXIS5_NAME)) park_point.j = RAW_J_POSITION(parser.linearval(AXIS5_NAME)), + if (parser.seenval(AXIS6_NAME)) park_point.k = RAW_K_POSITION(parser.linearval(AXIS6_NAME)), + if (parser.seenval(AXIS7_NAME)) park_point.u = RAW_U_POSITION(parser.linearval(AXIS7_NAME)), + if (parser.seenval(AXIS8_NAME)) park_point.v = RAW_V_POSITION(parser.linearval(AXIS8_NAME)), + if (parser.seenval(AXIS9_NAME)) park_point.w = RAW_W_POSITION(parser.linearval(AXIS9_NAME)) ); // Lift Z axis From 868e76b96543ca5282558396c679d7e81d29df49 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 29 Jul 2022 08:01:39 -0500 Subject: [PATCH 30/54] =?UTF-8?q?=F0=9F=8E=A8=20Renum=20boards.h?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 68 ++++++++++++++++++++-------------------- 1 file changed, 34 insertions(+), 34 deletions(-) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 506b9cbd0e..4e3227ba58 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -387,40 +387,40 @@ #define BOARD_RUMBA32_BTT 4204 // RUMBA32 STM32F446VE based controller from BIGTREETECH #define BOARD_BLACK_STM32F407VE 4205 // BLACK_STM32F407VE #define BOARD_BLACK_STM32F407ZE 4206 // BLACK_STM32F407ZE -#define BOARD_BTT_SKR_PRO_V1_1 4208 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) -#define BOARD_BTT_SKR_PRO_V1_2 4209 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) -#define BOARD_BTT_BTT002_V1_0 4210 // BigTreeTech BTT002 v1.0 (STM32F407VG) -#define BOARD_BTT_E3_RRF 4211 // BigTreeTech E3 RRF (STM32F407VG) -#define BOARD_BTT_SKR_V2_0_REV_A 4212 // BigTreeTech SKR v2.0 Rev A (STM32F407VG) -#define BOARD_BTT_SKR_V2_0_REV_B 4213 // BigTreeTech SKR v2.0 Rev B (STM32F407VG/STM32F429VG) -#define BOARD_BTT_GTR_V1_0 4214 // BigTreeTech GTR v1.0 (STM32F407IGT) -#define BOARD_BTT_OCTOPUS_V1_0 4215 // BigTreeTech Octopus v1.0 (STM32F446ZE) -#define BOARD_BTT_OCTOPUS_V1_1 4216 // BigTreeTech Octopus v1.1 (STM32F446ZE) -#define BOARD_BTT_OCTOPUS_PRO_V1_0 4217 // BigTreeTech Octopus Pro v1.0 (STM32F446ZE / STM32F429ZG) -#define BOARD_LERDGE_K 4218 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 4219 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 4220 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 4221 // VAkE 403D (STM32F446VE) -#define BOARD_FYSETC_S6 4222 // FYSETC S6 (STM32F446VE) -#define BOARD_FYSETC_S6_V2_0 4223 // FYSETC S6 v2.0 (STM32F446VE) -#define BOARD_FYSETC_SPIDER 4224 // FYSETC Spider (STM32F446VE) -#define BOARD_FLYF407ZG 4225 // FLYmaker FLYF407ZG (STM32F407ZG) -#define BOARD_MKS_ROBIN2 4226 // MKS_ROBIN2 (STM32F407ZE) -#define BOARD_MKS_ROBIN_PRO_V2 4227 // MKS Robin Pro V2 (STM32F407VE) -#define BOARD_MKS_ROBIN_NANO_V3 4228 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_MKS_ROBIN_NANO_V3_1 4229 // MKS Robin Nano V3.1 (STM32F407VE) -#define BOARD_MKS_MONSTER8_V1 4230 // MKS Monster8 V1 (STM32F407VE) -#define BOARD_MKS_MONSTER8_V2 4231 // MKS Monster8 V2 (STM32F407VE) -#define BOARD_ANET_ET4 4232 // ANET ET4 V1.x (STM32F407VG) -#define BOARD_ANET_ET4P 4233 // ANET ET4P V1.x (STM32F407VG) -#define BOARD_FYSETC_CHEETAH_V20 4234 // FYSETC Cheetah V2.0 (STM32F401RC) -#define BOARD_TH3D_EZBOARD_V2 4235 // TH3D EZBoard v2.0 (STM32F405RG) -#define BOARD_OPULO_LUMEN_REV3 4236 // Opulo Lumen PnP Controller REV3 (STM32F407VE / STM32F407VG) -#define BOARD_MKS_ROBIN_NANO_V1_3_F4 4237 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) -#define BOARD_MKS_EAGLE 4238 // MKS Eagle (STM32F407VE) -#define BOARD_ARTILLERY_RUBY 4239 // Artillery Ruby (STM32F401RC) -#define BOARD_FYSETC_SPIDER_V2_2 4240 // FYSETC Spider V2.2 (STM32F446VE) -#define BOARD_CREALITY_V24S1_301F4 4241 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4 +#define BOARD_BTT_SKR_PRO_V1_1 4207 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) +#define BOARD_BTT_SKR_PRO_V1_2 4208 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) +#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VG) +#define BOARD_BTT_E3_RRF 4210 // BigTreeTech E3 RRF (STM32F407VG) +#define BOARD_BTT_SKR_V2_0_REV_A 4211 // BigTreeTech SKR v2.0 Rev A (STM32F407VG) +#define BOARD_BTT_SKR_V2_0_REV_B 4212 // BigTreeTech SKR v2.0 Rev B (STM32F407VG/STM32F429VG) +#define BOARD_BTT_GTR_V1_0 4213 // BigTreeTech GTR v1.0 (STM32F407IGT) +#define BOARD_BTT_OCTOPUS_V1_0 4214 // BigTreeTech Octopus v1.0 (STM32F446ZE) +#define BOARD_BTT_OCTOPUS_V1_1 4215 // BigTreeTech Octopus v1.1 (STM32F446ZE) +#define BOARD_BTT_OCTOPUS_PRO_V1_0 4216 // BigTreeTech Octopus Pro v1.0 (STM32F446ZE / STM32F429ZG) +#define BOARD_LERDGE_K 4217 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 4218 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 4219 // Lerdge X (STM32F407VE) +#define BOARD_VAKE403D 4220 // VAkE 403D (STM32F446VE) +#define BOARD_FYSETC_S6 4221 // FYSETC S6 (STM32F446VE) +#define BOARD_FYSETC_S6_V2_0 4222 // FYSETC S6 v2.0 (STM32F446VE) +#define BOARD_FYSETC_SPIDER 4223 // FYSETC Spider (STM32F446VE) +#define BOARD_FLYF407ZG 4224 // FLYmaker FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 4225 // MKS_ROBIN2 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 4226 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 4227 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_MKS_ROBIN_NANO_V3_1 4228 // MKS Robin Nano V3.1 (STM32F407VE) +#define BOARD_MKS_MONSTER8_V1 4229 // MKS Monster8 V1 (STM32F407VE) +#define BOARD_MKS_MONSTER8_V2 4230 // MKS Monster8 V2 (STM32F407VE) +#define BOARD_ANET_ET4 4231 // ANET ET4 V1.x (STM32F407VG) +#define BOARD_ANET_ET4P 4232 // ANET ET4P V1.x (STM32F407VG) +#define BOARD_FYSETC_CHEETAH_V20 4233 // FYSETC Cheetah V2.0 (STM32F401RC) +#define BOARD_TH3D_EZBOARD_V2 4234 // TH3D EZBoard v2.0 (STM32F405RG) +#define BOARD_OPULO_LUMEN_REV3 4235 // Opulo Lumen PnP Controller REV3 (STM32F407VE / STM32F407VG) +#define BOARD_MKS_ROBIN_NANO_V1_3_F4 4236 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) +#define BOARD_MKS_EAGLE 4237 // MKS Eagle (STM32F407VE) +#define BOARD_ARTILLERY_RUBY 4238 // Artillery Ruby (STM32F401RC) +#define BOARD_FYSETC_SPIDER_V2_2 4239 // FYSETC Spider V2.2 (STM32F446VE) +#define BOARD_CREALITY_V24S1_301F4 4240 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4 // // ARM Cortex M7 From 6134d55360b8155435bb2ed10f51704268f5450f Mon Sep 17 00:00:00 2001 From: lukasradek Date: Sat, 30 Jul 2022 01:53:39 +0200 Subject: [PATCH 31/54] =?UTF-8?q?=F0=9F=93=9D=20README=20Updates=20(#24564?= =?UTF-8?q?)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- README.md | 6 ++++++ ini/stm32f1-maple.ini | 4 ++-- ini/stm32f1.ini | 4 ++-- ini/stm32g0.ini | 2 +- 4 files changed, 11 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index 9d3ac6baaa..fb1e881dc5 100644 --- a/README.md +++ b/README.md @@ -32,6 +32,10 @@ To build Marlin 2.1 you'll need [Arduino IDE 1.8.8 or newer](https://www.arduino - [Installing Marlin (Arduino)](http://marlinfw.org/docs/basics/install_arduino.html) - [Installing Marlin (VSCode)](http://marlinfw.org/docs/basics/install_platformio_vscode.html). +## Hardware Abstraction Layer (HAL) + +Marlin 2.0 introduced a layer of abstraction to allow all the existing high-level code to be built for 32-bit platforms while still retaining full 8-bit AVR compatibility. Retaining AVR compatibility and a single code-base is important to us, because we want to make sure that features and patches get as much testing and attention as possible, and that all platforms always benefit from the latest improvements. + ### Supported Platforms Platform|MCU|Example Boards @@ -45,6 +49,8 @@ To build Marlin 2.1 you'll need [Arduino IDE 1.8.8 or newer](https://www.arduino [STM32F103](https://www.st.com/en/microcontrollers-microprocessors/stm32f103.html)|ARM® Cortex-M3|Malyan M200, GTM32 Pro, MKS Robin, BTT SKR Mini [STM32F401](https://www.st.com/en/microcontrollers-microprocessors/stm32f401.html)|ARM® Cortex-M4|ARMED, Rumba32, SKR Pro, Lerdge, FYSETC S6, Artillery Ruby [STM32F7x6](https://www.st.com/en/microcontrollers-microprocessors/stm32f7x6.html)|ARM® Cortex-M7|The Borg, RemRam V1 + [STM32G0B1RET6](https://www.st.com/en/microcontrollers-microprocessors/stm32g0x1.html)|ARM® Cortex-M0+|BigTreeTech SKR mini E3 V3.0 + [STM32H743xIT6](https://www.st.com/en/microcontrollers-microprocessors/stm32h743-753.html)|ARM® Cortex-M7|BigTreeTech SKR V3.0, SKR EZ V3.0, SKR SE BX V2.0/V3.0 [SAMD51P20A](https://www.adafruit.com/product/4064)|ARM® Cortex-M4|Adafruit Grand Central M4 [Teensy 3.5](https://www.pjrc.com/store/teensy35.html)|ARM® Cortex-M4| [Teensy 3.6](https://www.pjrc.com/store/teensy36.html)|ARM® Cortex-M4| diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 18c861ba1e..84055bebab 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -92,7 +92,7 @@ debug_tool = stlink upload_protocol = serial # -# BigTree SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) +# BigTreeTech SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) # # STM32F103RC_btt_maple ............. RCT6 with 256K # STM32F103RC_btt_USB_maple ......... RCT6 with 256K (USB mass storage) @@ -145,7 +145,7 @@ board_build.address = 0x08010000 board_build.ldscript = crealityPro.ld # -# BigTree SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) +# BigTreeTech SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # # STM32F103RE_btt_maple ............. RET6 # STM32F103RE_btt_USB_maple ......... RET6 (USB mass storage) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 8dc9bc3061..c0415c5f84 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -51,7 +51,7 @@ board = genericSTM32F103ZE monitor_speed = 115200 # -# BigTree SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) +# BigTreeTech SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) # # STM32F103RC_btt ............. RCT6 with 256K # STM32F103RC_btt_USB ......... RCT6 with 256K (USB mass storage) @@ -171,7 +171,7 @@ extends = STM32F103Rx_creality_xfer board = genericSTM32F103RC # -# BigTree SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) +# BigTreeTech SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # # STM32F103RE_btt ............. RET6 # STM32F103RE_btt_USB ......... RET6 (USB mass storage) diff --git a/ini/stm32g0.ini b/ini/stm32g0.ini index b6074d3af8..c80c8dd9e2 100644 --- a/ini/stm32g0.ini +++ b/ini/stm32g0.ini @@ -20,7 +20,7 @@ ################################# # -# BigTree SKR mini E3 V3.0 (STM32G0B1RET6 ARM Cortex-M0+) +# BigTreeTech SKR mini E3 V3.0 (STM32G0B1RET6 ARM Cortex-M0+) # [env:STM32G0B1RE_btt] extends = stm32_variant From bbaccd342eaf5e4cdca6b988c367fa79faacab82 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 30 Jul 2022 17:51:25 -0700 Subject: [PATCH 32/54] =?UTF-8?q?=E2=9C=A8=20Encoder=20Noise=20Filter=20(#?= =?UTF-8?q?24538)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 10 ++++++++++ Marlin/src/lcd/marlinui.h | 6 +----- buildroot/tests/mega2560 | 2 +- 3 files changed, 12 insertions(+), 6 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 2f34ebb7e8..5e452f3c49 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2467,6 +2467,16 @@ // //#define REVERSE_SELECT_DIRECTION +// +// Encoder EMI Noise Filter +// +// This option increases encoder samples to filter out phantom encoder clicks caused by EMI noise. +// +//#define ENCODER_NOISE_FILTER +#if ENABLED(ENCODER_NOISE_FILTER) + #define ENCODER_SAMPLES 10 +#endif + // // Individual Axis Homing // diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 6bd9ec8737..b2a9bb5de9 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -694,11 +694,7 @@ public: static void update_buttons(); - #if HAS_ENCODER_NOISE - #ifndef ENCODER_SAMPLES - #define ENCODER_SAMPLES 10 - #endif - + #if ENABLED(ENCODER_NOISE_FILTER) /** * Some printers may have issues with EMI noise especially using a motherboard with 3.3V logic levels * it may cause the logical LOW to float into the undefined region and register as a logical HIGH diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 89f9e046ce..536f723b73 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -32,7 +32,7 @@ opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATU EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_MENU_MAIN FREEZE_FEATURE CANCEL_OBJECTS SOUND_MENU_ITEM \ MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE EXTRA_LIN_ADVANCE_K QUICK_HOME \ LCD_SET_PROGRESS_MANUALLY PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME \ - BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL + ENCODER_NOISE_FILTER BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 5 | RRDFGSC | UBL | LIN_ADVANCE ..." "$3" # From 9ee558afe1afc20e5e932fc0dcbecd7744065ec7 Mon Sep 17 00:00:00 2001 From: DerAndere <26200979+DerAndere1@users.noreply.github.com> Date: Sun, 31 Jul 2022 03:49:15 +0200 Subject: [PATCH 33/54] =?UTF-8?q?=F0=9F=90=9B=20Fix=20kinematic=20feedrate?= =?UTF-8?q?=20(#24568)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/motion.cpp | 2 +- Marlin/src/module/planner.cpp | 8 +++++--- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 0bf6dfb7d9..6101022fd4 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1084,7 +1084,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { if (!position_is_reachable(destination)) return true; // Get the linear distance in XYZ - float cartesian_mm = diff.magnitude(); + float cartesian_mm = xyz_float_t(diff).magnitude(); // If the move is very short, check the E move distance TERN_(HAS_EXTRUDERS, if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e)); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index b4455ca5ec..4bc81c1051 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2195,7 +2195,7 @@ bool Planner::_populate_block( ); #if SECONDARY_LINEAR_AXES >= 1 && NONE(FOAMCUTTER_XYUV, ARTICULATED_ROBOT_ARM) - if (NEAR_ZERO(distance_sqr)) { + if (UNEAR_ZERO(distance_sqr)) { // Move does not involve any primary linear axes (xyz) but might involve secondary linear axes distance_sqr = (0.0f SECONDARY_AXIS_GANG( @@ -2211,7 +2211,7 @@ bool Planner::_populate_block( #endif #if HAS_ROTATIONAL_AXES && NONE(FOAMCUTTER_XYUV, ARTICULATED_ROBOT_ARM) - if (NEAR_ZERO(distance_sqr)) { + if (UNEAR_ZERO(distance_sqr)) { // Move involves only rotational axes. Calculate angular distance in accordance with LinuxCNC TERN_(INCH_MODE_SUPPORT, cartesian_move = false); distance_sqr = ROTATIONAL_AXIS_GANG(sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k), + sq(steps_dist_mm.u), + sq(steps_dist_mm.v), + sq(steps_dist_mm.w)); @@ -3154,7 +3154,9 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s PlannerHints ph = hints; if (!hints.millimeters) - ph.millimeters = (cart_dist_mm.x || cart_dist_mm.y) ? cart_dist_mm.magnitude() : TERN0(HAS_Z_AXIS, ABS(cart_dist_mm.z)); + ph.millimeters = (cart_dist_mm.x || cart_dist_mm.y) + ? xyz_pos_t(cart_dist_mm).magnitude() + : TERN0(HAS_Z_AXIS, ABS(cart_dist_mm.z)); #if ENABLED(SCARA_FEEDRATE_SCALING) // For SCARA scale the feedrate from mm/s to degrees/s From 5dad7e0d035ec82d2eeb38c79101cba93f35c958 Mon Sep 17 00:00:00 2001 From: tombrazier <68918209+tombrazier@users.noreply.github.com> Date: Sun, 31 Jul 2022 03:05:16 +0100 Subject: [PATCH 34/54] =?UTF-8?q?=F0=9F=A9=B9=20Use=20=5FMIN/=5FMAX=20macr?= =?UTF-8?q?os=20for=20native=20compatibility=20(#24570)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/temperature.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 9374971741..56eceea39d 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1418,7 +1418,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { // At startup, initialize modeled temperatures if (isnan(hotend.modeled_block_temp)) { - hotend.modeled_ambient_temp = min(30.0f, hotend.celsius); // Cap initial value at reasonable max room temperature of 30C + hotend.modeled_ambient_temp = _MIN(30.0f, hotend.celsius); // Cap initial value at reasonable max room temperature of 30C hotend.modeled_block_temp = hotend.modeled_sensor_temp = hotend.celsius; } @@ -1464,7 +1464,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { // Only correct ambient when close to steady state (output power is not clipped or asymptotic temperature is reached) if (WITHIN(hotend.soft_pwm_amount, 1, 126) || fabs(blocktempdelta + delta_to_apply) < (MPC_STEADYSTATE * MPC_dT)) - hotend.modeled_ambient_temp += delta_to_apply > 0.f ? max(delta_to_apply, MPC_MIN_AMBIENT_CHANGE * MPC_dT) : min(delta_to_apply, -MPC_MIN_AMBIENT_CHANGE * MPC_dT); + hotend.modeled_ambient_temp += delta_to_apply > 0.f ? _MAX(delta_to_apply, MPC_MIN_AMBIENT_CHANGE * MPC_dT) : _MIN(delta_to_apply, -MPC_MIN_AMBIENT_CHANGE * MPC_dT); float power = 0.0; if (hotend.target != 0 && TERN1(HEATER_IDLE_HANDLER, !heater_idle[ee].timed_out)) { From fd319928d2889efe57c76913b3d5d28ff49a70d1 Mon Sep 17 00:00:00 2001 From: tombrazier <68918209+tombrazier@users.noreply.github.com> Date: Sun, 31 Jul 2022 03:39:48 +0100 Subject: [PATCH 35/54] Fix, improve Linear Advance (#24533) --- Marlin/src/module/planner.cpp | 219 ++++++++++----------- Marlin/src/module/planner.h | 11 +- Marlin/src/module/stepper.cpp | 351 +++++++++++++++++----------------- Marlin/src/module/stepper.h | 75 +------- 4 files changed, 305 insertions(+), 351 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 4bc81c1051..1c9601632d 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -788,7 +788,7 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t NOLESS(initial_rate, uint32_t(MINIMAL_STEP_RATE)); NOLESS(final_rate, uint32_t(MINIMAL_STEP_RATE)); - #if ENABLED(S_CURVE_ACCELERATION) + #if EITHER(S_CURVE_ACCELERATION, LIN_ADVANCE) // If we have some plateau time, the cruise rate will be the nominal rate uint32_t cruise_rate = block->nominal_rate; #endif @@ -820,7 +820,7 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t accelerate_steps = _MIN(uint32_t(_MAX(accelerate_steps_float, 0)), block->step_event_count); decelerate_steps = block->step_event_count - accelerate_steps; - #if ENABLED(S_CURVE_ACCELERATION) + #if EITHER(S_CURVE_ACCELERATION, LIN_ADVANCE) // We won't reach the cruising rate. Let's calculate the speed we will reach cruise_rate = final_speed(initial_rate, accel, accelerate_steps); #endif @@ -849,6 +849,14 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t #endif block->final_rate = final_rate; + #if ENABLED(LIN_ADVANCE) + if (block->la_advance_rate) { + const float comp = extruder_advance_K[block->extruder] * block->steps.e / block->step_event_count; + block->max_adv_steps = cruise_rate * comp; + block->final_adv_steps = final_rate * comp; + } + #endif + #if ENABLED(LASER_POWER_TRAP) /** * Laser Trapezoid Calculations @@ -899,75 +907,76 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t #endif // LASER_POWER_TRAP } -/* PLANNER SPEED DEFINITION - +--------+ <- current->nominal_speed - / \ - current->entry_speed -> + \ - | + <- next->entry_speed (aka exit speed) - +-------------+ - time --> - - Recalculates the motion plan according to the following basic guidelines: - - 1. Go over every feasible block sequentially in reverse order and calculate the junction speeds - (i.e. current->entry_speed) such that: - a. No junction speed exceeds the pre-computed maximum junction speed limit or nominal speeds of - neighboring blocks. - b. A block entry speed cannot exceed one reverse-computed from its exit speed (next->entry_speed) - with a maximum allowable deceleration over the block travel distance. - c. The last (or newest appended) block is planned from a complete stop (an exit speed of zero). - 2. Go over every block in chronological (forward) order and dial down junction speed values if - a. The exit speed exceeds the one forward-computed from its entry speed with the maximum allowable - acceleration over the block travel distance. - - When these stages are complete, the planner will have maximized the velocity profiles throughout the all - of the planner blocks, where every block is operating at its maximum allowable acceleration limits. In - other words, for all of the blocks in the planner, the plan is optimal and no further speed improvements - are possible. If a new block is added to the buffer, the plan is recomputed according to the said - guidelines for a new optimal plan. - - To increase computational efficiency of these guidelines, a set of planner block pointers have been - created to indicate stop-compute points for when the planner guidelines cannot logically make any further - changes or improvements to the plan when in normal operation and new blocks are streamed and added to the - planner buffer. For example, if a subset of sequential blocks in the planner have been planned and are - bracketed by junction velocities at their maximums (or by the first planner block as well), no new block - added to the planner buffer will alter the velocity profiles within them. So we no longer have to compute - them. Or, if a set of sequential blocks from the first block in the planner (or a optimal stop-compute - point) are all accelerating, they are all optimal and can not be altered by a new block added to the - planner buffer, as this will only further increase the plan speed to chronological blocks until a maximum - junction velocity is reached. However, if the operational conditions of the plan changes from infrequently - used feed holds or feedrate overrides, the stop-compute pointers will be reset and the entire plan is - recomputed as stated in the general guidelines. - - Planner buffer index mapping: - - block_buffer_tail: Points to the beginning of the planner buffer. First to be executed or being executed. - - block_buffer_head: Points to the buffer block after the last block in the buffer. Used to indicate whether - the buffer is full or empty. As described for standard ring buffers, this block is always empty. - - block_buffer_planned: Points to the first buffer block after the last optimally planned block for normal - streaming operating conditions. Use for planning optimizations by avoiding recomputing parts of the - planner buffer that don't change with the addition of a new block, as describe above. In addition, - this block can never be less than block_buffer_tail and will always be pushed forward and maintain - this requirement when encountered by the Planner::release_current_block() routine during a cycle. - - NOTE: Since the planner only computes on what's in the planner buffer, some motions with many short - segments (e.g., complex curves) may seem to move slowly. This is because there simply isn't - enough combined distance traveled in the entire buffer to accelerate up to the nominal speed and - then decelerate to a complete stop at the end of the buffer, as stated by the guidelines. If this - happens and becomes an annoyance, there are a few simple solutions: - - - Maximize the machine acceleration. The planner will be able to compute higher velocity profiles - within the same combined distance. - - - Maximize line motion(s) distance per block to a desired tolerance. The more combined distance the - planner has to use, the faster it can go. - - - Maximize the planner buffer size. This also will increase the combined distance for the planner to - compute over. It also increases the number of computations the planner has to perform to compute an - optimal plan, so select carefully. - - - Use G2/G3 arcs instead of many short segments. Arcs inform the planner of a safe exit speed at the - end of the last segment, which alleviates this problem. -*/ +/** + * PLANNER SPEED DEFINITION + * +--------+ <- current->nominal_speed + * / \ + * current->entry_speed -> + \ + * | + <- next->entry_speed (aka exit speed) + * +-------------+ + * time --> + * + * Recalculates the motion plan according to the following basic guidelines: + * + * 1. Go over every feasible block sequentially in reverse order and calculate the junction speeds + * (i.e. current->entry_speed) such that: + * a. No junction speed exceeds the pre-computed maximum junction speed limit or nominal speeds of + * neighboring blocks. + * b. A block entry speed cannot exceed one reverse-computed from its exit speed (next->entry_speed) + * with a maximum allowable deceleration over the block travel distance. + * c. The last (or newest appended) block is planned from a complete stop (an exit speed of zero). + * 2. Go over every block in chronological (forward) order and dial down junction speed values if + * a. The exit speed exceeds the one forward-computed from its entry speed with the maximum allowable + * acceleration over the block travel distance. + * + * When these stages are complete, the planner will have maximized the velocity profiles throughout the all + * of the planner blocks, where every block is operating at its maximum allowable acceleration limits. In + * other words, for all of the blocks in the planner, the plan is optimal and no further speed improvements + * are possible. If a new block is added to the buffer, the plan is recomputed according to the said + * guidelines for a new optimal plan. + * + * To increase computational efficiency of these guidelines, a set of planner block pointers have been + * created to indicate stop-compute points for when the planner guidelines cannot logically make any further + * changes or improvements to the plan when in normal operation and new blocks are streamed and added to the + * planner buffer. For example, if a subset of sequential blocks in the planner have been planned and are + * bracketed by junction velocities at their maximums (or by the first planner block as well), no new block + * added to the planner buffer will alter the velocity profiles within them. So we no longer have to compute + * them. Or, if a set of sequential blocks from the first block in the planner (or a optimal stop-compute + * point) are all accelerating, they are all optimal and can not be altered by a new block added to the + * planner buffer, as this will only further increase the plan speed to chronological blocks until a maximum + * junction velocity is reached. However, if the operational conditions of the plan changes from infrequently + * used feed holds or feedrate overrides, the stop-compute pointers will be reset and the entire plan is + * recomputed as stated in the general guidelines. + * + * Planner buffer index mapping: + * - block_buffer_tail: Points to the beginning of the planner buffer. First to be executed or being executed. + * - block_buffer_head: Points to the buffer block after the last block in the buffer. Used to indicate whether + * the buffer is full or empty. As described for standard ring buffers, this block is always empty. + * - block_buffer_planned: Points to the first buffer block after the last optimally planned block for normal + * streaming operating conditions. Use for planning optimizations by avoiding recomputing parts of the + * planner buffer that don't change with the addition of a new block, as describe above. In addition, + * this block can never be less than block_buffer_tail and will always be pushed forward and maintain + * this requirement when encountered by the Planner::release_current_block() routine during a cycle. + * + * NOTE: Since the planner only computes on what's in the planner buffer, some motions with many short + * segments (e.g., complex curves) may seem to move slowly. This is because there simply isn't + * enough combined distance traveled in the entire buffer to accelerate up to the nominal speed and + * then decelerate to a complete stop at the end of the buffer, as stated by the guidelines. If this + * happens and becomes an annoyance, there are a few simple solutions: + * + * - Maximize the machine acceleration. The planner will be able to compute higher velocity profiles + * within the same combined distance. + * + * - Maximize line motion(s) distance per block to a desired tolerance. The more combined distance the + * planner has to use, the faster it can go. + * + * - Maximize the planner buffer size. This also will increase the combined distance for the planner to + * compute over. It also increases the number of computations the planner has to perform to compute an + * optimal plan, so select carefully. + * + * - Use G2/G3 arcs instead of many short segments. Arcs inform the planner of a safe exit speed at the + * end of the last segment, which alleviates this problem. + */ // The kernel called by recalculate() when scanning the plan from last to first entry. void Planner::reverse_pass_kernel(block_t * const current, const block_t * const next @@ -1211,13 +1220,6 @@ void Planner::recalculate_trapezoids(TERN_(HINTS_SAFE_EXIT_SPEED, const_float_t // NOTE: Entry and exit factors always > 0 by all previous logic operations. const float nomr = 1.0f / block->nominal_speed; calculate_trapezoid_for_block(block, current_entry_speed * nomr, next_entry_speed * nomr); - #if ENABLED(LIN_ADVANCE) - if (block->use_advance_lead) { - const float comp = block->e_D_ratio * extruder_advance_K[active_extruder] * settings.axis_steps_per_mm[E_AXIS]; - block->max_adv_steps = block->nominal_speed * comp; - block->final_adv_steps = next_entry_speed * comp; - } - #endif } // Reset current only to ensure next trapezoid is computed - The @@ -1251,13 +1253,6 @@ void Planner::recalculate_trapezoids(TERN_(HINTS_SAFE_EXIT_SPEED, const_float_t const float nomr = 1.0f / block->nominal_speed; calculate_trapezoid_for_block(block, current_entry_speed * nomr, next_entry_speed * nomr); - #if ENABLED(LIN_ADVANCE) - if (block->use_advance_lead) { - const float comp = block->e_D_ratio * extruder_advance_K[active_extruder] * settings.axis_steps_per_mm[E_AXIS]; - block->max_adv_steps = block->nominal_speed * comp; - block->final_adv_steps = next_entry_speed * comp; - } - #endif } // Reset block to ensure its trapezoid is computed - The stepper is free to use @@ -2502,13 +2497,15 @@ bool Planner::_populate_block( // Compute and limit the acceleration rate for the trapezoid generator. const float steps_per_mm = block->step_event_count * inverse_millimeters; uint32_t accel; + #if ENABLED(LIN_ADVANCE) + bool use_advance_lead = false; + #endif if (NUM_AXIS_GANG( !block->steps.a, && !block->steps.b, && !block->steps.c, && !block->steps.i, && !block->steps.j, && !block->steps.k, && !block->steps.u, && !block->steps.v, && !block->steps.w) ) { // Is this a retract / recover move? accel = CEIL(settings.retract_acceleration * steps_per_mm); // Convert to: acceleration steps/sec^2 - TERN_(LIN_ADVANCE, block->use_advance_lead = false); // No linear advance for simple retract/recover } else { #define LIMIT_ACCEL_LONG(AXIS,INDX) do{ \ @@ -2535,33 +2532,29 @@ bool Planner::_populate_block( /** * Use LIN_ADVANCE for blocks if all these are true: * - * esteps : This is a print move, because we checked for A, B, C steps before. + * esteps : This is a print move, because we checked for A, B, C steps before. * - * extruder_advance_K[active_extruder] : There is an advance factor set for this extruder. + * extruder_advance_K[extruder] : There is an advance factor set for this extruder. * - * de > 0 : Extruder is running forward (e.g., for "Wipe while retracting" (Slic3r) or "Combing" (Cura) moves) + * de > 0 : Extruder is running forward (e.g., for "Wipe while retracting" (Slic3r) or "Combing" (Cura) moves) */ - block->use_advance_lead = esteps - && extruder_advance_K[active_extruder] - && de > 0; - - if (block->use_advance_lead) { - block->e_D_ratio = (target_float.e - position_float.e) / - #if IS_KINEMATIC - block->millimeters - #else + use_advance_lead = esteps && extruder_advance_K[extruder] && de > 0; + + if (use_advance_lead) { + float e_D_ratio = (target_float.e - position_float.e) / + TERN(IS_KINEMATIC, block->millimeters, SQRT(sq(target_float.x - position_float.x) + sq(target_float.y - position_float.y) + sq(target_float.z - position_float.z)) - #endif - ; + ); // Check for unusual high e_D ratio to detect if a retract move was combined with the last print move due to min. steps per segment. Never execute this with advance! // This assumes no one will use a retract length of 0mm < retr_length < ~0.2mm and no one will print 100mm wide lines using 3mm filament or 35mm wide lines using 1.75mm filament. - if (block->e_D_ratio > 3.0f) - block->use_advance_lead = false; + if (e_D_ratio > 3.0f) + use_advance_lead = false; else { - const uint32_t max_accel_steps_per_s2 = MAX_E_JERK(extruder) / (extruder_advance_K[active_extruder] * block->e_D_ratio) * steps_per_mm; + // Scale E acceleration so that it will be possible to jump to the advance speed. + const uint32_t max_accel_steps_per_s2 = MAX_E_JERK(extruder) / (extruder_advance_K[extruder] * e_D_ratio) * steps_per_mm; if (TERN0(LA_DEBUG, accel > max_accel_steps_per_s2)) SERIAL_ECHOLNPGM("Acceleration limited."); NOMORE(accel, max_accel_steps_per_s2); @@ -2593,13 +2586,21 @@ bool Planner::_populate_block( block->acceleration_rate = (uint32_t)(accel * (float(1UL << 24) / (STEPPER_TIMER_RATE))); #endif #if ENABLED(LIN_ADVANCE) - if (block->use_advance_lead) { - block->advance_speed = (STEPPER_TIMER_RATE) / (extruder_advance_K[active_extruder] * block->e_D_ratio * block->acceleration * settings.axis_steps_per_mm[E_AXIS_N(extruder)]); + block->la_advance_rate = 0; + block->la_scaling = 0; + + if (use_advance_lead) { + // the Bresenham algorithm will convert this step rate into extruder steps + block->la_advance_rate = extruder_advance_K[extruder] * block->acceleration_steps_per_s2; + + // reduce LA ISR frequency by calling it only often enough to ensure that there will + // never be more than four extruder steps per call + for (uint32_t dividend = block->steps.e << 1; dividend <= (block->step_event_count >> 2); dividend <<= 1) + block->la_scaling++; + #if ENABLED(LA_DEBUG) - if (extruder_advance_K[active_extruder] * block->e_D_ratio * block->acceleration * 2 < block->nominal_speed * block->e_D_ratio) - SERIAL_ECHOLNPGM("More than 2 steps per eISR loop executed."); - if (block->advance_speed < 200) - SERIAL_ECHOLNPGM("eISR running at > 10kHz."); + if (block->la_advance_rate >> block->la_scaling > 10000) + SERIAL_ECHOLNPGM("eISR running at > 10kHz: ", block->la_advance_rate); #endif } #endif diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 6eb5272071..09afee7db1 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -239,11 +239,10 @@ typedef struct PlannerBlock { // Advance extrusion #if ENABLED(LIN_ADVANCE) - bool use_advance_lead; - uint16_t advance_speed, // STEP timer value for extruder speed offset ISR - max_adv_steps, // max. advance steps to get cruising speed pressure (not always nominal_speed!) - final_adv_steps; // advance steps due to exit speed - float e_D_ratio; + uint32_t la_advance_rate; // The rate at which steps are added whilst accelerating + uint8_t la_scaling; // Scale ISR frequency down and step frequency up by 2 ^ la_scaling + uint16_t max_adv_steps, // Max advance steps to get cruising speed pressure + final_adv_steps; // Advance steps for exit speed pressure #endif uint32_t nominal_rate, // The nominal step rate for this block in step_events/sec @@ -1018,7 +1017,7 @@ class Planner { return target_velocity_sqr - 2 * accel * distance; } - #if ENABLED(S_CURVE_ACCELERATION) + #if EITHER(S_CURVE_ACCELERATION, LIN_ADVANCE) /** * Calculate the speed reached given initial speed, acceleration and distance */ diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index b7fd918561..cac2161a47 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -217,18 +217,12 @@ uint32_t Stepper::advance_divisor = 0, #endif #if ENABLED(LIN_ADVANCE) - uint32_t Stepper::nextAdvanceISR = LA_ADV_NEVER, - Stepper::LA_isr_rate = LA_ADV_NEVER; - uint16_t Stepper::LA_current_adv_steps = 0, - Stepper::LA_final_adv_steps, - Stepper::LA_max_adv_steps; - - int8_t Stepper::LA_steps = 0; - - bool Stepper::LA_use_advance_lead; - -#endif // LIN_ADVANCE + Stepper::la_interval = LA_ADV_NEVER; + int32_t Stepper::la_delta_error = 0, + Stepper::la_dividend = 0, + Stepper::la_advance_steps = 0; +#endif #if ENABLED(INTEGRATED_BABYSTEPPING) uint32_t Stepper::nextBabystepISR = BABYSTEP_NEVER; @@ -588,29 +582,27 @@ void Stepper::set_directions() { TERN_(HAS_V_DIR, SET_STEP_DIR(V)); TERN_(HAS_W_DIR, SET_STEP_DIR(W)); - #if DISABLED(LIN_ADVANCE) - #if ENABLED(MIXING_EXTRUDER) - // Because this is valid for the whole block we don't know - // what E steppers will step. Likely all. Set all. - if (motor_direction(E_AXIS)) { - MIXER_STEPPER_LOOP(j) REV_E_DIR(j); - count_direction.e = -1; - } - else { - MIXER_STEPPER_LOOP(j) NORM_E_DIR(j); - count_direction.e = 1; - } - #elif HAS_EXTRUDERS - if (motor_direction(E_AXIS)) { - REV_E_DIR(stepper_extruder); - count_direction.e = -1; - } - else { - NORM_E_DIR(stepper_extruder); - count_direction.e = 1; - } - #endif - #endif // !LIN_ADVANCE + #if ENABLED(MIXING_EXTRUDER) + // Because this is valid for the whole block we don't know + // what E steppers will step. Likely all. Set all. + if (motor_direction(E_AXIS)) { + MIXER_STEPPER_LOOP(j) REV_E_DIR(j); + count_direction.e = -1; + } + else { + MIXER_STEPPER_LOOP(j) NORM_E_DIR(j); + count_direction.e = 1; + } + #elif HAS_EXTRUDERS + if (motor_direction(E_AXIS)) { + REV_E_DIR(stepper_extruder); + count_direction.e = -1; + } + else { + NORM_E_DIR(stepper_extruder); + count_direction.e = 1; + } + #endif DIR_WAIT_AFTER(); } @@ -1467,14 +1459,19 @@ void Stepper::isr() { // Enable ISRs to reduce USART processing latency hal.isr_on(); - if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses + if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses #if ENABLED(LIN_ADVANCE) - if (!nextAdvanceISR) nextAdvanceISR = advance_isr(); // 0 = Do Linear Advance E Stepper pulses + if (!nextAdvanceISR) { // 0 = Do Linear Advance E Stepper pulses + advance_isr(); + nextAdvanceISR = la_interval; + } + else if (nextAdvanceISR == LA_ADV_NEVER) // Start LA steps if necessary + nextAdvanceISR = la_interval; #endif #if ENABLED(INTEGRATED_BABYSTEPPING) - const bool is_babystep = (nextBabystepISR == 0); // 0 = Do Babystepping (XY)Z pulses + const bool is_babystep = (nextBabystepISR == 0); // 0 = Do Babystepping (XY)Z pulses if (is_babystep) nextBabystepISR = babystepping_isr(); #endif @@ -1796,20 +1793,18 @@ void Stepper::pulse_phase_isr() { PULSE_PREP(W); #endif - #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER) - delta_error.e += advance_dividend.e; - if (delta_error.e >= 0) { - #if ENABLED(LIN_ADVANCE) - delta_error.e -= advance_divisor; - // Don't step E here - But remember the number of steps to perform - motor_direction(E_AXIS) ? --LA_steps : ++LA_steps; - #else - count_position.e += count_direction.e; - step_needed.e = true; - #endif - } - #elif HAS_E0_STEP + #if EITHER(HAS_E0_STEP, MIXING_EXTRUDER) PULSE_PREP(E); + + #if ENABLED(LIN_ADVANCE) + if (step_needed.e && current_block->la_advance_rate) { + // don't actually step here, but do subtract movements steps + // from the linear advance step count + step_needed.e = false; + count_position.e -= count_direction.e; + la_advance_steps--; + } + #endif #endif } @@ -1849,12 +1844,10 @@ void Stepper::pulse_phase_isr() { PULSE_START(W); #endif - #if DISABLED(LIN_ADVANCE) - #if ENABLED(MIXING_EXTRUDER) - if (step_needed.e) E_STEP_WRITE(mixer.get_next_stepper(), !INVERT_E_STEP_PIN); - #elif HAS_E0_STEP - PULSE_START(E); - #endif + #if ENABLED(MIXING_EXTRUDER) + if (step_needed.e) E_STEP_WRITE(mixer.get_next_stepper(), !INVERT_E_STEP_PIN); + #elif HAS_E0_STEP + PULSE_START(E); #endif TERN_(I2S_STEPPER_STREAM, i2s_push_sample()); @@ -1894,15 +1887,10 @@ void Stepper::pulse_phase_isr() { PULSE_STOP(W); #endif - #if DISABLED(LIN_ADVANCE) - #if ENABLED(MIXING_EXTRUDER) - if (delta_error.e >= 0) { - delta_error.e -= advance_divisor; - E_STEP_WRITE(mixer.get_stepper(), INVERT_E_STEP_PIN); - } - #elif HAS_E0_STEP - PULSE_STOP(E); - #endif + #if ENABLED(MIXING_EXTRUDER) + if (step_needed.e) E_STEP_WRITE(mixer.get_stepper(), INVERT_E_STEP_PIN); + #elif HAS_E0_STEP + PULSE_STOP(E); #endif #if ISR_MULTI_STEPS @@ -1912,6 +1900,69 @@ void Stepper::pulse_phase_isr() { } while (--events_to_do); } +// Calculate timer interval, with all limits applied. +uint32_t Stepper::calc_timer_interval(uint32_t step_rate) { + #ifdef CPU_32_BIT + // In case of high-performance processor, it is able to calculate in real-time + return uint32_t(STEPPER_TIMER_RATE) / step_rate; + #else + // AVR is able to keep up at 30khz Stepping ISR rate. + constexpr uint32_t min_step_rate = (F_CPU) / 500000U; + if (step_rate <= min_step_rate) { + step_rate = 0; + uintptr_t table_address = (uintptr_t)&speed_lookuptable_slow[0][0]; + return uint16_t(pgm_read_word(table_address)); + } + else { + step_rate -= min_step_rate; // Correct for minimal speed + if (step_rate >= 0x0800) { // higher step rate + const uint8_t rate_mod_256 = (step_rate & 0x00FF); + const uintptr_t table_address = uintptr_t(&speed_lookuptable_fast[uint8_t(step_rate >> 8)][0]), + gain = uint16_t(pgm_read_word(table_address + 2)); + return uint16_t(pgm_read_word(table_address)) - MultiU16X8toH16(rate_mod_256, gain); + } + else { // lower step rates + uintptr_t table_address = uintptr_t(&speed_lookuptable_slow[0][0]); + table_address += (step_rate >> 1) & 0xFFFC; + return uint16_t(pgm_read_word(table_address)) + - ((uint16_t(pgm_read_word(table_address + 2)) * uint8_t(step_rate & 0x0007)) >> 3); + } + } + #endif +} + +// Get the timer interval and the number of loops to perform per tick +uint32_t Stepper::calc_timer_interval(uint32_t step_rate, uint8_t &loops) { + uint8_t multistep = 1; + #if DISABLED(DISABLE_MULTI_STEPPING) + + // The stepping frequency limits for each multistepping rate + static const uint32_t limit[] PROGMEM = { + ( MAX_STEP_ISR_FREQUENCY_1X ), + ( MAX_STEP_ISR_FREQUENCY_2X >> 1), + ( MAX_STEP_ISR_FREQUENCY_4X >> 2), + ( MAX_STEP_ISR_FREQUENCY_8X >> 3), + ( MAX_STEP_ISR_FREQUENCY_16X >> 4), + ( MAX_STEP_ISR_FREQUENCY_32X >> 5), + ( MAX_STEP_ISR_FREQUENCY_64X >> 6), + (MAX_STEP_ISR_FREQUENCY_128X >> 7) + }; + + // Select the proper multistepping + uint8_t idx = 0; + while (idx < 7 && step_rate > (uint32_t)pgm_read_dword(&limit[idx])) { + step_rate >>= 1; + multistep <<= 1; + ++idx; + }; + #else + NOMORE(step_rate, uint32_t(MAX_STEP_ISR_FREQUENCY_1X)); + #endif + loops = multistep; + + return calc_timer_interval(step_rate); +} + // This is the last half of the stepper interrupt: This one processes and // properly schedules blocks from the planner. This is executed after creating // the step pulses, so it is not time critical, as pulses are already done. @@ -1964,15 +2015,14 @@ uint32_t Stepper::block_phase_isr() { // acc_step_rate is in steps/second // step_rate to timer interval and steps per stepper isr - interval = calc_timer_interval(acc_step_rate, &steps_per_isr); + interval = calc_timer_interval(acc_step_rate << oversampling_factor, steps_per_isr); acceleration_time += interval; #if ENABLED(LIN_ADVANCE) - if (LA_use_advance_lead) { - // Fire ISR if final adv_rate is reached - if (LA_steps && LA_isr_rate != current_block->advance_speed) nextAdvanceISR = 0; + if (current_block->la_advance_rate) { + const uint32_t la_step_rate = la_advance_steps < current_block->max_adv_steps ? current_block->la_advance_rate : 0; + la_interval = calc_timer_interval(acc_step_rate + la_step_rate) << current_block->la_scaling; } - else if (LA_steps) nextAdvanceISR = 0; #endif /** @@ -2035,18 +2085,41 @@ uint32_t Stepper::block_phase_isr() { #endif // step_rate to timer interval and steps per stepper isr - interval = calc_timer_interval(step_rate, &steps_per_isr); + interval = calc_timer_interval(step_rate << oversampling_factor, steps_per_isr); deceleration_time += interval; #if ENABLED(LIN_ADVANCE) - if (LA_use_advance_lead) { - // Wake up eISR on first deceleration loop and fire ISR if final adv_rate is reached - if (step_events_completed <= decelerate_after + steps_per_isr || (LA_steps && LA_isr_rate != current_block->advance_speed)) { - initiateLA(); - LA_isr_rate = current_block->advance_speed; + if (current_block->la_advance_rate) { + const uint32_t la_step_rate = la_advance_steps > current_block->final_adv_steps ? current_block->la_advance_rate : 0; + if (la_step_rate != step_rate) { + bool reverse_e = la_step_rate > step_rate; + la_interval = calc_timer_interval(reverse_e ? la_step_rate - step_rate : step_rate - la_step_rate) << current_block->la_scaling; + + if (reverse_e != motor_direction(E_AXIS)) { + TBI(last_direction_bits, E_AXIS); + count_direction.e = -count_direction.e; + + DIR_WAIT_BEFORE(); + + if (reverse_e) { + #if ENABLED(MIXING_EXTRUDER) + MIXER_STEPPER_LOOP(j) REV_E_DIR(j); + #else + REV_E_DIR(stepper_extruder); + #endif + } + else { + #if ENABLED(MIXING_EXTRUDER) + MIXER_STEPPER_LOOP(j) NORM_E_DIR(j); + #else + NORM_E_DIR(stepper_extruder); + #endif + } + + DIR_WAIT_AFTER(); + } } } - else if (LA_steps) nextAdvanceISR = 0; #endif // LIN_ADVANCE /* @@ -2069,15 +2142,15 @@ uint32_t Stepper::block_phase_isr() { } else { // Must be in cruise phase otherwise - #if ENABLED(LIN_ADVANCE) - // If there are any esteps, fire the next advance_isr "now" - if (LA_steps && LA_isr_rate != current_block->advance_speed) initiateLA(); - #endif - // Calculate the ticks_nominal for this nominal speed, if not done yet if (ticks_nominal < 0) { // step_rate to timer interval and loops for the nominal speed - ticks_nominal = calc_timer_interval(current_block->nominal_rate, &steps_per_isr); + ticks_nominal = calc_timer_interval(current_block->nominal_rate << oversampling_factor, steps_per_isr); + + #if ENABLED(LIN_ADVANCE) + if (current_block->la_advance_rate) + la_interval = calc_timer_interval(current_block->nominal_rate) << current_block->la_scaling; + #endif } // The timer interval is just the nominal value for the nominal speed @@ -2291,7 +2364,7 @@ uint32_t Stepper::block_phase_isr() { step_event_count = current_block->step_event_count << oversampling; // Initialize Bresenham delta errors to 1/2 - delta_error = -int32_t(step_event_count); + delta_error = TERN_(LIN_ADVANCE, la_delta_error =) -int32_t(step_event_count); // Calculate Bresenham dividends and divisors advance_dividend = current_block->steps << 1; @@ -2312,16 +2385,12 @@ uint32_t Stepper::block_phase_isr() { #if ENABLED(LIN_ADVANCE) #if DISABLED(MIXING_EXTRUDER) && E_STEPPERS > 1 // If the now active extruder wasn't in use during the last move, its pressure is most likely gone. - if (stepper_extruder != last_moved_extruder) LA_current_adv_steps = 0; + if (stepper_extruder != last_moved_extruder) la_advance_steps = 0; #endif - - if ((LA_use_advance_lead = current_block->use_advance_lead)) { - LA_final_adv_steps = current_block->final_adv_steps; - LA_max_adv_steps = current_block->max_adv_steps; - initiateLA(); // Start the ISR - LA_isr_rate = current_block->advance_speed; + if (current_block->la_advance_rate) { + // apply LA scaling and discount the effect of frequency scaling + la_dividend = (advance_dividend.e << current_block->la_scaling) << oversampling; } - else LA_isr_rate = LA_ADV_NEVER; #endif if ( ENABLED(DUAL_X_CARRIAGE) // TODO: Find out why this fixes "jittery" small circles @@ -2375,7 +2444,15 @@ uint32_t Stepper::block_phase_isr() { #endif // Calculate the initial timer interval - interval = calc_timer_interval(current_block->initial_rate, &steps_per_isr); + interval = calc_timer_interval(current_block->initial_rate << oversampling_factor, steps_per_isr); + acceleration_time += interval; + + #if ENABLED(LIN_ADVANCE) + if (current_block->la_advance_rate) { + const uint32_t la_step_rate = la_advance_steps < current_block->max_adv_steps ? current_block->la_advance_rate : 0; + la_interval = calc_timer_interval(current_block->initial_rate + la_step_rate) << current_block->la_scaling; + } + #endif } } @@ -2386,71 +2463,15 @@ uint32_t Stepper::block_phase_isr() { #if ENABLED(LIN_ADVANCE) // Timer interrupt for E. LA_steps is set in the main routine - uint32_t Stepper::advance_isr() { - uint32_t interval; - - if (LA_use_advance_lead) { - if (step_events_completed > decelerate_after && LA_current_adv_steps > LA_final_adv_steps) { - LA_steps--; - LA_current_adv_steps--; - interval = LA_isr_rate; - } - else if (step_events_completed < decelerate_after && LA_current_adv_steps < LA_max_adv_steps) { - LA_steps++; - LA_current_adv_steps++; - interval = LA_isr_rate; - } - else - interval = LA_isr_rate = LA_ADV_NEVER; - } - else - interval = LA_ADV_NEVER; - - if (!LA_steps) return interval; // Leave pins alone if there are no steps! - - DIR_WAIT_BEFORE(); - - #if ENABLED(MIXING_EXTRUDER) - // We don't know which steppers will be stepped because LA loop follows, - // with potentially multiple steps. Set all. - if (LA_steps > 0) { - MIXER_STEPPER_LOOP(j) NORM_E_DIR(j); - count_direction.e = 1; - } - else if (LA_steps < 0) { - MIXER_STEPPER_LOOP(j) REV_E_DIR(j); - count_direction.e = -1; - } - #else - if (LA_steps > 0) { - NORM_E_DIR(stepper_extruder); - count_direction.e = 1; - } - else if (LA_steps < 0) { - REV_E_DIR(stepper_extruder); - count_direction.e = -1; - } - #endif - - DIR_WAIT_AFTER(); - - //const hal_timer_t added_step_ticks = hal_timer_t(ADDED_STEP_TICKS); - - // Step E stepper if we have steps - #if ISR_MULTI_STEPS - bool firstStep = true; - USING_TIMED_PULSE(); - #endif - - while (LA_steps) { - #if ISR_MULTI_STEPS - if (firstStep) - firstStep = false; - else - AWAIT_LOW_PULSE(); - #endif - + void Stepper::advance_isr() { + // Apply Bresenham algorithm so that linear advance can piggy back on + // the acceleration and speed values calculated in block_phase_isr(). + // This helps keep LA in sync with, for example, S_CURVE_ACCELERATION. + la_delta_error += la_dividend; + if (la_delta_error >= 0) { count_position.e += count_direction.e; + la_advance_steps += count_direction.e; + la_delta_error -= advance_divisor; // Set the STEP pulse ON #if ENABLED(MIXING_EXTRUDER) @@ -2461,12 +2482,8 @@ uint32_t Stepper::block_phase_isr() { // Enforce a minimum duration for STEP pulse ON #if ISR_PULSE_CONTROL + USING_TIMED_PULSE(); START_HIGH_PULSE(); - #endif - - LA_steps < 0 ? ++LA_steps : --LA_steps; - - #if ISR_PULSE_CONTROL AWAIT_HIGH_PULSE(); #endif @@ -2476,15 +2493,7 @@ uint32_t Stepper::block_phase_isr() { #else E_STEP_WRITE(stepper_extruder, INVERT_E_STEP_PIN); #endif - - // For minimum pulse time wait before looping - // Just wait for the requested pulse duration - #if ISR_PULSE_CONTROL - if (LA_steps) START_LOW_PULSE(); - #endif - } // LA_steps - - return interval; + } } #endif // LIN_ADVANCE diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index d8fb5af229..ccf342b573 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -417,10 +417,11 @@ class Stepper { #if ENABLED(LIN_ADVANCE) static constexpr uint32_t LA_ADV_NEVER = 0xFFFFFFFF; - static uint32_t nextAdvanceISR, LA_isr_rate; - static uint16_t LA_current_adv_steps, LA_final_adv_steps, LA_max_adv_steps; // Copy from current executed block. Needed because current_block is set to NULL "too early". - static int8_t LA_steps; - static bool LA_use_advance_lead; + static uint32_t nextAdvanceISR, + la_interval; // Interval between ISR calls for LA + static int32_t la_delta_error, // Analogue of delta_error.e for E steps in LA ISR + la_dividend, // Analogue of advance_dividend.e for E steps in LA ISR + la_advance_steps; // Count of steps added to increase nozzle pressure #endif #if ENABLED(INTEGRATED_BABYSTEPPING) @@ -475,8 +476,7 @@ class Stepper { #if ENABLED(LIN_ADVANCE) // The Linear advance ISR phase - static uint32_t advance_isr(); - FORCE_INLINE static void initiateLA() { nextAdvanceISR = 0; } + static void advance_isr(); #endif #if ENABLED(INTEGRATED_BABYSTEPPING) @@ -512,6 +512,7 @@ class Stepper { current_block = nullptr; axis_did_move = 0; planner.release_current_block(); + TERN_(LIN_ADVANCE, la_interval = nextAdvanceISR = LA_ADV_NEVER); } // Quickly stop all steppers @@ -631,65 +632,9 @@ class Stepper { // Set the current position in steps static void _set_position(const abce_long_t &spos); - FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t *loops) { - uint32_t timer; - - // Scale the frequency, as requested by the caller - step_rate <<= oversampling_factor; - - uint8_t multistep = 1; - #if DISABLED(DISABLE_MULTI_STEPPING) - - // The stepping frequency limits for each multistepping rate - static const uint32_t limit[] PROGMEM = { - ( MAX_STEP_ISR_FREQUENCY_1X ), - ( MAX_STEP_ISR_FREQUENCY_2X >> 1), - ( MAX_STEP_ISR_FREQUENCY_4X >> 2), - ( MAX_STEP_ISR_FREQUENCY_8X >> 3), - ( MAX_STEP_ISR_FREQUENCY_16X >> 4), - ( MAX_STEP_ISR_FREQUENCY_32X >> 5), - ( MAX_STEP_ISR_FREQUENCY_64X >> 6), - (MAX_STEP_ISR_FREQUENCY_128X >> 7) - }; - - // Select the proper multistepping - uint8_t idx = 0; - while (idx < 7 && step_rate > (uint32_t)pgm_read_dword(&limit[idx])) { - step_rate >>= 1; - multistep <<= 1; - ++idx; - }; - #else - NOMORE(step_rate, uint32_t(MAX_STEP_ISR_FREQUENCY_1X)); - #endif - *loops = multistep; - - #ifdef CPU_32_BIT - // In case of high-performance processor, it is able to calculate in real-time - timer = uint32_t(STEPPER_TIMER_RATE) / step_rate; - #else - constexpr uint32_t min_step_rate = (F_CPU) / 500000U; - NOLESS(step_rate, min_step_rate); - step_rate -= min_step_rate; // Correct for minimal speed - if (step_rate >= (8 * 256)) { // higher step rate - const uint8_t tmp_step_rate = (step_rate & 0x00FF); - const uint16_t table_address = (uint16_t)&speed_lookuptable_fast[(uint8_t)(step_rate >> 8)][0], - gain = (uint16_t)pgm_read_word(table_address + 2); - timer = MultiU16X8toH16(tmp_step_rate, gain); - timer = (uint16_t)pgm_read_word(table_address) - timer; - } - else { // lower step rates - uint16_t table_address = (uint16_t)&speed_lookuptable_slow[0][0]; - table_address += ((step_rate) >> 1) & 0xFFFC; - timer = (uint16_t)pgm_read_word(table_address) - - (((uint16_t)pgm_read_word(table_address + 2) * (uint8_t)(step_rate & 0x0007)) >> 3); - } - // (there is no need to limit the timer value here. All limits have been - // applied above, and AVR is able to keep up at 30khz Stepping ISR rate) - #endif - - return timer; - } + // Calculate timing interval for the given step rate + static uint32_t calc_timer_interval(uint32_t step_rate); + static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t &loops); #if ENABLED(S_CURVE_ACCELERATION) static void _calc_bezier_curve_coeffs(const int32_t v0, const int32_t v1, const uint32_t av); From c0cb7e35afe4a2e94133506d0e7c1d95ddbf80ba Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Sat, 30 Jul 2022 22:55:32 -0400 Subject: [PATCH 36/54] =?UTF-8?q?=E2=9C=A8=20Configurable=20Switching=20No?= =?UTF-8?q?zzle=20dwell=20(#24304)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 1 + Marlin/src/module/tool_change.cpp | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 5e452f3c49..986e3c49ab 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -270,6 +270,7 @@ #define SWITCHING_NOZZLE_SERVO_NR 0 //#define SWITCHING_NOZZLE_E1_SERVO_NR 1 // If two servos are used, the index of the second #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 (single servo) or lowered/raised (dual servo) + #define SWITCHING_NOZZLE_SERVO_DWELL 2500 // Dwell time to wait for servo to make physical move #endif /** diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 4b292c92f9..dbd95121dc 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -132,7 +132,7 @@ constexpr int16_t sns_angles[2] = SWITCHING_NOZZLE_SERVO_ANGLES; planner.synchronize(); servo[sns_index[e]].move(sns_angles[angle_index]); - safe_delay(500); + safe_delay(SWITCHING_NOZZLE_SERVO_DWELL); } void lower_nozzle(const uint8_t e) { _move_nozzle_servo(e, 0); } @@ -143,7 +143,7 @@ void move_nozzle_servo(const uint8_t angle_index) { planner.synchronize(); servo[SWITCHING_NOZZLE_SERVO_NR].move(servo_angles[SWITCHING_NOZZLE_SERVO_NR][angle_index]); - safe_delay(500); + safe_delay(SWITCHING_NOZZLE_SERVO_DWELL); } #endif From c3f258644541cc81150e5e306aa3db60a31fc5bf Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Mon, 1 Aug 2022 01:03:45 -0500 Subject: [PATCH 37/54] =?UTF-8?q?=F0=9F=90=9B=20Fix=20laser=20menu=20enabl?= =?UTF-8?q?e=5Fstate=20(#24557)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/spindle_laser.h | 25 +++++++++++----------- Marlin/src/lcd/menu/menu_spindle_laser.cpp | 4 ++-- 2 files changed, 15 insertions(+), 14 deletions(-) diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 8c73394c9b..b667da25bb 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -197,7 +197,7 @@ public: * - For CUTTER_MODE_ERROR set the output enable_state flag directly and set power to 0 for any mode. * This mode allows a global power shutdown action to occur. */ - static void set_enabled(const bool enable) { + static void set_enabled(bool enable) { switch (cutter_mode) { case CUTTER_MODE_STANDARD: apply_power(enable ? TERN(SPINDLE_LASER_USE_PWM, (power ?: (unitPower ? upower_to_ocr(cpwr_to_upwr(SPEED_POWER_STARTUP)) : 0)), 255) : 0); @@ -209,7 +209,7 @@ public: TERN_(LASER_FEATURE, set_inline_enabled(enable)); break; case CUTTER_MODE_ERROR: // Error mode, no enable and kill power. - enable_state = false; + enable = false; apply_power(0); } #if SPINDLE_LASER_ENA_PIN @@ -279,13 +279,14 @@ public: #if ENABLED(LASER_FEATURE) // Toggle the laser on/off with menuPower. Apply SPEED_POWER_STARTUP if it was 0 on entry. - static void laser_menu_toggle(const bool state) { + static void menu_set_enabled(const bool state) { set_enabled(state); if (state) { if (!menuPower) menuPower = cpwr_to_upwr(SPEED_POWER_STARTUP); power = upower_to_ocr(menuPower); apply_power(power); - } + } else + apply_power(0); } /** @@ -295,10 +296,10 @@ public: */ static void test_fire_pulse() { BUZZ(30, 3000); - cutter_mode = CUTTER_MODE_STANDARD;// Menu needs standard mode. - laser_menu_toggle(true); // Laser On - delay(testPulse); // Delay for time set by user in pulse ms menu screen. - laser_menu_toggle(false); // Laser Off + cutter_mode = CUTTER_MODE_STANDARD; // Menu needs standard mode. + menu_set_enabled(true); // Laser On + delay(testPulse); // Delay for time set by user in pulse ms menu screen. + menu_set_enabled(false); // Laser Off } #endif // LASER_FEATURE @@ -308,14 +309,14 @@ public: // Dynamic mode rate calculation static uint8_t calc_dynamic_power() { - if (feedrate_mm_m > 65535) return 255; // Too fast, go always on - uint16_t rate = uint16_t(feedrate_mm_m); // 16 bits from the G-code parser float input - rate >>= 8; // Take the G-code input e.g. F40000 and shift off the lower bits to get an OCR value from 1-255 + if (feedrate_mm_m > 65535) return 255; // Too fast, go always on + uint16_t rate = uint16_t(feedrate_mm_m); // 16 bits from the G-code parser float input + rate >>= 8; // Take the G-code input e.g. F40000 and shift off the lower bits to get an OCR value from 1-255 return uint8_t(rate); } // Inline modes of all other functions; all enable planner inline power control - static void set_inline_enabled(const bool enable) { planner.laser_inline.status.isEnabled = enable;} + static void set_inline_enabled(const bool enable) { planner.laser_inline.status.isEnabled = enable; } // Set the power for subsequent movement blocks static void inline_power(const cutter_power_t cpwr) { diff --git a/Marlin/src/lcd/menu/menu_spindle_laser.cpp b/Marlin/src/lcd/menu/menu_spindle_laser.cpp index bef86a6db8..a6f99546f6 100644 --- a/Marlin/src/lcd/menu/menu_spindle_laser.cpp +++ b/Marlin/src/lcd/menu/menu_spindle_laser.cpp @@ -48,12 +48,12 @@ cutter.mpower_min(), cutter.mpower_max(), cutter.update_from_mpower); #endif - editable.state = is_enabled; + editable.state = is_enabled; // State before toggle EDIT_ITEM(bool, MSG_CUTTER(TOGGLE), &is_enabled, []{ #if ENABLED(SPINDLE_FEATURE) if (editable.state) cutter.disable(); else cutter.enable_same_dir(); #else - cutter.laser_menu_toggle(!editable.state); + cutter.menu_set_enabled(!editable.state); #endif }); From 3b30951e83f0ec189c38ec993e5002f16556e087 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 1 Aug 2022 01:14:58 -0500 Subject: [PATCH 38/54] =?UTF-8?q?=F0=9F=94=A8=20Simplify=20scripts=20with?= =?UTF-8?q?=20pathlib=20(#24574)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/upload_extra_script.py | 38 ++++++----- .../scripts/STM32F1_create_variant.py | 27 ++++---- .../share/PlatformIO/scripts/chitu_crypt.py | 22 +++---- .../PlatformIO/scripts/download_mks_assets.py | 42 ++++++------ .../scripts/generic_create_variant.py | 24 ++++--- .../jgaurora_a5s_a1_with_bootloader.py | 51 +++++++------- buildroot/share/PlatformIO/scripts/lerdge.py | 4 +- buildroot/share/PlatformIO/scripts/marlin.py | 31 ++++----- .../PlatformIO/scripts/offset_and_rename.py | 12 ++-- .../PlatformIO/scripts/preflight-checks.py | 31 +++++---- .../share/PlatformIO/scripts/preprocessor.py | 66 ++++++++----------- buildroot/share/dwin/bin/DWIN_ICO.py | 2 +- buildroot/share/scripts/config-labels.py | 26 ++++---- buildroot/share/vscode/auto_build.py | 8 +-- 14 files changed, 185 insertions(+), 199 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/upload_extra_script.py b/Marlin/src/HAL/LPC1768/upload_extra_script.py index 7975f151f7..3e23c63ca1 100755 --- a/Marlin/src/HAL/LPC1768/upload_extra_script.py +++ b/Marlin/src/HAL/LPC1768/upload_extra_script.py @@ -12,7 +12,7 @@ if pioutil.is_pio_build(): target_filename = "FIRMWARE.CUR" target_drive = "REARM" - import os,getpass,platform + import platform current_OS = platform.system() Import("env") @@ -26,7 +26,8 @@ if pioutil.is_pio_build(): def before_upload(source, target, env): try: - # + from pathlib import Path + # # Find a disk for upload # upload_disk = 'Disk not found' @@ -38,6 +39,7 @@ if pioutil.is_pio_build(): # Windows - doesn't care about the disk's name, only cares about the drive letter import subprocess,string from ctypes import windll + from pathlib import PureWindowsPath # getting list of drives # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python @@ -49,7 +51,7 @@ if pioutil.is_pio_build(): bitmask >>= 1 for drive in drives: - final_drive_name = drive + ':\\' + final_drive_name = drive + ':' # print ('disc check: {}'.format(final_drive_name)) try: volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) @@ -59,29 +61,33 @@ if pioutil.is_pio_build(): else: if target_drive in volume_info and not target_file_found: # set upload if not found target file yet target_drive_found = True - upload_disk = final_drive_name + upload_disk = PureWindowsPath(final_drive_name) if target_filename in volume_info: if not target_file_found: - upload_disk = final_drive_name + upload_disk = PureWindowsPath(final_drive_name) target_file_found = True elif current_OS == 'Linux': # # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive' # - drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser())) + import getpass + user = getpass.getuser() + mpath = Path('media', user) + drives = [ x for x in mpath.iterdir() if x.is_dir() ] if target_drive in drives: # If target drive is found, use it. target_drive_found = True - upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep + upload_disk = mpath / target_drive else: for drive in drives: try: - files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive)) + fpath = mpath / drive + files = [ x for x in fpath.iterdir() if x.is_file() ] except: continue else: if target_filename in files: - upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep + upload_disk = mpath / drive target_file_found = True break # @@ -97,26 +103,28 @@ if pioutil.is_pio_build(): # # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive' # - drives = os.listdir('/Volumes') # human readable names + dpath = Path('/Volumes') # human readable names + drives = [ x for x in dpath.iterdir() ] if target_drive in drives and not target_file_found: # set upload if not found target file yet target_drive_found = True - upload_disk = '/Volumes/' + target_drive + '/' + upload_disk = dpath / target_drive for drive in drives: try: - filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected + fpath = dpath / drive # will get an error if the drive is protected + files = [ x for x in fpath.iterdir() ] except: continue else: - if target_filename in filenames: + if target_filename in files: if not target_file_found: - upload_disk = '/Volumes/' + drive + '/' + upload_disk = dpath / drive target_file_found = True # # Set upload_port to drive if found # if target_file_found or target_drive_found: - env.Replace(UPLOAD_PORT=upload_disk) + env.Replace(UPLOAD_PORT=str(upload_disk)) print('\nUpload disk: ', upload_disk, '\n') else: print_error('Autodetect Error') diff --git a/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py b/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py index 592fa50e5e..0eab7a8361 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py @@ -3,30 +3,29 @@ # import pioutil if pioutil.is_pio_build(): - import os,shutil,marlin - from SCons.Script import DefaultEnvironment - from platformio import util + import shutil,marlin + from pathlib import Path - env = DefaultEnvironment() + Import("env") platform = env.PioPlatform() board = env.BoardConfig() - FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32-maple") - assert os.path.isdir(FRAMEWORK_DIR) + FRAMEWORK_DIR = Path(platform.get_package_dir("framework-arduinoststm32-maple")) + assert FRAMEWORK_DIR.is_dir() - source_root = os.path.join("buildroot", "share", "PlatformIO", "variants") - assert os.path.isdir(source_root) + source_root = Path("buildroot/share/PlatformIO/variants") + assert source_root.is_dir() variant = board.get("build.variant") - variant_dir = os.path.join(FRAMEWORK_DIR, "STM32F1", "variants", variant) + variant_dir = FRAMEWORK_DIR / "STM32F1/variants" / variant - source_dir = os.path.join(source_root, variant) - assert os.path.isdir(source_dir) + source_dir = source_root / variant + assert source_dir.is_dir() - if os.path.isdir(variant_dir): + if variant_dir.is_dir(): shutil.rmtree(variant_dir) - if not os.path.isdir(variant_dir): - os.mkdir(variant_dir) + if not variant_dir.is_dir(): + variant_dir.mkdir() marlin.copytree(source_dir, variant_dir) diff --git a/buildroot/share/PlatformIO/scripts/chitu_crypt.py b/buildroot/share/PlatformIO/scripts/chitu_crypt.py index b28156bfb9..54b8375713 100644 --- a/buildroot/share/PlatformIO/scripts/chitu_crypt.py +++ b/buildroot/share/PlatformIO/scripts/chitu_crypt.py @@ -4,9 +4,7 @@ # import pioutil if pioutil.is_pio_build(): - import os,random,struct,uuid,marlin - # Relocate firmware from 0x08000000 to 0x08008800 - marlin.relocate_firmware("0x08008800") + import struct,uuid def calculate_crc(contents, seed): accumulating_xor_value = seed; @@ -105,13 +103,13 @@ if pioutil.is_pio_build(): # Encrypt ${PROGNAME}.bin and save it as 'update.cbd' def encrypt(source, target, env): - firmware = open(target[0].path, "rb") - update = open(target[0].dir.path + '/update.cbd', "wb") - length = os.path.getsize(target[0].path) - - encrypt_file(firmware, update, length) - - firmware.close() - update.close() - + from pathlib import Path + fwpath = Path(target[0].path) + fwsize = fwpath.stat().st_size + fwfile = fwpath.open("rb") + upfile = Path(target[0].dir.path, 'update.cbd').open("wb") + encrypt_file(fwfile, upfile, fwsize) + + import marlin + marlin.relocate_firmware("0x08008800") marlin.add_post_action(encrypt); diff --git a/buildroot/share/PlatformIO/scripts/download_mks_assets.py b/buildroot/share/PlatformIO/scripts/download_mks_assets.py index 1990400222..8d186b755f 100644 --- a/buildroot/share/PlatformIO/scripts/download_mks_assets.py +++ b/buildroot/share/PlatformIO/scripts/download_mks_assets.py @@ -5,45 +5,49 @@ import pioutil if pioutil.is_pio_build(): Import("env") - import os,requests,zipfile,tempfile,shutil + import requests,zipfile,tempfile,shutil + from pathlib import Path url = "https://github.com/makerbase-mks/Mks-Robin-Nano-Marlin2.0-Firmware/archive/0263cdaccf.zip" - deps_path = env.Dictionary("PROJECT_LIBDEPS_DIR") - zip_path = os.path.join(deps_path, "mks-assets.zip") - assets_path = os.path.join(env.Dictionary("PROJECT_BUILD_DIR"), env.Dictionary("PIOENV"), "assets") + deps_path = Path(env.Dictionary("PROJECT_LIBDEPS_DIR")) + zip_path = deps_path / "mks-assets.zip" + assets_path = Path(env.Dictionary("PROJECT_BUILD_DIR"), env.Dictionary("PIOENV"), "assets") def download_mks_assets(): print("Downloading MKS Assets") r = requests.get(url, stream=True) # the user may have a very clean workspace, # so create the PROJECT_LIBDEPS_DIR directory if not exits - if os.path.exists(deps_path) == False: - os.mkdir(deps_path) - with open(zip_path, 'wb') as fd: + if not deps_path.exists(): + deps_path.mkdir() + with zip_path.open('wb') as fd: for chunk in r.iter_content(chunk_size=128): fd.write(chunk) def copy_mks_assets(): print("Copying MKS Assets") - output_path = tempfile.mkdtemp() + output_path = Path(tempfile.mkdtemp()) zip_obj = zipfile.ZipFile(zip_path, 'r') zip_obj.extractall(output_path) zip_obj.close() - if os.path.exists(assets_path) == True and os.path.isdir(assets_path) == False: - os.unlink(assets_path) - if os.path.exists(assets_path) == False: - os.mkdir(assets_path) + if assets_path.exists() and not assets_path.is_dir(): + assets_path.unlink() + if not assets_path.exists(): + assets_path.mkdir() base_path = '' - for filename in os.listdir(output_path): + for filename in output_path.iterdir(): base_path = filename - for filename in os.listdir(os.path.join(output_path, base_path, 'Firmware', 'mks_font')): - shutil.copy(os.path.join(output_path, base_path, 'Firmware', 'mks_font', filename), assets_path) - for filename in os.listdir(os.path.join(output_path, base_path, 'Firmware', 'mks_pic')): - shutil.copy(os.path.join(output_path, base_path, 'Firmware', 'mks_pic', filename), assets_path) + fw_path = (output_path / base_path / 'Firmware') + font_path = fw_path / 'mks_font' + for filename in font_path.iterdir(): + shutil.copy(font_path / filename, assets_path) + pic_path = fw_path / 'mks_pic' + for filename in pic_path.iterdir(): + shutil.copy(pic_path / filename, assets_path) shutil.rmtree(output_path, ignore_errors=True) - if os.path.exists(zip_path) == False: + if not zip_path.exists(): download_mks_assets() - if os.path.exists(assets_path) == False: + if not assets_path.exists(): copy_mks_assets() diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index 1bd77812f7..5e3637604f 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -7,16 +7,14 @@ # import pioutil if pioutil.is_pio_build(): - import os,shutil,marlin - from SCons.Script import DefaultEnvironment - from platformio import util - - env = DefaultEnvironment() + import shutil,marlin + from pathlib import Path # # Get the platform name from the 'platform_packages' option, # or look it up by the platform.class.name. # + env = marlin.env platform = env.PioPlatform() from platformio.package.meta import PackageSpec @@ -37,8 +35,8 @@ if pioutil.is_pio_build(): if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino", "biqu-bx-workaround", "main" ]: platform_name = "framework-arduinoststm32" - FRAMEWORK_DIR = platform.get_package_dir(platform_name) - assert os.path.isdir(FRAMEWORK_DIR) + FRAMEWORK_DIR = Path(platform.get_package_dir(platform_name)) + assert FRAMEWORK_DIR.is_dir() board = env.BoardConfig() @@ -47,14 +45,14 @@ if pioutil.is_pio_build(): #series = mcu_type[:7].upper() + "xx" # Prepare a new empty folder at the destination - variant_dir = os.path.join(FRAMEWORK_DIR, "variants", variant) - if os.path.isdir(variant_dir): + variant_dir = FRAMEWORK_DIR / "variants" / variant + if variant_dir.is_dir(): shutil.rmtree(variant_dir) - if not os.path.isdir(variant_dir): - os.mkdir(variant_dir) + if not variant_dir.is_dir(): + variant_dir.mkdir() # Source dir is a local variant sub-folder - source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant) - assert os.path.isdir(source_dir) + source_dir = Path("buildroot/share/PlatformIO/variants", variant) + assert source_dir.is_dir() marlin.copytree(source_dir, variant_dir) diff --git a/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py b/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py index 0af9c1046d..b9516931b5 100644 --- a/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +++ b/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py @@ -4,37 +4,32 @@ # import pioutil if pioutil.is_pio_build(): - import os,marlin + # Append ${PROGNAME}.bin firmware after bootloader and save it as 'jgaurora_firmware.bin' def addboot(source, target, env): - firmware = open(target[0].path, "rb") - lengthfirmware = os.path.getsize(target[0].path) - bootloader_bin = "buildroot/share/PlatformIO/scripts/" + "jgaurora_bootloader.bin" - bootloader = open(bootloader_bin, "rb") - lengthbootloader = os.path.getsize(bootloader_bin) + from pathlib import Path + + fw_path = Path(target[0].path) + fwb_path = fw_path.parent / 'firmware_with_bootloader.bin' + with fwb_path.open("wb") as fwb_file: + bl_path = Path("buildroot/share/PlatformIO/scripts/jgaurora_bootloader.bin") + bl_file = bl_path.open("rb") + while True: + b = bl_file.read(1) + if b == b'': break + else: fwb_file.write(b) + + with fw_path.open("rb") as fw_file: + while True: + b = fw_file.read(1) + if b == b'': break + else: fwb_file.write(b) - firmware_with_boothloader_bin = target[0].dir.path + '/firmware_with_bootloader.bin' - if os.path.exists(firmware_with_boothloader_bin): - os.remove(firmware_with_boothloader_bin) - firmwareimage = open(firmware_with_boothloader_bin, "wb") - position = 0 - while position < lengthbootloader: - byte = bootloader.read(1) - firmwareimage.write(byte) - position += 1 - position = 0 - while position < lengthfirmware: - byte = firmware.read(1) - firmwareimage.write(byte) - position += 1 - bootloader.close() - firmware.close() - firmwareimage.close() + fws_path = Path(target[0].dir.path, 'firmware_for_sd_upload.bin') + if fws_path.exists(): + fws_path.unlink() - firmware_without_bootloader_bin = target[0].dir.path + '/firmware_for_sd_upload.bin' - if os.path.exists(firmware_without_bootloader_bin): - os.remove(firmware_without_bootloader_bin) - os.rename(target[0].path, firmware_without_bootloader_bin) - #os.rename(target[0].dir.path+'/firmware_with_bootloader.bin', target[0].dir.path+'/firmware.bin') + fw_path.rename(fws_path) + import marlin marlin.add_post_action(addboot); diff --git a/buildroot/share/PlatformIO/scripts/lerdge.py b/buildroot/share/PlatformIO/scripts/lerdge.py index 06e4543930..dc0c633139 100644 --- a/buildroot/share/PlatformIO/scripts/lerdge.py +++ b/buildroot/share/PlatformIO/scripts/lerdge.py @@ -8,10 +8,8 @@ import pioutil if pioutil.is_pio_build(): import os,marlin - Import("env") - from SCons.Script import DefaultEnvironment - board = DefaultEnvironment().BoardConfig() + board = marlin.env.BoardConfig() def encryptByte(byte): byte = 0xFF & ((byte << 6) | (byte >> 2)) diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index 580268c423..068d0331a8 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -2,21 +2,18 @@ # marlin.py # Helper module with some commonly-used functions # -import os,shutil +import shutil +from pathlib import Path from SCons.Script import DefaultEnvironment env = DefaultEnvironment() -from os.path import join - def copytree(src, dst, symlinks=False, ignore=None): - for item in os.listdir(src): - s = join(src, item) - d = join(dst, item) - if os.path.isdir(s): - shutil.copytree(s, d, symlinks, ignore) + for item in src.iterdir(): + if item.is_dir(): + shutil.copytree(item, dst / item.name, symlinks, ignore) else: - shutil.copy2(s, d) + shutil.copy2(item, dst / item.name) def replace_define(field, value): for define in env['CPPDEFINES']: @@ -34,7 +31,7 @@ def relocate_vtab(address): # Replace the existing -Wl,-T with the given ldscript path def custom_ld_script(ldname): - apath = os.path.abspath("buildroot/share/PlatformIO/ldscripts/" + ldname) + apath = str(Path("buildroot/share/PlatformIO/ldscripts", ldname).resolve()) for i, flag in enumerate(env["LINKFLAGS"]): if "-Wl,-T" in flag: env["LINKFLAGS"][i] = "-Wl,-T" + apath @@ -52,15 +49,15 @@ def encrypt_mks(source, target, env, new_name): mf = env["MARLIN_FEATURES"] if "FIRMWARE_BIN" in mf: new_name = mf["FIRMWARE_BIN"] - fwpath = target[0].path - fwfile = open(fwpath, "rb") - enfile = open(target[0].dir.path + "/" + new_name, "wb") - length = os.path.getsize(fwpath) + fwpath = Path(target[0].path) + fwfile = fwpath.open("rb") + enfile = Path(target[0].dir.path, new_name).open("wb") + length = fwpath.stat().st_size position = 0 try: while position < length: byte = fwfile.read(1) - if position >= 320 and position < 31040: + if 320 <= position < 31040: byte = chr(ord(byte) ^ key[position & 31]) if sys.version_info[0] > 2: byte = bytes(byte, 'latin1') @@ -69,7 +66,7 @@ def encrypt_mks(source, target, env, new_name): finally: fwfile.close() enfile.close() - os.remove(fwpath) + fwpath.unlink() def add_post_action(action): - env.AddPostAction(join("$BUILD_DIR", "${PROGNAME}.bin"), action); + env.AddPostAction(str(Path("$BUILD_DIR", "${PROGNAME}.bin")), action); diff --git a/buildroot/share/PlatformIO/scripts/offset_and_rename.py b/buildroot/share/PlatformIO/scripts/offset_and_rename.py index 6f44524619..10a34d9c73 100644 --- a/buildroot/share/PlatformIO/scripts/offset_and_rename.py +++ b/buildroot/share/PlatformIO/scripts/offset_and_rename.py @@ -10,12 +10,10 @@ # import pioutil if pioutil.is_pio_build(): - import os,sys,marlin - Import("env") - - from SCons.Script import DefaultEnvironment - board = DefaultEnvironment().BoardConfig() + import sys,marlin + env = marlin.env + board = env.BoardConfig() board_keys = board.get("build").keys() # @@ -56,7 +54,7 @@ if pioutil.is_pio_build(): if 'rename' in board_keys: def rename_target(source, target, env): - firmware = os.path.join(target[0].dir.path, board.get("build.rename")) - os.replace(target[0].path, firmware) + from pathlib import Path + Path(target[0].path).replace(Path(target[0].dir.path, board.get("build.rename"))) marlin.add_post_action(rename_target) diff --git a/buildroot/share/PlatformIO/scripts/preflight-checks.py b/buildroot/share/PlatformIO/scripts/preflight-checks.py index bbcf40e885..0fa9f9d6cc 100644 --- a/buildroot/share/PlatformIO/scripts/preflight-checks.py +++ b/buildroot/share/PlatformIO/scripts/preflight-checks.py @@ -6,10 +6,12 @@ import pioutil if pioutil.is_pio_build(): import os,re,sys + from pathlib import Path Import("env") def get_envs_for_board(board): - with open(os.path.join("Marlin", "src", "pins", "pins.h"), "r") as file: + ppath = Path("Marlin/src/pins/pins.h") + with ppath.open() as file: if sys.platform == 'win32': envregex = r"(?:env|win):" @@ -77,9 +79,10 @@ if pioutil.is_pio_build(): # # Check for Config files in two common incorrect places # - for p in [ env['PROJECT_DIR'], os.path.join(env['PROJECT_DIR'], "config") ]: - for f in [ "Configuration.h", "Configuration_adv.h" ]: - if os.path.isfile(os.path.join(p, f)): + epath = Path(env['PROJECT_DIR']) + for p in [ epath, epath / "config" ]: + for f in ("Configuration.h", "Configuration_adv.h"): + if (p / f).is_file(): err = "ERROR: Config files found in directory %s. Please move them into the Marlin subfolder." % p raise SystemExit(err) @@ -87,12 +90,12 @@ if pioutil.is_pio_build(): # Find the name.cpp.o or name.o and remove it # def rm_ofile(subdir, name): - build_dir = os.path.join(env['PROJECT_BUILD_DIR'], build_env); - for outdir in [ build_dir, os.path.join(build_dir, "debug") ]: - for ext in [ ".cpp.o", ".o" ]: - fpath = os.path.join(outdir, "src", "src", subdir, name + ext) - if os.path.exists(fpath): - os.remove(fpath) + build_dir = Path(env['PROJECT_BUILD_DIR'], build_env); + for outdir in (build_dir, build_dir / "debug"): + for ext in (".cpp.o", ".o"): + fpath = outdir / "src/src" / subdir / (name + ext) + if fpath.exists(): + fpath.unlink() # # Give warnings on every build @@ -109,13 +112,13 @@ if pioutil.is_pio_build(): # Check for old files indicating an entangled Marlin (mixing old and new code) # mixedin = [] - p = os.path.join(env['PROJECT_DIR'], "Marlin", "src", "lcd", "dogm") + p = Path(env['PROJECT_DIR'], "Marlin/src/lcd/dogm") for f in [ "ultralcd_DOGM.cpp", "ultralcd_DOGM.h" ]: - if os.path.isfile(os.path.join(p, f)): + if (p / f).is_file(): mixedin += [ f ] - p = os.path.join(env['PROJECT_DIR'], "Marlin", "src", "feature", "bedlevel", "abl") + p = Path(env['PROJECT_DIR'], "Marlin/src/feature/bedlevel/abl") for f in [ "abl.cpp", "abl.h" ]: - if os.path.isfile(os.path.join(p, f)): + if (p / f).is_file(): mixedin += [ f ] if mixedin: err = "ERROR: Old files fell into your Marlin folder. Remove %s and try again" % ", ".join(mixedin) diff --git a/buildroot/share/PlatformIO/scripts/preprocessor.py b/buildroot/share/PlatformIO/scripts/preprocessor.py index d0395cd481..19e8dfe0e1 100644 --- a/buildroot/share/PlatformIO/scripts/preprocessor.py +++ b/buildroot/share/PlatformIO/scripts/preprocessor.py @@ -1,7 +1,7 @@ # # preprocessor.py # -import subprocess,os,re +import subprocess,re nocache = 1 verbose = 0 @@ -54,51 +54,41 @@ def run_preprocessor(env, fn=None): # def search_compiler(env): - ENV_BUILD_PATH = os.path.join(env['PROJECT_BUILD_DIR'], env['PIOENV']) - GCC_PATH_CACHE = os.path.join(ENV_BUILD_PATH, ".gcc_path") + from pathlib import Path, PurePath + + ENV_BUILD_PATH = Path(env['PROJECT_BUILD_DIR'], env['PIOENV']) + GCC_PATH_CACHE = ENV_BUILD_PATH / ".gcc_path" try: - filepath = env.GetProjectOption('custom_gcc') + gccpath = env.GetProjectOption('custom_gcc') blab("Getting compiler from env") - return filepath + return gccpath except: pass # Warning: The cached .gcc_path will obscure a newly-installed toolkit - if not nocache and os.path.exists(GCC_PATH_CACHE): + if not nocache and GCC_PATH_CACHE.exists(): blab("Getting g++ path from cache") - with open(GCC_PATH_CACHE, 'r') as f: - return f.read() + return GCC_PATH_CACHE.read_text() - # Find the current platform compiler by searching the $PATH - # which will be in a platformio toolchain bin folder - path_regex = re.escape(env['PROJECT_PACKAGES_DIR']) - gcc = "g++" + # Use any item in $PATH corresponding to a platformio toolchain bin folder + path_separator = ':' + gcc_exe = '*g++' if env['PLATFORM'] == 'win32': path_separator = ';' - path_regex += r'.*\\bin' - gcc += ".exe" - else: - path_separator = ':' - path_regex += r'/.+/bin' - - # Search for the compiler - for pathdir in env['ENV']['PATH'].split(path_separator): - if not re.search(path_regex, pathdir, re.IGNORECASE): - continue - for filepath in os.listdir(pathdir): - if not filepath.endswith(gcc): - continue - # Use entire path to not rely on env PATH - filepath = os.path.sep.join([pathdir, filepath]) - # Cache the g++ path to no search always - if not nocache and os.path.exists(ENV_BUILD_PATH): - blab("Caching g++ for current env") - with open(GCC_PATH_CACHE, 'w+') as f: - f.write(filepath) - - return filepath - - filepath = env.get('CXX') - blab("Couldn't find a compiler! Fallback to %s" % filepath) - return filepath + gcc_exe += ".exe" + + # Search for the compiler in PATH + for ppath in map(Path, env['ENV']['PATH'].split(path_separator)): + if ppath.match(env['PROJECT_PACKAGES_DIR'] + "/**/bin"): + for gpath in ppath.glob(gcc_exe): + gccpath = str(gpath.resolve()) + # Cache the g++ path to no search always + if not nocache and ENV_BUILD_PATH.exists(): + blab("Caching g++ for current env") + GCC_PATH_CACHE.write_text(gccpath) + return gccpath + + gccpath = env.get('CXX') + blab("Couldn't find a compiler! Fallback to %s" % gccpath) + return gccpath diff --git a/buildroot/share/dwin/bin/DWIN_ICO.py b/buildroot/share/dwin/bin/DWIN_ICO.py index 8ac680c61e..3ddc734022 100644 --- a/buildroot/share/dwin/bin/DWIN_ICO.py +++ b/buildroot/share/dwin/bin/DWIN_ICO.py @@ -144,7 +144,7 @@ class DWIN_ICO_File(): # process each file: try: index = int(dirEntry.name[0:3]) - if (index < 0) or (index > 255): + if not (0 <= index <= 255): print('...Ignoring invalid index on', dirEntry.path) continue #dirEntry.path is iconDir/name diff --git a/buildroot/share/scripts/config-labels.py b/buildroot/share/scripts/config-labels.py index 700604e452..519f7b67ca 100755 --- a/buildroot/share/scripts/config-labels.py +++ b/buildroot/share/scripts/config-labels.py @@ -22,7 +22,7 @@ # 2020-06-05 SRL style tweaks #----------------------------------- # -import sys,os +import sys from pathlib import Path from distutils.dir_util import copy_tree # for copy_tree, because shutil.copytree can't handle existing files, dirs @@ -58,10 +58,10 @@ def process_file(subdir: str, filename: str): # Read file #------------------------ lines = [] - infilepath = os.path.join(input_examples_dir, subdir, filename) + infilepath = Path(input_examples_dir, subdir, filename) try: # UTF-8 because some files contain unicode chars - with open(infilepath, 'rt', encoding="utf-8") as infile: + with infilepath.open('rt', encoding="utf-8") as infile: lines = infile.readlines() except Exception as e: @@ -123,25 +123,24 @@ def process_file(subdir: str, filename: str): #------------------------- # Output file #------------------------- - outdir = os.path.join(output_examples_dir, subdir) - outfilepath = os.path.join(outdir, filename) + outdir = Path(output_examples_dir, subdir) + outfilepath = outdir / filename if file_modified: # Note: no need to create output dirs, as the initial copy_tree # will do that. - print(' writing ' + str(outfilepath)) + print(' writing ' + outfilepath) try: # Preserve unicode chars; Avoid CR-LF on Windows. - with open(outfilepath, "w", encoding="utf-8", newline='\n') as outfile: - outfile.write("\n".join(outlines)) - outfile.write("\n") + with outfilepath.open("w", encoding="utf-8", newline='\n') as outfile: + outfile.write("\n".join(outlines) + "\n") except Exception as e: print('Failed to write file: ' + str(e) ) raise Exception else: - print(' no change for ' + str(outfilepath)) + print(' no change for ' + outfilepath) #---------- def main(): @@ -159,8 +158,8 @@ def main(): output_examples_dir = output_examples_dir.strip() output_examples_dir = output_examples_dir.rstrip('\\/') - for dir in [input_examples_dir, output_examples_dir]: - if not (os.path.exists(dir)): + for dir in (input_examples_dir, output_examples_dir): + if not Path(dir).exists(): print('Directory not found: ' + dir) sys.exit(1) @@ -181,8 +180,7 @@ def main(): #----------------------------- # Find and process files #----------------------------- - len_input_examples_dir = len(input_examples_dir); - len_input_examples_dir += 1 + len_input_examples_dir = 1 + len(input_examples_dir) for filename in files_to_mod: input_path = Path(input_examples_dir) diff --git a/buildroot/share/vscode/auto_build.py b/buildroot/share/vscode/auto_build.py index 5bd769478e..31ef271551 100644 --- a/buildroot/share/vscode/auto_build.py +++ b/buildroot/share/vscode/auto_build.py @@ -252,7 +252,7 @@ def resolve_path(path): while 0 <= path.find('../'): end = path.find('../') - 1 start = path.find('/') - while 0 <= path.find('/', start) and end > path.find('/', start): + while 0 <= path.find('/', start) < end: start = path.find('/', start) + 1 path = path[0:start] + path[end + 4:] @@ -674,7 +674,7 @@ def line_print(line_input): if 0 == highlight[1]: found_1 = text.find(' ') found_tab = text.find('\t') - if found_1 < 0 or found_1 > found_tab: + if not (0 <= found_1 <= found_tab): found_1 = found_tab write_to_screen_queue(text[:found_1 + 1]) for highlight_2 in highlights: @@ -684,7 +684,7 @@ def line_print(line_input): if found >= 0: found_space = text.find(' ', found_1 + 1) found_tab = text.find('\t', found_1 + 1) - if found_space < 0 or found_space > found_tab: + if not (0 <= found_space <= found_tab): found_space = found_tab found_right = text.find(']', found + 1) write_to_screen_queue(text[found_1 + 1:found_space + 1], highlight[2]) @@ -701,7 +701,7 @@ def line_print(line_input): break if did_something == False: r_loc = text.find('\r') + 1 - if r_loc > 0 and r_loc < len(text): # need to split this line + if 0 < r_loc < len(text): # need to split this line text = text.split('\r') for line in text: if line != '': From 17794e18ae66793e0a4d6135de674d92e3d4b3d0 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Mon, 1 Aug 2022 18:17:57 +1200 Subject: [PATCH 39/54] =?UTF-8?q?=F0=9F=94=A7=20Update=20644p/1284p=20Seri?= =?UTF-8?q?al=201=20sanity=20check=20(#24575)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/inc/SanityCheck.h | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 1c1d8d4413..89425ca853 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -35,11 +35,19 @@ || X_STEP_PIN == N || Y_STEP_PIN == N || Z_STEP_PIN == N \ || X_DIR_PIN == N || Y_DIR_PIN == N || Z_DIR_PIN == N \ || X_ENA_PIN == N || Y_ENA_PIN == N || Z_ENA_PIN == N \ + || BTN_EN1 == N || BTN_EN2 == N \ ) -#if CONF_SERIAL_IS(0) // D0-D1. No known conflicts. +#if CONF_SERIAL_IS(0) + // D0-D1. No known conflicts. #endif -#if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(18) || CHECK_SERIAL_PIN(19)) - #error "Serial Port 1 pin D18 and/or D19 conflicts with another pin on the board." +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) + #if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(18) || CHECK_SERIAL_PIN(19)) + #error "Serial Port 1 pin D18 and/or D19 conflicts with another pin on the board." + #endif +#else + #if CONF_SERIAL_IS(1) && (CHECK_SERIAL_PIN(10) || CHECK_SERIAL_PIN(11)) + #error "Serial Port 1 pin D10 and/or D11 conflicts with another pin on the board." + #endif #endif #if CONF_SERIAL_IS(2) && (CHECK_SERIAL_PIN(16) || CHECK_SERIAL_PIN(17)) #error "Serial Port 2 pin D16 and/or D17 conflicts with another pin on the board." From 9a42d1e577a364d6f4491657d1eabb92f14ed55a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 Aug 2022 01:17:10 -0500 Subject: [PATCH 40/54] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20Malyan=20M300=20with?= =?UTF-8?q?=20S-Curve=20compile?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #24548 --- Marlin/src/module/stepper.cpp | 2 +- Marlin/src/pins/stm32f0/pins_MALYAN_M300.h | 11 +++++++---- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index cac2161a47..b759d97098 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1345,7 +1345,7 @@ void Stepper::set_directions() { } FORCE_INLINE int32_t Stepper::_eval_bezier_curve(const uint32_t curr_step) { - #if (defined(__arm__) || defined(__thumb__)) && !defined(STM32G0B1xx) // TODO: Test define STM32G0xx versus STM32G0B1xx + #if (defined(__arm__) || defined(__thumb__)) && __ARM_ARCH >= 6 && !defined(STM32G0B1xx) // TODO: Test define STM32G0xx versus STM32G0B1xx // For ARM Cortex M3/M4 CPUs, we have the optimized assembler version, that takes 43 cycles to execute uint32_t flo = 0; diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h index d38d4bbdb3..c55c63aa29 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h @@ -51,10 +51,13 @@ // // Limit Switches // -#define X_MAX_PIN PC13 -#define Y_MAX_PIN PC14 -#define Z_MAX_PIN PC15 -#define Z_MIN_PIN PB7 +#define X_STOP_PIN PC13 +#define Y_STOP_PIN PC14 +#define Z_STOP_PIN PC15 + +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB7 +#endif // // Steppers From bbf20332112948aad99bb8c7fba27fd661dc3a3a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 Aug 2022 02:38:15 -0500 Subject: [PATCH 41/54] =?UTF-8?q?=F0=9F=94=A7=20Config=20INI,=20dump=20opt?= =?UTF-8?q?ions=20(#24528)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 101 +++-- Marlin/Configuration_adv.h | 102 ++++- Marlin/config.ini | 211 +++++++++ Marlin/src/MarlinCore.cpp | 4 +- Marlin/src/core/macros.h | 5 + Marlin/src/gcode/temp/M303.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 53 +++ Marlin/src/inc/Conditionals_adv.h | 39 +- Marlin/src/inc/Conditionals_post.h | 12 +- Marlin/src/inc/SanityCheck.h | 8 +- Marlin/src/module/temperature.cpp | 37 +- Marlin/src/module/temperature.h | 4 +- .../share/PlatformIO/scripts/configuration.py | 239 +++++++++++ buildroot/share/PlatformIO/scripts/schema.py | 403 ++++++++++++++++++ .../share/PlatformIO/scripts/signature.py | 125 +++++- platformio.ini | 4 +- 16 files changed, 1249 insertions(+), 100 deletions(-) create mode 100644 Marlin/config.ini create mode 100644 buildroot/share/PlatformIO/scripts/configuration.py create mode 100755 buildroot/share/PlatformIO/scripts/schema.py diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 986e3c49ab..9259468374 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -112,6 +112,7 @@ * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] */ #define BAUDRATE 250000 + //#define BAUD_RATE_GCODE // Enable G-code M575 to set the baud rate /** @@ -120,7 +121,7 @@ * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7] */ //#define SERIAL_PORT_2 -1 -//#define BAUDRATE_2 250000 // Enable to override BAUDRATE +//#define BAUDRATE_2 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE /** * Select a third serial port on the board to use for communication with the host. @@ -128,7 +129,7 @@ * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] */ //#define SERIAL_PORT_3 1 -//#define BAUDRATE_3 250000 // Enable to override BAUDRATE +//#define BAUDRATE_3 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE // Enable the Bluetooth serial interface on AT90USB devices //#define BLUETOOTH @@ -387,7 +388,7 @@ //#define HOTEND_OFFSET_Y { 0.0, 5.00 } // (mm) relative Y-offset for each nozzle //#define HOTEND_OFFSET_Z { 0.0, 0.00 } // (mm) relative Z-offset for each nozzle -// @section machine +// @section psu control /** * Power Supply Control @@ -549,22 +550,32 @@ #define DUMMY_THERMISTOR_999_VALUE 100 // Resistor values when using MAX31865 sensors (-5) on TEMP_SENSOR_0 / 1 -//#define MAX31865_SENSOR_OHMS_0 100 // (Ω) Typically 100 or 1000 (PT100 or PT1000) -//#define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for Adafruit PT100; 4300 for Adafruit PT1000 -//#define MAX31865_SENSOR_OHMS_1 100 -//#define MAX31865_CALIBRATION_OHMS_1 430 +#if TEMP_SENSOR_IS_MAX_TC(0) + #define MAX31865_SENSOR_OHMS_0 100 // (Ω) Typically 100 or 1000 (PT100 or PT1000) + #define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for Adafruit PT100; 4300 for Adafruit PT1000 +#endif +#if TEMP_SENSOR_IS_MAX_TC(1) + #define MAX31865_SENSOR_OHMS_1 100 + #define MAX31865_CALIBRATION_OHMS_1 430 +#endif -#define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 -#define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer -#define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#if HAS_E_TEMP_SENSOR + #define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 + #define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer + #define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#endif -#define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190 -#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer -#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#if TEMP_SENSOR_BED + #define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190 + #define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer + #define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#endif -#define TEMP_CHAMBER_RESIDENCY_TIME 10 // (seconds) Time to wait for chamber to "settle" in M191 -#define TEMP_CHAMBER_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer -#define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#if TEMP_SENSOR_CHAMBER + #define TEMP_CHAMBER_RESIDENCY_TIME 10 // (seconds) Time to wait for chamber to "settle" in M191 + #define TEMP_CHAMBER_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer + #define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#endif /** * Redundant Temperature Sensor (TEMP_SENSOR_REDUNDANT) @@ -623,6 +634,8 @@ //============================= PID Settings ================================ //=========================================================================== +// @section hotend temp + // Enable PIDTEMP for PID control or MPCTEMP for Predictive Model. // temperature control. Disable both for bang-bang heating. #define PIDTEMP // See the PID Tuning Guide at https://reprap.org/wiki/PID_Tuning @@ -633,7 +646,8 @@ #define PID_K1 0.95 // Smoothing factor within any PID loop #if ENABLED(PIDTEMP) - //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) + //#define PID_DEBUG // Print PID debug data to the serial port. Use 'M303 D' to toggle activation. + //#define PID_PARAMS_PER_HOTEND // Use separate PID parameters for each extruder (useful for mismatched extruders) // Set/get with G-code: M301 E[extruder number, 0-2] #if ENABLED(PID_PARAMS_PER_HOTEND) @@ -655,6 +669,7 @@ * Use a physical model of the hotend to control temperature. When configured correctly * this gives better responsiveness and stability than PID and it also removes the need * for PID_EXTRUSION_SCALING and PID_FAN_SCALING. Use M306 T to autotune the model. + * @section mpctemp */ #if ENABLED(MPCTEMP) //#define MPC_EDIT_MENU // Add MPC editing to the "Advanced Settings" menu. (~1300 bytes of flash) @@ -707,6 +722,7 @@ * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W * heater. If your configuration is significantly different than this and you don't understand * the issues involved, don't use bed PID until someone else verifies that your hardware works. + * @section bed temp */ //#define PIDTEMPBED @@ -722,7 +738,7 @@ #if ENABLED(PIDTEMPBED) //#define MIN_BED_POWER 0 - //#define PID_BED_DEBUG // Sends debug data to the serial port. + //#define PID_BED_DEBUG // Print Bed PID debug data to the serial port. // 120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) // from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) @@ -750,6 +766,7 @@ * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 200W * heater. If your configuration is significantly different than this and you don't understand * the issues involved, don't use chamber PID until someone else verifies that your hardware works. + * @section chamber temp */ //#define PIDTEMPCHAMBER //#define CHAMBER_LIMIT_SWITCHING @@ -764,7 +781,7 @@ #if ENABLED(PIDTEMPCHAMBER) #define MIN_CHAMBER_POWER 0 - //#define PID_CHAMBER_DEBUG // Sends debug data to the serial port. + //#define PID_CHAMBER_DEBUG // Print Chamber PID debug data to the serial port. // Lasko "MyHeat Personal Heater" (200w) modified with a Fotek SSR-10DA to control only the heating element // and placed inside the small Creality printer enclosure tent. @@ -778,7 +795,6 @@ #endif // PIDTEMPCHAMBER #if ANY(PIDTEMP, PIDTEMPBED, PIDTEMPCHAMBER) - //#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation. //#define PID_OPENLOOP // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature @@ -788,7 +804,7 @@ //#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of flash) #endif -// @section extruder +// @section safety /** * Prevent extrusion if the temperature is below EXTRUDE_MINTEMP. @@ -856,6 +872,8 @@ #define POLAR_SEGMENTS_PER_SECOND 5 #endif +// @section delta + // Enable for DELTA kinematics and configure below //#define DELTA #if ENABLED(DELTA) @@ -915,6 +933,8 @@ //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } #endif +// @section scara + /** * MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013. * Implemented and slightly reworked by JCERNY in June, 2014. @@ -958,6 +978,8 @@ #endif +// @section tpara + // Enable for TPARA kinematics and configure below //#define AXEL_TPARA #if ENABLED(AXEL_TPARA) @@ -984,6 +1006,8 @@ #define PSI_HOMING_OFFSET 0 #endif +// @section machine + // Articulated robot (arm). Joints are directly mapped to axes with no kinematics. //#define ARTICULATED_ROBOT_ARM @@ -995,7 +1019,7 @@ //============================== Endstop Settings =========================== //=========================================================================== -// @section homing +// @section endstops // Specify here all the endstop connectors that are connected to any endstop or probe. // Almost all printers will be using one per axis. Probes will use one or more of the @@ -1659,7 +1683,7 @@ //#define V_HOME_DIR -1 //#define W_HOME_DIR -1 -// @section machine +// @section geometry // The size of the printable area #define X_BED_SIZE 200 @@ -2119,7 +2143,7 @@ //============================= Additional Features =========================== //============================================================================= -// @section extras +// @section eeprom /** * EEPROM @@ -2139,6 +2163,8 @@ //#define EEPROM_INIT_NOW // Init EEPROM on first boot after a new build. #endif +// @section host + // // Host Keepalive // @@ -2149,6 +2175,8 @@ #define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113. #define BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating +// @section units + // // G20/G21 Inch mode support // @@ -2176,6 +2204,8 @@ #define PREHEAT_2_TEMP_CHAMBER 35 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 +// @section motion + /** * Nozzle Park * @@ -2274,6 +2304,8 @@ #endif +// @section host + /** * Print Job Timer * @@ -2300,6 +2332,8 @@ */ #define PRINTJOB_TIMER_AUTOSTART +// @section stats + /** * Print Counter * @@ -2317,6 +2351,8 @@ #define PRINTCOUNTER_SAVE_INTERVAL 60 // (minutes) EEPROM save interval during print #endif +// @section security + /** * Password * @@ -2352,7 +2388,7 @@ //============================= LCD and SD support ============================ //============================================================================= -// @section lcd +// @section interface /** * LCD LANGUAGE @@ -2508,6 +2544,7 @@ //======================== LCD / Controller Selection ========================= //======================== (Character-based LCDs) ========================= //============================================================================= +// @section lcd // // RepRapDiscount Smart Controller. @@ -3142,7 +3179,7 @@ //=============================== Extra Features ============================== //============================================================================= -// @section extras +// @section fans // Set number of user-controlled fans. Disable to use all board-defined fans. // :[1,2,3,4,5,6,7,8] @@ -3166,14 +3203,18 @@ // duty cycle is attained. //#define SOFT_PWM_DITHER +// @section extras + +// Support for the BariCUDA Paste Extruder +//#define BARICUDA + +// @section lights + // Temperature status LEDs that display the hotend and bed temperature. // If all hotends, bed temperature, and target temperature are under 54C // then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis) //#define TEMP_STAT_LEDS -// Support for the BariCUDA Paste Extruder -//#define BARICUDA - // Support for BlinkM/CyzRgb //#define BLINKM @@ -3259,6 +3300,8 @@ #define PRINTER_EVENT_LEDS #endif +// @section servos + /** * Number of servos * diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 3d69cb3feb..b076949a88 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -32,6 +32,24 @@ */ #define CONFIGURATION_ADV_H_VERSION 02010100 +// @section develop + +/** + * Configuration Export + * + * Export the configuration as part of the build. (See signature.py) + * Output files are saved with the build (e.g., .pio/build/mega2560). + * + * See `build_all_examples --ini` as an example of config.ini archiving. + * + * 1 = marlin_config.json - Dictionary containing the configuration. + * This file is also generated for CONFIGURATION_EMBEDDING. + * 2 = config.ini - File format for PlatformIO preprocessing. + * 3 = schema.json - The entire configuration schema. (13 = pattern groups) + * 4 = schema.yml - The entire configuration schema. + */ +//#define CONFIG_EXPORT // :[1:'JSON', 2:'config.ini', 3:'schema.json', 4:'schema.yml'] + //=========================================================================== //============================= Thermal Settings ============================ //=========================================================================== @@ -2545,6 +2563,8 @@ #endif #endif // HAS_MULTI_EXTRUDER +// @section advanced pause + /** * Advanced Pause for Filament Change * - Adds the G-code M600 Filament Change to initiate a filament change. @@ -2603,13 +2623,12 @@ //#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302) #endif -// @section tmc - /** * TMC26X Stepper Driver options * * The TMC26XStepper library is required for this stepper driver. * https://github.com/trinamic/TMC26XStepper + * @section tmc/tmc26x */ #if HAS_DRIVER(TMC26X) @@ -2747,8 +2766,6 @@ #endif // TMC26X -// @section tmc_smart - /** * To use TMC2130, TMC2160, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode * connect your SPI pins to the hardware SPI interface on your board and define @@ -2764,6 +2781,7 @@ * * TMCStepper library is required to use TMC stepper drivers. * https://github.com/teemuatlut/TMCStepper + * @section tmc/config */ #if HAS_TRINAMIC_CONFIG @@ -2987,6 +3005,8 @@ //#define E7_HOLD_MULTIPLIER 0.5 #endif + // @section tmc/spi + /** * Override default SPI pins for TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160 drivers here. * The default pins can be found in your board's pins file. @@ -3024,6 +3044,8 @@ //#define TMC_SW_MISO -1 //#define TMC_SW_SCK -1 + // @section tmc/serial + /** * Four TMC2209 drivers can use the same HW/SW serial port with hardware configured addresses. * Set the address using jumpers on pins MS1 and MS2. @@ -3059,6 +3081,8 @@ //#define E6_SLAVE_ADDRESS 0 //#define E7_SLAVE_ADDRESS 0 + // @section tmc/smart + /** * Software enable * @@ -3067,6 +3091,8 @@ */ //#define SOFTWARE_DRIVER_ENABLE + // @section tmc/stealthchop + /** * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only * Use Trinamic's ultra quiet stepping mode. @@ -3121,6 +3147,8 @@ //#define CHOPPER_TIMING_E6 CHOPPER_TIMING_E //#define CHOPPER_TIMING_E7 CHOPPER_TIMING_E + // @section tmc/status + /** * Monitor Trinamic drivers * for error conditions like overtemperature and short to ground. @@ -3140,6 +3168,8 @@ #define STOP_ON_ERROR #endif + // @section tmc/hybrid + /** * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only * The driver will switch to spreadCycle when stepper speed is over HYBRID_THRESHOLD. @@ -3196,6 +3226,7 @@ * homing and adds a guard period for endstop triggering. * * Comment *_STALL_SENSITIVITY to disable sensorless homing for that axis. + * @section tmc/stallguard */ //#define SENSORLESS_HOMING // StallGuard capable drivers only @@ -3219,6 +3250,8 @@ //#define IMPROVE_HOMING_RELIABILITY #endif + // @section tmc/config + /** * TMC Homing stepper phase. * @@ -3258,7 +3291,6 @@ #endif // HAS_TRINAMIC_CONFIG - // @section i2cbus // @@ -3300,7 +3332,7 @@ #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave #endif -// @section extras +// @section photo /** * Photo G-code @@ -3343,6 +3375,8 @@ #endif #endif +// @section cnc + /** * Spindle & Laser control * @@ -3546,6 +3580,8 @@ #define COOLANT_FLOOD_INVERT false // Set "true" if the on/off function is reversed #endif +// @section filament width + /** * Filament Width Sensor * @@ -3579,6 +3615,8 @@ //#define FILAMENT_LCD_DISPLAY #endif +// @section power + /** * Power Monitor * Monitor voltage (V) and/or current (A), and -when possible- power (W) @@ -3602,6 +3640,8 @@ #define POWER_MONITOR_VOLTAGE_OFFSET 0 // Offset (in volts) applied to the calculated voltage #endif +// @section safety + /** * Stepper Driver Anti-SNAFU Protection * @@ -3611,6 +3651,8 @@ */ //#define DISABLE_DRIVER_SAFE_POWER_PROTECT +// @section cnc + /** * CNC Coordinate Systems * @@ -3619,6 +3661,8 @@ */ //#define CNC_COORDINATE_SYSTEMS +// @section reporting + /** * Auto-report fan speed with M123 S * Requires fans with tachometer pins @@ -3646,6 +3690,8 @@ //#define M115_GEOMETRY_REPORT #endif +// @section security + /** * Expected Printer Check * Add the M16 G-code to compare a string to the MACHINE_NAME. @@ -3653,6 +3699,8 @@ */ //#define EXPECTED_PRINTER_CHECK +// @section volumetrics + /** * Disable all Volumetric extrusion options */ @@ -3681,14 +3729,7 @@ #endif #endif -/** - * Enable this option for a leaner build of Marlin that removes all - * workspace offsets, simplifying coordinate transformations, leveling, etc. - * - * - M206 and M428 are disabled. - * - G92 will revert to its behavior from Marlin 1.0. - */ -//#define NO_WORKSPACE_OFFSETS +// @section reporting // Extra options for the M114 "Current Position" report //#define M114_DETAIL // Use 'M114` for details to check planner calculations @@ -3697,6 +3738,8 @@ //#define REPORT_FAN_CHANGE // Report the new fan speed when changed by M106 (and others) +// @section gcode + /** * Spend 28 bytes of SRAM to optimize the G-code parser */ @@ -3714,6 +3757,15 @@ //#define REPETIER_GCODE_M360 // Add commands originally from Repetier FW +/** + * Enable this option for a leaner build of Marlin that removes all + * workspace offsets, simplifying coordinate transformations, leveling, etc. + * + * - M206 and M428 are disabled. + * - G92 will revert to its behavior from Marlin 1.0. + */ +//#define NO_WORKSPACE_OFFSETS + /** * CNC G-code options * Support CNC-style G-code dialects used by laser cutters, drawing machine cams, etc. @@ -3729,6 +3781,8 @@ //#define VARIABLE_G0_FEEDRATE // The G0 feedrate is set by F in G0 motion mode #endif +// @section gcode + /** * Startup commands * @@ -3753,6 +3807,8 @@ * Up to 25 may be defined, but the actual number is LCD-dependent. */ +// @section custom main menu + // Custom Menu: Main Menu //#define CUSTOM_MENU_MAIN #if ENABLED(CUSTOM_MENU_MAIN) @@ -3783,6 +3839,8 @@ //#define MAIN_MENU_ITEM_5_CONFIRM #endif +// @section custom config menu + // Custom Menu: Configuration Menu //#define CUSTOM_MENU_CONFIG #if ENABLED(CUSTOM_MENU_CONFIG) @@ -3813,6 +3871,8 @@ //#define CONFIG_MENU_ITEM_5_CONFIRM #endif +// @section custom buttons + /** * User-defined buttons to run custom G-code. * Up to 25 may be defined. @@ -3844,6 +3904,8 @@ #endif #endif +// @section host + /** * Host Action Commands * @@ -3869,6 +3931,8 @@ //#define HOST_SHUTDOWN_MENU_ITEM // Add a menu item that tells the host to shut down #endif +// @section extras + /** * Cancel Objects * @@ -3890,6 +3954,7 @@ * Alternative Supplier: https://reliabuild3d.com/ * * Reliabuild encoders have been modified to improve reliability. + * @section i2c encoders */ //#define I2C_POSITION_ENCODERS @@ -3961,6 +4026,7 @@ /** * Analog Joystick(s) + * @section joystick */ //#define JOYSTICK #if ENABLED(JOYSTICK) @@ -3985,6 +4051,7 @@ * Modern replacement for the Prusa TMC_Z_CALIBRATION. * Adds capability to work with any adjustable current drivers. * Implemented as G34 because M915 is deprecated. + * @section calibrate */ //#define MECHANICAL_GANTRY_CALIBRATION #if ENABLED(MECHANICAL_GANTRY_CALIBRATION) @@ -4002,6 +4069,7 @@ /** * Instant freeze / unfreeze functionality * Potentially useful for emergency stop that allows being resumed. + * @section interface */ //#define FREEZE_FEATURE #if ENABLED(FREEZE_FEATURE) @@ -4014,6 +4082,7 @@ * * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display. * Requires 3 signal wires. Some useful debug options are included to demonstrate its usage. + * @section debug matrix */ //#define MAX7219_DEBUG #if ENABLED(MAX7219_DEBUG) @@ -4052,6 +4121,7 @@ * Support for Synchronized Z moves when used with NanoDLP. G0/G1 axis moves will * output a "Z_move_comp" string to enable synchronization with DLP projector exposure. * This feature allows you to use [[WaitForDoneMessage]] instead of M400 commands. + * @section nanodlp */ //#define NANODLP_Z_SYNC #if ENABLED(NANODLP_Z_SYNC) @@ -4060,6 +4130,7 @@ /** * Ethernet. Use M552 to enable and set the IP address. + * @section network */ #if HAS_ETHERNET #define MAC_ADDRESS { 0xDE, 0xAD, 0xBE, 0xEF, 0xF0, 0x0D } // A MAC address unique to your network @@ -4087,6 +4158,8 @@ //#include "Configuration_Secure.h" // External file with WiFi SSID / Password #endif +// @section multi-material + /** * Průša Multi-Material Unit (MMU) * Enable in Configuration.h @@ -4192,6 +4265,7 @@ /** * Advanced Print Counter settings + * @section stats */ #if ENABLED(PRINTCOUNTER) #define SERVICE_WARNING_BUZZES 3 diff --git a/Marlin/config.ini b/Marlin/config.ini new file mode 100644 index 0000000000..0fb9fb0c93 --- /dev/null +++ b/Marlin/config.ini @@ -0,0 +1,211 @@ +# +# Marlin Firmware +# config.ini - Options to apply before the build +# +[config:base] +ini_use_config = none + +# Load all config: sections in this file +;ini_use_config = all +# Load config file relative to Marlin/ +;ini_use_config = another.ini +# Download configurations from GitHub +;ini_use_config = example/Creality/Ender-5 Plus @ bugfix-2.1.x +# Download configurations from your server +;ini_use_config = https://me.myserver.com/path/to/configs +# Evaluate config:base and do a config dump +;ini_use_config = base +;config_export = 2 + +[config:minimal] +motherboard = BOARD_RAMPS_14_EFB +serial_port = 0 +baudrate = 250000 + +use_watchdog = on +thermal_protection_hotends = on +thermal_protection_hysteresis = 4 +thermal_protection_period = 40 + +bufsize = 4 +block_buffer_size = 16 +max_cmd_size = 96 + +extruders = 1 +temp_sensor_0 = 1 + +temp_hysteresis = 3 +heater_0_mintemp = 5 +heater_0_maxtemp = 275 +preheat_1_temp_hotend = 180 + +bang_max = 255 +pidtemp = on +pid_k1 = 0.95 +pid_max = BANG_MAX +pid_functional_range = 10 + +default_kp = 22.20 +default_ki = 1.08 +default_kd = 114.00 + +x_driver_type = A4988 +y_driver_type = A4988 +z_driver_type = A4988 +e0_driver_type = A4988 + +x_bed_size = 200 +x_min_pos = 0 +x_max_pos = X_BED_SIZE + +y_bed_size = 200 +y_min_pos = 0 +y_max_pos = Y_BED_SIZE + +z_min_pos = 0 +z_max_pos = 200 + +x_home_dir = -1 +y_home_dir = -1 +z_home_dir = -1 + +use_xmin_plug = on +use_ymin_plug = on +use_zmin_plug = on + +x_min_endstop_inverting = false +y_min_endstop_inverting = false +z_min_endstop_inverting = false + +default_axis_steps_per_unit = { 80, 80, 400, 500 } +axis_relative_modes = { false, false, false, false } +default_max_feedrate = { 300, 300, 5, 25 } +default_max_acceleration = { 3000, 3000, 100, 10000 } + +homing_feedrate_mm_m = { (50*60), (50*60), (4*60) } +homing_bump_divisor = { 2, 2, 4 } + +x_enable_on = 0 +y_enable_on = 0 +z_enable_on = 0 +e_enable_on = 0 + +invert_x_dir = false +invert_y_dir = true +invert_z_dir = false +invert_e0_dir = false + +invert_e_step_pin = false +invert_x_step_pin = false +invert_y_step_pin = false +invert_z_step_pin = false + +disable_x = false +disable_y = false +disable_z = false +disable_e = false + +proportional_font_ratio = 1.0 +default_nominal_filament_dia = 1.75 + +junction_deviation_mm = 0.013 + +default_acceleration = 3000 +default_travel_acceleration = 3000 +default_retract_acceleration = 3000 + +default_minimumfeedrate = 0.0 +default_mintravelfeedrate = 0.0 + +minimum_planner_speed = 0.05 +min_steps_per_segment = 6 +default_minsegmenttime = 20000 + +[config:basic] +bed_overshoot = 10 +busy_while_heating = on +default_ejerk = 5.0 +default_keepalive_interval = 2 +default_leveling_fade_height = 0.0 +disable_inactive_extruder = on +display_charset_hd44780 = JAPANESE +eeprom_boot_silent = on +eeprom_chitchat = on +endstoppullups = on +extrude_maxlength = 200 +extrude_mintemp = 170 +host_keepalive_feature = on +hotend_overshoot = 15 +jd_handle_small_segments = on +lcd_info_screen_style = 0 +lcd_language = en +max_bed_power = 255 +mesh_inset = 0 +min_software_endstops = on +max_software_endstops = on +min_software_endstop_x = on +min_software_endstop_y = on +min_software_endstop_z = on +max_software_endstop_x = on +max_software_endstop_y = on +max_software_endstop_z = on +preheat_1_fan_speed = 0 +preheat_1_label = "PLA" +preheat_1_temp_bed = 70 +prevent_cold_extrusion = on +prevent_lengthy_extrude = on +printjob_timer_autostart = on +probing_margin = 10 +show_bootscreen = on +soft_pwm_scale = 0 +string_config_h_author = "(none, default config)" +temp_bed_hysteresis = 3 +temp_bed_residency_time = 10 +temp_bed_window = 1 +temp_residency_time = 10 +temp_window = 1 +validate_homing_endstops = on +xy_probe_feedrate = (133*60) +z_clearance_between_probes = 5 +z_clearance_deploy_probe = 10 +z_clearance_multi_probe = 5 + +[config:advanced] +arc_support = on +auto_report_temperatures = on +autotemp = on +autotemp_oldweight = 0.98 +bed_check_interval = 5000 +default_stepper_deactive_time = 120 +default_volumetric_extruder_limit = 0.00 +disable_inactive_e = true +disable_inactive_x = true +disable_inactive_y = true +disable_inactive_z = true +e0_auto_fan_pin = -1 +encoder_100x_steps_per_sec = 80 +encoder_10x_steps_per_sec = 30 +encoder_rate_multiplier = on +extended_capabilities_report = on +extruder_auto_fan_speed = 255 +extruder_auto_fan_temperature = 50 +fanmux0_pin = -1 +fanmux1_pin = -1 +fanmux2_pin = -1 +faster_gcode_parser = on +homing_bump_mm = { 5, 5, 2 } +max_arc_segment_mm = 1.0 +min_arc_segment_mm = 0.1 +min_circle_segments = 72 +n_arc_correction = 25 +serial_overrun_protection = on +slowdown = on +slowdown_divisor = 2 +temp_sensor_bed = 0 +thermal_protection_bed_hysteresis = 2 +thermocouple_max_errors = 15 +tx_buffer_size = 0 +watch_bed_temp_increase = 2 +watch_bed_temp_period = 60 +watch_temp_increase = 2 +watch_temp_period = 20 diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 37918f619f..31b6184317 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1220,10 +1220,10 @@ void setup() { SETUP_RUN(hal.init()); // Init and disable SPI thermocouples; this is still needed - #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0)) + #if TEMP_SENSOR_IS_MAX_TC(0) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E0)) OUT_WRITE(TEMP_0_CS_PIN, HIGH); // Disable #endif - #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1)) + #if TEMP_SENSOR_IS_MAX_TC(1) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1)) OUT_WRITE(TEMP_1_CS_PIN, HIGH); #endif diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 09a6164568..ddcf27b2b8 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -730,3 +730,8 @@ #define __MAPLIST() _MAPLIST #define MAPLIST(OP,V...) EVAL(_MAPLIST(OP,V)) + +// Temperature Sensor Config +#define _HAS_E_TEMP(N) || (TEMP_SENSOR_##N != 0) +#define HAS_E_TEMP_SENSOR (0 REPEAT(EXTRUDERS, _HAS_E_TEMP)) +#define TEMP_SENSOR_IS_MAX_TC(T) (TEMP_SENSOR_##T == -5 || TEMP_SENSOR_##T == -3 || TEMP_SENSOR_##T == -2) diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index ce362984a6..a4d514c733 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -48,7 +48,7 @@ void GcodeSuite::M303() { - #if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) + #if HAS_PID_DEBUG if (parser.seen_test('D')) { thermalManager.pid_debug_flag ^= true; SERIAL_ECHO_START(); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 0873c1f525..a6be04e237 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -668,6 +668,31 @@ #define E_MANUAL EXTRUDERS #endif +#if E_STEPPERS <= 7 + #undef INVERT_E7_DIR + #if E_STEPPERS <= 6 + #undef INVERT_E6_DIR + #if E_STEPPERS <= 5 + #undef INVERT_E5_DIR + #if E_STEPPERS <= 4 + #undef INVERT_E4_DIR + #if E_STEPPERS <= 3 + #undef INVERT_E3_DIR + #if E_STEPPERS <= 2 + #undef INVERT_E2_DIR + #if E_STEPPERS <= 1 + #undef INVERT_E1_DIR + #if E_STEPPERS == 0 + #undef INVERT_E0_DIR + #endif + #endif + #endif + #endif + #endif + #endif + #endif +#endif + /** * Number of Linear Axes (e.g., XYZIJKUVW) * All the logical axes except for the tool (E) axis @@ -768,6 +793,9 @@ #undef Y_MIN_POS #undef Y_MAX_POS #undef MANUAL_Y_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_Y + #undef MAX_SOFTWARE_ENDSTOP_Y + #undef SAFE_BED_LEVELING_START_Y #endif #if !HAS_Z_AXIS @@ -785,6 +813,9 @@ #undef Z_MIN_POS #undef Z_MAX_POS #undef MANUAL_Z_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_Z + #undef MAX_SOFTWARE_ENDSTOP_Z + #undef SAFE_BED_LEVELING_START_Z #endif #if !HAS_I_AXIS @@ -799,6 +830,9 @@ #undef I_MIN_POS #undef I_MAX_POS #undef MANUAL_I_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_I + #undef MAX_SOFTWARE_ENDSTOP_I + #undef SAFE_BED_LEVELING_START_I #endif #if !HAS_J_AXIS @@ -813,6 +847,9 @@ #undef J_MIN_POS #undef J_MAX_POS #undef MANUAL_J_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_J + #undef MAX_SOFTWARE_ENDSTOP_J + #undef SAFE_BED_LEVELING_START_J #endif #if !HAS_K_AXIS @@ -827,6 +864,9 @@ #undef K_MIN_POS #undef K_MAX_POS #undef MANUAL_K_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_K + #undef MAX_SOFTWARE_ENDSTOP_K + #undef SAFE_BED_LEVELING_START_K #endif #if !HAS_U_AXIS @@ -841,6 +881,9 @@ #undef U_MIN_POS #undef U_MAX_POS #undef MANUAL_U_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_U + #undef MAX_SOFTWARE_ENDSTOP_U + #undef SAFE_BED_LEVELING_START_U #endif #if !HAS_V_AXIS @@ -855,6 +898,9 @@ #undef V_MIN_POS #undef V_MAX_POS #undef MANUAL_V_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_V + #undef MAX_SOFTWARE_ENDSTOP_V + #undef SAFE_BED_LEVELING_START_V #endif #if !HAS_W_AXIS @@ -869,6 +915,9 @@ #undef W_MIN_POS #undef W_MAX_POS #undef MANUAL_W_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_W + #undef MAX_SOFTWARE_ENDSTOP_W + #undef SAFE_BED_LEVELING_START_W #endif #ifdef X2_DRIVER_TYPE @@ -1398,6 +1447,10 @@ #define EXTRUDE_MINTEMP 170 #endif +#if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) + #define HAS_PID_DEBUG 1 +#endif + /** * TFT Displays * diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 49a1d7ef9c..21bc424f59 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -116,6 +116,31 @@ #undef STEALTHCHOP_E #endif +#if HOTENDS <= 7 + #undef E7_AUTO_FAN_PIN + #if HOTENDS <= 6 + #undef E6_AUTO_FAN_PIN + #if HOTENDS <= 5 + #undef E5_AUTO_FAN_PIN + #if HOTENDS <= 4 + #undef E4_AUTO_FAN_PIN + #if HOTENDS <= 3 + #undef E3_AUTO_FAN_PIN + #if HOTENDS <= 2 + #undef E2_AUTO_FAN_PIN + #if HOTENDS <= 1 + #undef E1_AUTO_FAN_PIN + #if HOTENDS == 0 + #undef E0_AUTO_FAN_PIN + #endif + #endif + #endif + #endif + #endif + #endif + #endif +#endif + /** * Temperature Sensors; define what sensor(s) we have. */ @@ -154,8 +179,7 @@ #define REDUNDANT_TEMP_MATCH(...) 0 #endif -#if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2 - #define TEMP_SENSOR_0_IS_MAX_TC 1 +#if TEMP_SENSOR_IS_MAX_TC(0) #if TEMP_SENSOR_0 == -5 #define TEMP_SENSOR_0_IS_MAX31865 1 #define TEMP_SENSOR_0_MAX_TC_TMIN 0 @@ -191,8 +215,7 @@ #undef HEATER_0_MAXTEMP #endif -#if TEMP_SENSOR_1 == -5 || TEMP_SENSOR_1 == -3 || TEMP_SENSOR_1 == -2 - #define TEMP_SENSOR_1_IS_MAX_TC 1 +#if TEMP_SENSOR_IS_MAX_TC(1) #if TEMP_SENSOR_1 == -5 #define TEMP_SENSOR_1_IS_MAX31865 1 #define TEMP_SENSOR_1_MAX_TC_TMIN 0 @@ -238,9 +261,7 @@ #undef HEATER_1_MAXTEMP #endif -#if TEMP_SENSOR_REDUNDANT == -5 || TEMP_SENSOR_REDUNDANT == -3 || TEMP_SENSOR_REDUNDANT == -2 - #define TEMP_SENSOR_REDUNDANT_IS_MAX_TC 1 - +#if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) #if TEMP_SENSOR_REDUNDANT == -5 #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." @@ -282,7 +303,7 @@ #endif #endif - #if (TEMP_SENSOR_0_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_1_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) + #if (TEMP_SENSOR_IS_MAX_TC(0) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_IS_MAX_TC(1) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) #if TEMP_SENSOR_REDUNDANT == -5 #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." #elif TEMP_SENSOR_REDUNDANT == -3 @@ -304,7 +325,7 @@ #endif #endif -#if TEMP_SENSOR_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC || TEMP_SENSOR_REDUNDANT_IS_MAX_TC +#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(REDUNDANT) #define HAS_MAX_TC 1 #endif #if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 1c67a43ed4..650c420532 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -681,7 +681,7 @@ #if HAS_MAX_TC // Translate old _SS, _CS, _SCK, _DO, _DI, _MISO, and _MOSI PIN defines. - #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1)) + #if TEMP_SENSOR_IS_MAX_TC(0) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1)) #if !PIN_EXISTS(TEMP_0_CS) // SS, CS #if PIN_EXISTS(MAX6675_SS) @@ -748,9 +748,9 @@ #endif #endif - #endif // TEMP_SENSOR_0_IS_MAX_TC + #endif // TEMP_SENSOR_IS_MAX_TC(0) - #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1)) + #if TEMP_SENSOR_IS_MAX_TC(1) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1)) #if !PIN_EXISTS(TEMP_1_CS) // SS2, CS2 #if PIN_EXISTS(MAX6675_SS2) @@ -817,7 +817,7 @@ #endif #endif - #endif // TEMP_SENSOR_1_IS_MAX_TC + #endif // TEMP_SENSOR_IS_MAX_TC(1) // // User-defined thermocouple libraries @@ -2656,7 +2656,7 @@ // // ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface) // -#define HAS_ADC_TEST(P) (PIN_EXISTS(TEMP_##P) && TEMP_SENSOR_##P != 0 && NONE(TEMP_SENSOR_##P##_IS_MAX_TC, TEMP_SENSOR_##P##_IS_DUMMY)) +#define HAS_ADC_TEST(P) (PIN_EXISTS(TEMP_##P) && TEMP_SENSOR_##P != 0 && !TEMP_SENSOR_IS_MAX_TC(P) && !TEMP_SENSOR_##P##_IS_DUMMY) #if HOTENDS > 0 && HAS_ADC_TEST(0) #define HAS_TEMP_ADC_0 1 #endif @@ -2700,7 +2700,7 @@ #define HAS_TEMP_ADC_REDUNDANT 1 #endif -#define HAS_TEMP(N) ANY(HAS_TEMP_ADC_##N, TEMP_SENSOR_##N##_IS_MAX_TC, TEMP_SENSOR_##N##_IS_DUMMY) +#define HAS_TEMP(N) (TEMP_SENSOR_IS_MAX_TC(N) || EITHER(HAS_TEMP_ADC_##N, TEMP_SENSOR_##N##_IS_DUMMY)) #if HAS_HOTEND && HAS_TEMP(0) #define HAS_TEMP_HOTEND 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ed223cb6ec..234f850cdb 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2328,9 +2328,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TEMP_SENSOR_REDUNDANT_TARGET can't be COOLER without TEMP_COOLER_PIN defined." #endif - #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0) && !PIN_EXISTS(TEMP_0_CS) + #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E0) && !PIN_EXISTS(TEMP_0_CS) #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE E0 requires TEMP_0_CS_PIN." - #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1) && !PIN_EXISTS(TEMP_1_CS) + #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1) && !PIN_EXISTS(TEMP_1_CS) #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE E1 requires TEMP_1_CS_PIN." #endif #endif @@ -2343,7 +2343,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TEMP_0_PIN or TEMP_0_CS_PIN not defined for this board." #elif HAS_EXTRUDERS && !HAS_HEATER_0 #error "HEATER_0_PIN not defined for this board." -#elif TEMP_SENSOR_0_IS_MAX_TC && !PIN_EXISTS(TEMP_0_CS) +#elif TEMP_SENSOR_IS_MAX_TC(0) && !PIN_EXISTS(TEMP_0_CS) #error "TEMP_SENSOR_0 MAX thermocouple requires TEMP_0_CS_PIN." #elif HAS_HOTEND && !HAS_TEMP_HOTEND && !TEMP_SENSOR_0_IS_DUMMY #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." @@ -2352,7 +2352,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #if HAS_MULTI_HOTEND - #if TEMP_SENSOR_1_IS_MAX_TC && !PIN_EXISTS(TEMP_1_CS) + #if TEMP_SENSOR_IS_MAX_TC(1) && !PIN_EXISTS(TEMP_1_CS) #error "TEMP_SENSOR_1 MAX thermocouple requires TEMP_1_CS_PIN." #elif TEMP_SENSOR_1 == 0 #error "TEMP_SENSOR_1 is required with 2 or more HOTENDS." diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 56eceea39d..ecd95b5e8f 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -77,7 +77,7 @@ // MAX TC related macros #define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_MAX##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX##M) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) -#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) +#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (TEMP_SENSOR_IS_MAX_TC(n) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) // LIB_MAX6675 can be added to the build_flags in platformio.ini to use a user-defined library // If LIB_MAX6675 is not on the build_flags then raw SPI reads will be used. @@ -1317,8 +1317,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { _temp_error(heater_id, F(STR_T_MINTEMP), GET_TEXT_F(MSG_ERR_MINTEMP)); } -#if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) - #define HAS_PID_DEBUG 1 +#if HAS_PID_DEBUG bool Temperature::pid_debug_flag; // = false #endif @@ -1856,15 +1855,15 @@ void Temperature::task() { if (!updateTemperaturesIfReady()) return; // Will also reset the watchdog if temperatures are ready #if DISABLED(IGNORE_THERMOCOUPLE_ERRORS) - #if TEMP_SENSOR_0_IS_MAX_TC + #if TEMP_SENSOR_IS_MAX_TC(0) if (degHotend(0) > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.0)) max_temp_error(H_E0); if (degHotend(0) < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + .01)) min_temp_error(H_E0); #endif - #if TEMP_SENSOR_1_IS_MAX_TC + #if TEMP_SENSOR_IS_MAX_TC(1) if (degHotend(1) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) max_temp_error(H_E1); if (degHotend(1) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) min_temp_error(H_E1); #endif - #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC + #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) max_temp_error(H_REDUNDANT); if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) min_temp_error(H_REDUNDANT); #endif @@ -2072,7 +2071,7 @@ void Temperature::task() { case 0: #if TEMP_SENSOR_0_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_0, raw); - #elif TEMP_SENSOR_0_IS_MAX_TC + #elif TEMP_SENSOR_IS_MAX_TC(0) #if TEMP_SENSOR_0_IS_MAX31865 return TERN(LIB_INTERNAL_MAX31865, max31865_0.temperature(raw), @@ -2091,7 +2090,7 @@ void Temperature::task() { case 1: #if TEMP_SENSOR_1_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_1, raw); - #elif TEMP_SENSOR_1_IS_MAX_TC + #elif TEMP_SENSOR_IS_MAX_TC(1) #if TEMP_SENSOR_0_IS_MAX31865 return TERN(LIB_INTERNAL_MAX31865, max31865_1.temperature(raw), @@ -2275,9 +2274,9 @@ void Temperature::task() { celsius_float_t Temperature::analog_to_celsius_redundant(const raw_adc_t raw) { #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM return user_thermistor_to_deg_c(CTI_REDUNDANT, raw); - #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0) + #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E0) return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(raw), (int16_t)raw * 0.25); - #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1) + #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1) return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(raw), (int16_t)raw * 0.25); #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); @@ -2308,9 +2307,15 @@ void Temperature::updateTemperaturesFromRawValues() { hal.watchdog_refresh(); // Reset because raw_temps_ready was set by the interrupt - TERN_(TEMP_SENSOR_0_IS_MAX_TC, temp_hotend[0].setraw(READ_MAX_TC(0))); - TERN_(TEMP_SENSOR_1_IS_MAX_TC, temp_hotend[1].setraw(READ_MAX_TC(1))); - TERN_(TEMP_SENSOR_REDUNDANT_IS_MAX_TC, temp_redundant.setraw(READ_MAX_TC(HEATER_ID(TEMP_SENSOR_REDUNDANT_SOURCE)))); + #if TEMP_SENSOR_IS_MAX_TC(0) + temp_hotend[0].setraw(READ_MAX_TC(0)); + #endif + #if TEMP_SENSOR_IS_MAX_TC(1) + temp_hotend[1].setraw(READ_MAX_TC(1)); + #endif + #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) + temp_redundant.setraw(READ_MAX_TC(HEATER_ID(TEMP_SENSOR_REDUNDANT_SOURCE))); + #endif #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].getraw(), e); @@ -3139,15 +3144,15 @@ void Temperature::disable_all_heaters() { void Temperature::update_raw_temperatures() { // TODO: can this be collapsed into a HOTEND_LOOP()? - #if HAS_TEMP_ADC_0 && !TEMP_SENSOR_0_IS_MAX_TC + #if HAS_TEMP_ADC_0 && !TEMP_SENSOR_IS_MAX_TC(0) temp_hotend[0].update(); #endif - #if HAS_TEMP_ADC_1 && !TEMP_SENSOR_1_IS_MAX_TC + #if HAS_TEMP_ADC_1 && !TEMP_SENSOR_IS_MAX_TC(1) temp_hotend[1].update(); #endif - #if HAS_TEMP_ADC_REDUNDANT && !TEMP_SENSOR_REDUNDANT_IS_MAX_TC + #if HAS_TEMP_ADC_REDUNDANT && !TEMP_SENSOR_IS_MAX_TC(REDUNDANT) temp_redundant.update(); #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index feec318050..f6cf81b8a9 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -953,7 +953,7 @@ class Temperature { */ #if HAS_PID_HEATING - #if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG) + #if HAS_PID_DEBUG static bool pid_debug_flag; #endif @@ -1035,7 +1035,7 @@ class Temperature { // MAX Thermocouples #if HAS_MAX_TC - #define MAX_TC_COUNT COUNT_ENABLED(TEMP_SENSOR_0_IS_MAX_TC, TEMP_SENSOR_1_IS_MAX_TC, TEMP_SENSOR_REDUNDANT_IS_MAX_TC) + #define MAX_TC_COUNT TEMP_SENSOR_IS_MAX_TC(0) + TEMP_SENSOR_IS_MAX_TC(1) + TEMP_SENSOR_IS_MAX_TC(REDUNDANT) #if MAX_TC_COUNT > 1 #define HAS_MULTI_MAX_TC 1 #define READ_MAX_TC(N) read_max_tc(N) diff --git a/buildroot/share/PlatformIO/scripts/configuration.py b/buildroot/share/PlatformIO/scripts/configuration.py new file mode 100644 index 0000000000..3ab0295749 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/configuration.py @@ -0,0 +1,239 @@ +# +# configuration.py +# Apply options from config.ini to the existing Configuration headers +# +import re, shutil, configparser +from pathlib import Path + +verbose = 0 +def blab(str,level=1): + if verbose >= level: print(f"[config] {str}") + +def config_path(cpath): + return Path("Marlin", cpath) + +# Apply a single name = on/off ; name = value ; etc. +# TODO: Limit to the given (optional) configuration +def apply_opt(name, val, conf=None): + if name == "lcd": name, val = val, "on" + + # Create a regex to match the option and capture parts of the line + regex = re.compile(rf'^(\s*)(//\s*)?(#define\s+)({name}\b)(\s*)(.*?)(\s*)(//.*)?$', re.IGNORECASE) + + # Find and enable and/or update all matches + for file in ("Configuration.h", "Configuration_adv.h"): + fullpath = config_path(file) + lines = fullpath.read_text().split('\n') + found = False + for i in range(len(lines)): + line = lines[i] + match = regex.match(line) + if match and match[4].upper() == name.upper(): + found = True + # For boolean options un/comment the define + if val in ("on", "", None): + newline = re.sub(r'^(\s*)//+\s*(#define)(\s{1,3})?(\s*)', r'\1\2 \4', line) + elif val == "off": + newline = re.sub(r'^(\s*)(#define)(\s{1,3})?(\s*)', r'\1//\2 \4', line) + else: + # For options with values, enable and set the value + newline = match[1] + match[3] + match[4] + match[5] + val + if match[8]: + sp = match[7] if match[7] else ' ' + newline += sp + match[8] + lines[i] = newline + blab(f"Set {name} to {val}") + + # If the option was found, write the modified lines + if found: + fullpath.write_text('\n'.join(lines)) + break + + # If the option didn't appear in either config file, add it + if not found: + # OFF options are added as disabled items so they appear + # in config dumps. Useful for custom settings. + prefix = "" + if val == "off": + prefix, val = "//", "" # Item doesn't appear in config dump + #val = "false" # Item appears in config dump + + # Uppercase the option unless already mixed/uppercase + added = name.upper() if name.islower() else name + + # Add the provided value after the name + if val != "on" and val != "" and val is not None: + added += " " + val + + # Prepend the new option after the first set of #define lines + fullpath = config_path("Configuration.h") + with fullpath.open() as f: + lines = f.readlines() + linenum = 0 + gotdef = False + for line in lines: + isdef = line.startswith("#define") + if not gotdef: + gotdef = isdef + elif not isdef: + break + linenum += 1 + lines.insert(linenum, f"{prefix}#define {added} // Added by config.ini\n") + fullpath.write_text('\n'.join(lines)) + +# Fetch configuration files from GitHub given the path. +# Return True if any files were fetched. +def fetch_example(path): + if path.endswith("/"): + path = path[:-1] + + if '@' in path: + path, brch = map(strip, path.split('@')) + + url = path.replace("%", "%25").replace(" ", "%20") + if not path.startswith('http'): + url = "https://raw.githubusercontent.com/MarlinFirmware/Configurations/bugfix-2.1.x/config/%s" % url + + # Find a suitable fetch command + if shutil.which("curl") is not None: + fetch = "curl -L -s -S -f -o" + elif shutil.which("wget") is not None: + fetch = "wget -q -O" + else: + blab("Couldn't find curl or wget", -1) + return False + + import os + + # Reset configurations to default + os.system("git reset --hard HEAD") + + gotfile = False + + # Try to fetch the remote files + for fn in ("Configuration.h", "Configuration_adv.h", "_Bootscreen.h", "_Statusscreen.h"): + if os.system("%s wgot %s/%s >/dev/null 2>&1" % (fetch, url, fn)) == 0: + shutil.move('wgot', config_path(fn)) + gotfile = True + + if Path('wgot').exists(): + shutil.rmtree('wgot') + + return gotfile + +def section_items(cp, sectkey): + return cp.items(sectkey) if sectkey in cp.sections() else [] + +# Apply all items from a config section +def apply_ini_by_name(cp, sect): + iniok = True + if sect in ('config:base', 'config:root'): + iniok = False + items = section_items(cp, 'config:base') + section_items(cp, 'config:root') + else: + items = cp.items(sect) + + for item in items: + if iniok or not item[0].startswith('ini_'): + apply_opt(item[0], item[1]) + +# Apply all config sections from a parsed file +def apply_all_sections(cp): + for sect in cp.sections(): + if sect.startswith('config:'): + apply_ini_by_name(cp, sect) + +# Apply certain config sections from a parsed file +def apply_sections(cp, ckey='all', addbase=False): + blab("[config] apply section key: %s" % ckey) + if ckey == 'all': + apply_all_sections(cp) + else: + # Apply the base/root config.ini settings after external files are done + if addbase or ckey in ('base', 'root'): + apply_ini_by_name(cp, 'config:base') + + # Apply historically 'Configuration.h' settings everywhere + if ckey == 'basic': + apply_ini_by_name(cp, 'config:basic') + + # Apply historically Configuration_adv.h settings everywhere + # (Some of which rely on defines in 'Conditionals_LCD.h') + elif ckey in ('adv', 'advanced'): + apply_ini_by_name(cp, 'config:advanced') + + # Apply a specific config: section directly + elif ckey.startswith('config:'): + apply_ini_by_name(cp, ckey) + +# Apply settings from a top level config.ini +def apply_config_ini(cp): + blab("=" * 20 + " Gather 'config.ini' entries...") + + # Pre-scan for ini_use_config to get config_keys + base_items = section_items(cp, 'config:base') + section_items(cp, 'config:root') + config_keys = ['base'] + for ikey, ival in base_items: + if ikey == 'ini_use_config': + config_keys = [ x.strip() for x in ival.split(',') ] + + # For each ini_use_config item perform an action + for ckey in config_keys: + addbase = False + + # For a key ending in .ini load and parse another .ini file + if ckey.endswith('.ini'): + sect = 'base' + if '@' in ckey: sect, ckey = ckey.split('@') + other_ini = configparser.ConfigParser() + other_ini.read(config_path(ckey)) + apply_sections(other_ini, sect) + + # (Allow 'example/' as a shortcut for 'examples/') + elif ckey.startswith('example/'): + ckey = 'examples' + ckey[7:] + + # For 'examples/' fetch an example set from GitHub. + # For https?:// do a direct fetch of the URL. + elif ckey.startswith('examples/') or ckey.startswith('http'): + addbase = True + fetch_example(ckey) + + # Apply keyed sections after external files are done + apply_sections(cp, 'config:' + ckey, addbase) + +if __name__ == "__main__": + # + # From command line use the given file name + # + import sys + args = sys.argv[1:] + if len(args) > 0: + if args[0].endswith('.ini'): + ini_file = args[0] + else: + print("Usage: %s <.ini file>" % sys.argv[0]) + else: + ini_file = config_path('config.ini') + + if ini_file: + user_ini = configparser.ConfigParser() + user_ini.read(ini_file) + apply_config_ini(user_ini) + +else: + # + # From within PlatformIO use the loaded INI file + # + import pioutil + if pioutil.is_pio_build(): + + Import("env") + + try: + verbose = int(env.GetProjectOption('custom_verbose')) + except: + pass + + from platformio.project.config import ProjectConfig + apply_config_ini(ProjectConfig()) diff --git a/buildroot/share/PlatformIO/scripts/schema.py b/buildroot/share/PlatformIO/scripts/schema.py new file mode 100755 index 0000000000..767748757e --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/schema.py @@ -0,0 +1,403 @@ +#!/usr/bin/env python3 +# +# schema.py +# +# Used by signature.py via common-dependencies.py to generate a schema file during the PlatformIO build. +# This script can also be run standalone from within the Marlin repo to generate all schema files. +# +import re,json +from pathlib import Path + +def extend_dict(d:dict, k:tuple): + if len(k) >= 1 and k[0] not in d: + d[k[0]] = {} + if len(k) >= 2 and k[1] not in d[k[0]]: + d[k[0]][k[1]] = {} + if len(k) >= 3 and k[2] not in d[k[0]][k[1]]: + d[k[0]][k[1]][k[2]] = {} + +grouping_patterns = [ + re.compile(r'^([XYZIJKUVW]|[XYZ]2|Z[34]|E[0-7])$'), + re.compile(r'^AXIS\d$'), + re.compile(r'^(MIN|MAX)$'), + re.compile(r'^[0-8]$'), + re.compile(r'^HOTEND[0-7]$'), + re.compile(r'^(HOTENDS|BED|PROBE|COOLER)$'), + re.compile(r'^[XYZIJKUVW]M(IN|AX)$') +] +# If the indexed part of the option name matches a pattern +# then add it to the dictionary. +def find_grouping(gdict, filekey, sectkey, optkey, pindex): + optparts = optkey.split('_') + if 1 < len(optparts) > pindex: + for patt in grouping_patterns: + if patt.match(optparts[pindex]): + subkey = optparts[pindex] + modkey = '_'.join(optparts) + optparts[pindex] = '*' + wildkey = '_'.join(optparts) + kkey = f'{filekey}|{sectkey}|{wildkey}' + if kkey not in gdict: gdict[kkey] = [] + gdict[kkey].append((subkey, modkey)) + +# Build a list of potential groups. Only those with multiple items will be grouped. +def group_options(schema): + for pindex in range(10, -1, -1): + found_groups = {} + for filekey, f in schema.items(): + for sectkey, s in f.items(): + for optkey in s: + find_grouping(found_groups, filekey, sectkey, optkey, pindex) + + fkeys = [ k for k in found_groups.keys() ] + for kkey in fkeys: + items = found_groups[kkey] + if len(items) > 1: + f, s, w = kkey.split('|') + extend_dict(schema, (f, s, w)) # Add wildcard group to schema + for subkey, optkey in items: # Add all items to wildcard group + schema[f][s][w][subkey] = schema[f][s][optkey] # Move non-wildcard item to wildcard group + del schema[f][s][optkey] + del found_groups[kkey] + +# Extract all board names from boards.h +def load_boards(): + bpath = Path("Marlin/src/core/boards.h") + if bpath.is_file(): + with bpath.open() as bfile: + boards = [] + for line in bfile: + if line.startswith("#define BOARD_"): + bname = line.split()[1] + if bname != "BOARD_UNKNOWN": boards.append(bname) + return "['" + "','".join(boards) + "']" + return '' + +# +# Extract a schema from the current configuration files +# +def extract(): + # Load board names from boards.h + boards = load_boards() + + # Parsing states + class Parse: + NORMAL = 0 # No condition yet + BLOCK_COMMENT = 1 # Looking for the end of the block comment + EOL_COMMENT = 2 # EOL comment started, maybe add the next comment? + GET_SENSORS = 3 # Gathering temperature sensor options + ERROR = 9 # Syntax error + + # List of files to process, with shorthand + filekey = { 'Configuration.h':'basic', 'Configuration_adv.h':'advanced' } + # A JSON object to store the data + sch_out = { 'basic':{}, 'advanced':{} } + # Regex for #define NAME [VALUE] [COMMENT] with sanitized line + defgrep = re.compile(r'^(//)?\s*(#define)\s+([A-Za-z0-9_]+)\s*(.*?)\s*(//.+)?$') + # Defines to ignore + ignore = ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION', 'CONFIG_EXPORT') + # Start with unknown state + state = Parse.NORMAL + # Serial ID + sid = 0 + # Loop through files and parse them line by line + for fn, fk in filekey.items(): + with Path("Marlin", fn).open() as fileobj: + section = 'none' # Current Settings section + line_number = 0 # Counter for the line number of the file + conditions = [] # Create a condition stack for the current file + comment_buff = [] # A temporary buffer for comments + options_json = '' # A buffer for the most recent options JSON found + eol_options = False # The options came from end of line, so only apply once + join_line = False # A flag that the line should be joined with the previous one + line = '' # A line buffer to handle \ continuation + last_added_ref = None # Reference to the last added item + # Loop through the lines in the file + for the_line in fileobj.readlines(): + line_number += 1 + + # Clean the line for easier parsing + the_line = the_line.strip() + + if join_line: # A previous line is being made longer + line += (' ' if line else '') + the_line + else: # Otherwise, start the line anew + line, line_start = the_line, line_number + + # If the resulting line ends with a \, don't process now. + # Strip the end off. The next line will be joined with it. + join_line = line.endswith("\\") + if join_line: + line = line[:-1].strip() + continue + else: + line_end = line_number + + defmatch = defgrep.match(line) + + # Special handling for EOL comments after a #define. + # At this point the #define is already digested and inserted, + # so we have to extend it + if state == Parse.EOL_COMMENT: + # If the line is not a comment, we're done with the EOL comment + if not defmatch and the_line.startswith('//'): + comment_buff.append(the_line[2:].strip()) + else: + last_added_ref['comment'] = ' '.join(comment_buff) + comment_buff = [] + state = Parse.NORMAL + + def use_comment(c, opt, sec, bufref): + if c.startswith(':'): # If the comment starts with : then it has magic JSON + d = c[1:].strip() # Strip the leading : + cbr = c.rindex('}') if d.startswith('{') else c.rindex(']') if d.startswith('[') else 0 + if cbr: + opt, cmt = c[1:cbr+1].strip(), c[cbr+1:].strip() + if cmt != '': bufref.append(cmt) + else: + opt = c[1:].strip() + elif c.startswith('@section'): # Start a new section + sec = c[8:].strip() + elif not c.startswith('========'): + bufref.append(c) + return opt, sec + + # In a block comment, capture lines up to the end of the comment. + # Assume nothing follows the comment closure. + if state in (Parse.BLOCK_COMMENT, Parse.GET_SENSORS): + endpos = line.find('*/') + if endpos < 0: + cline = line + else: + cline, line = line[:endpos].strip(), line[endpos+2:].strip() + + # Temperature sensors are done + if state == Parse.GET_SENSORS: + options_json = f'[ {options_json[:-2]} ]' + + state = Parse.NORMAL + + # Strip the leading '*' from block comments + if cline.startswith('*'): cline = cline[1:].strip() + + # Collect temperature sensors + if state == Parse.GET_SENSORS: + sens = re.match(r'^(-?\d+)\s*:\s*(.+)$', cline) + if sens: + s2 = sens[2].replace("'","''") + options_json += f"{sens[1]}:'{s2}', " + + elif state == Parse.BLOCK_COMMENT: + + # Look for temperature sensors + if cline == "Temperature sensors available:": + state, cline = Parse.GET_SENSORS, "Temperature Sensors" + + options_json, section = use_comment(cline, options_json, section, comment_buff) + + # For the normal state we're looking for any non-blank line + elif state == Parse.NORMAL: + # Skip a commented define when evaluating comment opening + st = 2 if re.match(r'^//\s*#define', line) else 0 + cpos1 = line.find('/*') # Start a block comment on the line? + cpos2 = line.find('//', st) # Start an end of line comment on the line? + + # Only the first comment starter gets evaluated + cpos = -1 + if cpos1 != -1 and (cpos1 < cpos2 or cpos2 == -1): + cpos = cpos1 + comment_buff = [] + state = Parse.BLOCK_COMMENT + eol_options = False + + elif cpos2 != -1 and (cpos2 < cpos1 or cpos1 == -1): + cpos = cpos2 + + # Expire end-of-line options after first use + if cline.startswith(':'): eol_options = True + + # Comment after a define may be continued on the following lines + if state == Parse.NORMAL and defmatch != None and cpos > 10: + state = Parse.EOL_COMMENT + comment_buff = [] + + # Process the start of a new comment + if cpos != -1: + cline, line = line[cpos+2:].strip(), line[:cpos].strip() + + # Strip leading '*' from block comments + if state == Parse.BLOCK_COMMENT: + if cline.startswith('*'): cline = cline[1:].strip() + + # Buffer a non-empty comment start + if cline != '': + options_json, section = use_comment(cline, options_json, section, comment_buff) + + # If the line has nothing before the comment, go to the next line + if line == '': + options_json = '' + continue + + # Parenthesize the given expression if needed + def atomize(s): + if s == '' \ + or re.match(r'^[A-Za-z0-9_]*(\([^)]+\))?$', s) \ + or re.match(r'^[A-Za-z0-9_]+ == \d+?$', s): + return s + return f'({s})' + + # + # The conditions stack is an array containing condition-arrays. + # Each condition-array lists the conditions for the current block. + # IF/N/DEF adds a new condition-array to the stack. + # ELSE/ELIF/ENDIF pop the condition-array. + # ELSE/ELIF negate the last item in the popped condition-array. + # ELIF adds a new condition to the end of the array. + # ELSE/ELIF re-push the condition-array. + # + cparts = line.split() + iselif, iselse = cparts[0] == '#elif', cparts[0] == '#else' + if iselif or iselse or cparts[0] == '#endif': + if len(conditions) == 0: + raise Exception(f'no #if block at line {line_number}') + + # Pop the last condition-array from the stack + prev = conditions.pop() + + if iselif or iselse: + prev[-1] = '!' + prev[-1] # Invert the last condition + if iselif: prev.append(atomize(line[5:].strip())) + conditions.append(prev) + + elif cparts[0] == '#if': + conditions.append([ atomize(line[3:].strip()) ]) + elif cparts[0] == '#ifdef': + conditions.append([ f'defined({line[6:].strip()})' ]) + elif cparts[0] == '#ifndef': + conditions.append([ f'!defined({line[7:].strip()})' ]) + + # Handle a complete #define line + elif defmatch != None: + + # Get the match groups into vars + enabled, define_name, val = defmatch[1] == None, defmatch[3], defmatch[4] + + # Increment the serial ID + sid += 1 + + # Create a new dictionary for the current #define + define_info = { + 'section': section, + 'name': define_name, + 'enabled': enabled, + 'line': line_start, + 'sid': sid + } + + if val != '': define_info['value'] = val + + # Type is based on the value + if val == '': + value_type = 'switch' + elif re.match(r'^(true|false)$', val): + value_type = 'bool' + val = val == 'true' + elif re.match(r'^[-+]?\s*\d+$', val): + value_type = 'int' + val = int(val) + elif re.match(r'[-+]?\s*(\d+\.|\d*\.\d+)([eE][-+]?\d+)?[fF]?', val): + value_type = 'float' + val = float(val.replace('f','')) + else: + value_type = 'string' if val[0] == '"' \ + else 'char' if val[0] == "'" \ + else 'state' if re.match(r'^(LOW|HIGH)$', val) \ + else 'enum' if re.match(r'^[A-Za-z0-9_]{3,}$', val) \ + else 'int[]' if re.match(r'^{(\s*[-+]?\s*\d+\s*(,\s*)?)+}$', val) \ + else 'float[]' if re.match(r'^{(\s*[-+]?\s*(\d+\.|\d*\.\d+)([eE][-+]?\d+)?[fF]?\s*(,\s*)?)+}$', val) \ + else 'array' if val[0] == '{' \ + else '' + + if value_type != '': define_info['type'] = value_type + + # Join up accumulated conditions with && + if conditions: define_info['requires'] = ' && '.join(sum(conditions, [])) + + # If the comment_buff is not empty, add the comment to the info + if comment_buff: + full_comment = '\n'.join(comment_buff) + + # An EOL comment will be added later + # The handling could go here instead of above + if state == Parse.EOL_COMMENT: + define_info['comment'] = '' + else: + define_info['comment'] = full_comment + comment_buff = [] + + # If the comment specifies units, add that to the info + units = re.match(r'^\(([^)]+)\)', full_comment) + if units: + units = units[1] + if units == 's' or units == 'sec': units = 'seconds' + define_info['units'] = units + + # Set the options for the current #define + if define_name == "MOTHERBOARD" and boards != '': + define_info['options'] = boards + elif options_json != '': + define_info['options'] = options_json + if eol_options: options_json = '' + + # Create section dict if it doesn't exist yet + if section not in sch_out[fk]: sch_out[fk][section] = {} + + # If define has already been seen... + if define_name in sch_out[fk][section]: + info = sch_out[fk][section][define_name] + if isinstance(info, dict): info = [ info ] # Convert a single dict into a list + info.append(define_info) # Add to the list + else: + # Add the define dict with name as key + sch_out[fk][section][define_name] = define_info + + if state == Parse.EOL_COMMENT: + last_added_ref = define_info + + return sch_out + +def dump_json(schema:dict, jpath:Path): + with jpath.open('w') as jfile: + json.dump(schema, jfile, ensure_ascii=False, indent=2) + +def dump_yaml(schema:dict, ypath:Path): + import yaml + with ypath.open('w') as yfile: + yaml.dump(schema, yfile, default_flow_style=False, width=120, indent=2) + +def main(): + try: + schema = extract() + except Exception as exc: + print("Error: " + str(exc)) + schema = None + + if schema: + print("Generating JSON ...") + dump_json(schema, Path('schema.json')) + group_options(schema) + dump_json(schema, Path('schema_grouped.json')) + + try: + import yaml + except ImportError: + print("Installing YAML module ...") + import subprocess + subprocess.run(['python3', '-m', 'pip', 'install', 'pyyaml']) + import yaml + + print("Generating YML ...") + dump_yaml(schema, Path('schema.yml')) + +if __name__ == '__main__': + main() diff --git a/buildroot/share/PlatformIO/scripts/signature.py b/buildroot/share/PlatformIO/scripts/signature.py index f1c86bb839..43d56ac6e1 100644 --- a/buildroot/share/PlatformIO/scripts/signature.py +++ b/buildroot/share/PlatformIO/scripts/signature.py @@ -1,7 +1,11 @@ # # signature.py # -import os,subprocess,re,json,hashlib +import schema + +import subprocess,re,json,hashlib +from datetime import datetime +from pathlib import Path # # Return all macro names in a header as an array, so we can take @@ -35,8 +39,8 @@ def get_file_sha256sum(filepath): # Compress a JSON file into a zip file # import zipfile -def compress_file(filepath, outputbase): - with zipfile.ZipFile(outputbase + '.zip', 'w', compression=zipfile.ZIP_BZIP2, compresslevel=9) as zipf: +def compress_file(filepath, outpath): + with zipfile.ZipFile(outpath, 'w', compression=zipfile.ZIP_BZIP2, compresslevel=9) as zipf: zipf.write(filepath, compress_type=zipfile.ZIP_BZIP2, compresslevel=9) # @@ -51,19 +55,19 @@ def compute_build_signature(env): # Definitions from these files will be kept files_to_keep = [ 'Marlin/Configuration.h', 'Marlin/Configuration_adv.h' ] - build_dir = os.path.join(env['PROJECT_BUILD_DIR'], env['PIOENV']) + build_path = Path(env['PROJECT_BUILD_DIR'], env['PIOENV']) # Check if we can skip processing hashes = '' for header in files_to_keep: hashes += get_file_sha256sum(header)[0:10] - marlin_json = os.path.join(build_dir, 'marlin_config.json') - marlin_zip = os.path.join(build_dir, 'mc') + marlin_json = build_path / 'marlin_config.json' + marlin_zip = build_path / 'mc.zip' # Read existing config file try: - with open(marlin_json, 'r') as infile: + with marlin_json.open() as infile: conf = json.load(infile) if conf['__INITIAL_HASH'] == hashes: # Same configuration, skip recomputing the building signature @@ -109,7 +113,10 @@ def compute_build_signature(env): defines[key] = value if len(value) else "" - if not 'CONFIGURATION_EMBEDDING' in defines: + # + # Continue to gather data for CONFIGURATION_EMBEDDING or CONFIG_EXPORT + # + if not ('CONFIGURATION_EMBEDDING' in defines or 'CONFIG_EXPORT' in defines): return # Second step is to filter useless macro @@ -145,6 +152,85 @@ def compute_build_signature(env): if key in conf_defines[header]: data[header][key] = resolved_defines[key] + # Every python needs this toy + def tryint(key): + try: + return int(defines[key]) + except: + return 0 + + config_dump = tryint('CONFIG_EXPORT') + + # + # Produce an INI file if CONFIG_EXPORT == 2 + # + if config_dump == 2: + print("Generating config.ini ...") + config_ini = build_path / 'config.ini' + with config_ini.open('w') as outfile: + ignore = ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION', 'CONFIG_EXPORT') + filegrp = { 'Configuration.h':'config:basic', 'Configuration_adv.h':'config:advanced' } + vers = defines["CONFIGURATION_H_VERSION"] + dt_string = datetime.now().strftime("%Y-%m-%d at %H:%M:%S") + ini_fmt = '{0:40}{1}\n' + outfile.write( + '#\n' + + '# Marlin Firmware\n' + + '# config.ini - Options to apply before the build\n' + + '#\n' + + f'# Generated by Marlin build on {dt_string}\n' + + '#\n' + + '\n' + + '[config:base]\n' + + ini_fmt.format('ini_use_config', ' = all') + + ini_fmt.format('ini_config_vers', f' = {vers}') + ) + # Loop through the data array of arrays + for header in data: + if header.startswith('__'): + continue + outfile.write('\n[' + filegrp[header] + ']\n') + for key in sorted(data[header]): + if key not in ignore: + val = 'on' if data[header][key] == '' else data[header][key] + outfile.write(ini_fmt.format(key.lower(), ' = ' + val)) + + # + # Produce a schema.json file if CONFIG_EXPORT == 3 + # + if config_dump >= 3: + try: + conf_schema = schema.extract() + except Exception as exc: + print("Error: " + str(exc)) + conf_schema = None + + if conf_schema: + # + # Produce a schema.json file if CONFIG_EXPORT == 3 + # + if config_dump in (3, 13): + print("Generating schema.json ...") + schema.dump_json(conf_schema, build_path / 'schema.json') + if config_dump == 13: + schema.group_options(conf_schema) + schema.dump_json(conf_schema, build_path / 'schema_grouped.json') + + # + # Produce a schema.yml file if CONFIG_EXPORT == 4 + # + elif config_dump == 4: + print("Generating schema.yml ...") + try: + import yaml + except ImportError: + env.Execute(env.VerboseAction( + '$PYTHONEXE -m pip install "pyyaml"', + "Installing YAML for schema.yml export", + )) + import yaml + schema.dump_yaml(conf_schema, build_path / 'schema.yml') + # Append the source code version and date data['VERSION'] = {} data['VERSION']['DETAILED_BUILD_VERSION'] = resolved_defines['DETAILED_BUILD_VERSION'] @@ -156,10 +242,17 @@ def compute_build_signature(env): pass # - # Produce a JSON file for CONFIGURATION_EMBEDDING or CONFIG_DUMP > 0 + # Produce a JSON file for CONFIGURATION_EMBEDDING or CONFIG_EXPORT == 1 # - with open(marlin_json, 'w') as outfile: - json.dump(data, outfile, separators=(',', ':')) + if config_dump == 1 or 'CONFIGURATION_EMBEDDING' in defines: + with marlin_json.open('w') as outfile: + json.dump(data, outfile, separators=(',', ':')) + + # + # The rest only applies to CONFIGURATION_EMBEDDING + # + if not 'CONFIGURATION_EMBEDDING' in defines: + return # Compress the JSON file as much as we can compress_file(marlin_json, marlin_zip) @@ -167,17 +260,17 @@ def compute_build_signature(env): # Generate a C source file for storing this array with open('Marlin/src/mczip.h','wb') as result_file: result_file.write( - b'#ifndef NO_CONFIGURATION_EMBEDDING_WARNING\n' + b'#ifndef NO_CONFIGURATION_EMBEDDING_WARNING\n' + b' #warning "Generated file \'mc.zip\' is embedded (Define NO_CONFIGURATION_EMBEDDING_WARNING to suppress this warning.)"\n' + b'#endif\n' + b'const unsigned char mc_zip[] PROGMEM = {\n ' ) count = 0 - for b in open(os.path.join(build_dir, 'mc.zip'), 'rb').read(): + for b in (build_path / 'mc.zip').open('rb').read(): result_file.write(b' 0x%02X,' % b) count += 1 - if (count % 16 == 0): - result_file.write(b'\n ') - if (count % 16): + if count % 16 == 0: + result_file.write(b'\n ') + if count % 16: result_file.write(b'\n') result_file.write(b'};\n') diff --git a/platformio.ini b/platformio.ini index 26f58662cc..b2f178ec0f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -16,6 +16,7 @@ boards_dir = buildroot/share/PlatformIO/boards default_envs = mega2560 include_dir = Marlin extra_configs = + Marlin/config.ini ini/avr.ini ini/due.ini ini/esp32.ini @@ -44,12 +45,13 @@ extra_configs = build_flags = -g3 -D__MARLIN_FIRMWARE__ -DNDEBUG -fmax-errors=5 extra_scripts = + pre:buildroot/share/PlatformIO/scripts/configuration.py pre:buildroot/share/PlatformIO/scripts/common-dependencies.py pre:buildroot/share/PlatformIO/scripts/common-cxxflags.py pre:buildroot/share/PlatformIO/scripts/preflight-checks.py post:buildroot/share/PlatformIO/scripts/common-dependencies-post.py lib_deps = -default_src_filter = + - - + +default_src_filter = + - - + - - - - - - - - - - - - - From 2ccdc4f9ed232af3b55fe633fafe64a9be508ff8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 Aug 2022 17:56:09 -0500 Subject: [PATCH 42/54] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20MARLI?= =?UTF-8?q?N=5FTEST=5FBUILD=20=E2=80=93=20for=20future=20use=20(#24077)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 3 ++ Marlin/src/MarlinCore.cpp | 18 +++++++----- Marlin/src/tests/marlin_tests.cpp | 47 +++++++++++++++++++++++++++++++ Marlin/src/tests/marlin_tests.h | 25 ++++++++++++++++ ini/features.ini | 1 + platformio.ini | 2 +- 6 files changed, 88 insertions(+), 8 deletions(-) create mode 100644 Marlin/src/tests/marlin_tests.cpp create mode 100644 Marlin/src/tests/marlin_tests.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index b076949a88..921d36b7a8 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -4295,6 +4295,9 @@ // //#define PINS_DEBUGGING +// Enable Tests that will run at startup and produce a report +//#define MARLIN_TEST_BUILD + // Enable Marlin dev mode which adds some special commands //#define MARLIN_DEV_MODE diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 31b6184317..921c3c60bc 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -39,17 +39,13 @@ #endif #include -#include "core/utility.h" - +#include "module/endstops.h" #include "module/motion.h" #include "module/planner.h" -#include "module/endstops.h" -#include "module/temperature.h" -#include "module/settings.h" #include "module/printcounter.h" // PrintCounter or Stopwatch - +#include "module/settings.h" #include "module/stepper.h" -#include "module/stepper/indirection.h" +#include "module/temperature.h" #include "gcode/gcode.h" #include "gcode/parser.h" @@ -248,6 +244,10 @@ #include "feature/easythreed_ui.h" #endif +#if ENABLED(MARLIN_TEST_BUILD) + #include "tests/marlin_tests.h" +#endif + PGMSTR(M112_KILL_STR, "M112 Shutdown"); MarlinState marlin_state = MF_INITIALIZING; @@ -1635,6 +1635,8 @@ void setup() { marlin_state = MF_RUNNING; SETUP_LOG("setup() completed."); + + TERN_(MARLIN_TEST_BUILD, runStartupTests()); } /** @@ -1669,5 +1671,7 @@ void loop() { TERN_(HAS_TFT_LVGL_UI, printer_state_polling()); + TERN_(MARLIN_TEST_BUILD, runPeriodicTests()); + } while (ENABLED(__AVR__)); // Loop forever on slower (AVR) boards } diff --git a/Marlin/src/tests/marlin_tests.cpp b/Marlin/src/tests/marlin_tests.cpp new file mode 100644 index 0000000000..89e5664345 --- /dev/null +++ b/Marlin/src/tests/marlin_tests.cpp @@ -0,0 +1,47 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ + +#include "../inc/MarlinConfigPre.h" + +#if ENABLED(MARLIN_TEST_BUILD) + +#include "../module/endstops.h" +#include "../module/motion.h" +#include "../module/planner.h" +#include "../module/settings.h" +#include "../module/stepper.h" +#include "../module/temperature.h" + +// Individual tests are localized in each module. +// Each test produces its own report. + +// Startup tests are run at the end of setup() +void runStartupTests() { + // Call post-setup tests here to validate behaviors. +} + +// Periodic tests are run from within loop() +void runPeriodicTests() { + // Call periodic tests here to validate behaviors. +} + +#endif // MARLIN_TEST_BUILD diff --git a/Marlin/src/tests/marlin_tests.h b/Marlin/src/tests/marlin_tests.h new file mode 100644 index 0000000000..6afce1ef37 --- /dev/null +++ b/Marlin/src/tests/marlin_tests.h @@ -0,0 +1,25 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ +#pragma once + +void runStartupTests(); +void runPeriodicTests(); diff --git a/ini/features.ini b/ini/features.ini index ee065cb9b9..b6a07c76df 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -14,6 +14,7 @@ YHCB2004 = red-scorp/LiquidCrystal_AIP31068@^1.0.4 HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/master.zip src_filter=+ extra_scripts=download_mks_assets.py +MARLIN_TEST_BUILD = src_filter=+ POSTMORTEM_DEBUGGING = src_filter=+ + build_flags=-funwind-tables MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/master.zip diff --git a/platformio.ini b/platformio.ini index b2f178ec0f..4f5598f6af 100644 --- a/platformio.ini +++ b/platformio.ini @@ -51,7 +51,7 @@ extra_scripts = pre:buildroot/share/PlatformIO/scripts/preflight-checks.py post:buildroot/share/PlatformIO/scripts/common-dependencies-post.py lib_deps = -default_src_filter = + - - + - +default_src_filter = + - - + - - - - - - - - - - - - - From a0409289c8815e71b34eae1a09687229ed4e93b6 Mon Sep 17 00:00:00 2001 From: Ruedi Steinmann Date: Fri, 5 Aug 2022 01:00:19 +0200 Subject: [PATCH 43/54] =?UTF-8?q?=F0=9F=9A=B8=20Laser=20with=20only=20PWM?= =?UTF-8?q?=20pin=20(#24345)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/spindle_laser.cpp | 10 +++++++--- Marlin/src/inc/SanityCheck.h | 4 ++-- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index da38646a36..e7898268e8 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -67,7 +67,7 @@ cutter_frequency_t SpindleLaser::frequency; // PWM fre void SpindleLaser::init() { #if ENABLED(SPINDLE_SERVO) servo[SPINDLE_SERVO_NR].move(SPINDLE_SERVO_MIN); - #else + #elif PIN_EXISTS(SPINDLE_LASER_ENA) OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Init spindle to off #endif #if ENABLED(SPINDLE_CHANGE_DIR) @@ -104,12 +104,16 @@ void SpindleLaser::init() { } void SpindleLaser::set_ocr(const uint8_t ocr) { - WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_STATE); // Cutter ON + #if PIN_EXISTS(SPINDLE_LASER_ENA) + WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_STATE); // Cutter ON + #endif _set_ocr(ocr); } void SpindleLaser::ocr_off() { - WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Cutter OFF + #if PIN_EXISTS(SPINDLE_LASER_ENA) + WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Cutter OFF + #endif _set_ocr(0); } #endif // SPINDLE_LASER_USE_PWM diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 234f850cdb..cab8641e8a 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3912,8 +3912,8 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #define _PIN_CONFLICT(P) (PIN_EXISTS(P) && P##_PIN == SPINDLE_LASER_PWM_PIN) #if BOTH(SPINDLE_FEATURE, LASER_FEATURE) #error "Enable only one of SPINDLE_FEATURE or LASER_FEATURE." - #elif !PIN_EXISTS(SPINDLE_LASER_ENA) && DISABLED(SPINDLE_SERVO) - #error "(SPINDLE|LASER)_FEATURE requires SPINDLE_LASER_ENA_PIN or SPINDLE_SERVO to control the power." + #elif NONE(SPINDLE_SERVO, SPINDLE_LASER_USE_PWM) && !PIN_EXISTS(SPINDLE_LASER_ENA) + #error "(SPINDLE|LASER)_FEATURE requires SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_USE_PWM, or SPINDLE_SERVO to control the power." #elif ENABLED(SPINDLE_CHANGE_DIR) && !PIN_EXISTS(SPINDLE_DIR) #error "SPINDLE_DIR_PIN is required for SPINDLE_CHANGE_DIR." #elif ENABLED(SPINDLE_LASER_USE_PWM) From 98095ddad6818c1fd9dfca214d09f5107633106b Mon Sep 17 00:00:00 2001 From: Travis Ziegler Date: Fri, 5 Aug 2022 22:37:24 -0400 Subject: [PATCH 45/54] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20LPC176x=20USB=20Host?= =?UTF-8?q?=20Shield=20(#24588)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/sd/usb_flashdrive/lib-uhs2/message.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/message.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/message.cpp index dcc309025a..1c1131cd3c 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/message.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/message.cpp @@ -59,7 +59,7 @@ void E_NotifyStr(char const * msg, int lvl) { void E_Notify(uint8_t b, int lvl) { if (UsbDEBUGlvl < lvl) return; USB_HOST_SERIAL.print(b - #if !defined(ARDUINO) || ARDUINO < 100 + #if !defined(ARDUINO) && !defined(ARDUINO_ARCH_LPC176X) , DEC #endif ); From e06340abd13822fe54a1c0be5be57421b03490ef Mon Sep 17 00:00:00 2001 From: "J.C. Nelson" <32139633+xC0000005@users.noreply.github.com> Date: Fri, 5 Aug 2022 22:09:46 -0700 Subject: [PATCH 46/54] =?UTF-8?q?=F0=9F=94=A8=20Trigorilla=20Pro=20disk=20?= =?UTF-8?q?based=20update=20(#24591)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 2 +- .../share/PlatformIO/scripts/chitu_crypt.py | 19 +++++++++++++++---- ini/stm32f1.ini | 19 +++++++++++++++++++ 3 files changed, 35 insertions(+), 5 deletions(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index a60365d980..37e222d004 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -590,7 +590,7 @@ #elif MB(CREALITY_V25S1) #include "stm32f1/pins_CREALITY_V25S1.h" // STM32F1 env:STM32F103RE_creality_smartPro env:STM32F103RE_creality_smartPro_maple #elif MB(TRIGORILLA_PRO) - #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro env:trigorilla_pro_maple + #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro env:trigorilla_pro_maple env:trigorilla_pro_disk #elif MB(FLY_MINI) #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI env:FLY_MINI_maple #elif MB(FLSUN_HISPEED) diff --git a/buildroot/share/PlatformIO/scripts/chitu_crypt.py b/buildroot/share/PlatformIO/scripts/chitu_crypt.py index 54b8375713..76792030cf 100644 --- a/buildroot/share/PlatformIO/scripts/chitu_crypt.py +++ b/buildroot/share/PlatformIO/scripts/chitu_crypt.py @@ -4,7 +4,9 @@ # import pioutil if pioutil.is_pio_build(): - import struct,uuid + import struct,uuid,marlin + + board = marlin.env.BoardConfig() def calculate_crc(contents, seed): accumulating_xor_value = seed; @@ -104,12 +106,21 @@ if pioutil.is_pio_build(): # Encrypt ${PROGNAME}.bin and save it as 'update.cbd' def encrypt(source, target, env): from pathlib import Path + fwpath = Path(target[0].path) fwsize = fwpath.stat().st_size + + enname = board.get("build.crypt_chitu") + enpath = Path(target[0].dir.path) + fwfile = fwpath.open("rb") - upfile = Path(target[0].dir.path, 'update.cbd').open("wb") - encrypt_file(fwfile, upfile, fwsize) + enfile = (enpath / enname).open("wb") + + print(f"Encrypting {fwpath} to {enname}") + encrypt_file(fwfile, enfile, fwsize) + fwfile.close() + enfile.close() + fwpath.unlink() - import marlin marlin.relocate_firmware("0x08008800") marlin.add_post_action(encrypt); diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index c0415c5f84..d68704216f 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -378,12 +378,31 @@ build_flags = ${stm32_variant.build_flags} build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC +# +# TRIGORILLA PRO DISK BASED (STM32F103ZET6) +# Builds for Trigorilla to update from SD +# +[env:trigorilla_pro_disk] +extends = stm32_variant +board = genericSTM32F103ZE +board_build.crypt_chitu = update.zw +board_build.variant = MARLIN_F103Zx +board_build.offset = 0x8800 +build_flags = ${stm32_variant.build_flags} + -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 +build_unflags = ${stm32_variant.build_unflags} + -DUSBCON -DUSBD_USE_CDC +extra_scripts = ${stm32_variant.extra_scripts} + buildroot/share/PlatformIO/scripts/chitu_crypt.py + + # # Chitu boards like Tronxy X5s (STM32F103ZET6) # [env:chitu_f103] extends = stm32_variant board = genericSTM32F103ZE +board_build.crypt_chitu = update.cbd board_build.variant = MARLIN_F103Zx board_build.offset = 0x8800 build_flags = ${stm32_variant.build_flags} From 7196f1312508bdb04d8e943572773a5f23c8509e Mon Sep 17 00:00:00 2001 From: qwertymodo Date: Fri, 5 Aug 2022 22:07:30 -0700 Subject: [PATCH 47/54] =?UTF-8?q?=E2=9C=A8=20M150=20K=20=E2=80=93=20Keep?= =?UTF-8?q?=20unspecified=20components=20(#24315)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/leds/neopixel.h | 8 ++++++++ Marlin/src/gcode/feature/leds/M150.cpp | 21 +++++++++++++-------- 2 files changed, 21 insertions(+), 8 deletions(-) diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index d71aa25770..2048e2c2ee 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -131,6 +131,13 @@ public: // Accessors static uint16_t pixels() { return adaneo1.numPixels() * TERN1(NEOPIXEL2_INSERIES, 2); } + static uint32_t pixel_color(const uint16_t n) { + #if ENABLED(NEOPIXEL2_INSERIES) + if (n >= NEOPIXEL_PIXELS) return adaneo2.getPixelColor(n - (NEOPIXEL_PIXELS)); + #endif + return adaneo1.getPixelColor(n); + } + static uint8_t brightness() { return adaneo1.getBrightness(); } static uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w)) { @@ -174,6 +181,7 @@ extern Marlin_NeoPixel neo; // Accessors static uint16_t pixels() { return adaneo.numPixels();} + static uint32_t pixel_color(const uint16_t n) { return adaneo.getPixelColor(n); } static uint8_t brightness() { return adaneo.getBrightness(); } static uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED2, uint8_t w)) { return adaneo.Color(r, g, b OPTARG(HAS_WHITE_LED2, w)); diff --git a/Marlin/src/gcode/feature/leds/M150.cpp b/Marlin/src/gcode/feature/leds/M150.cpp index 95e7367b6e..77c58411a3 100644 --- a/Marlin/src/gcode/feature/leds/M150.cpp +++ b/Marlin/src/gcode/feature/leds/M150.cpp @@ -31,11 +31,13 @@ * M150: Set Status LED Color - Use R-U-B-W for R-G-B-W * and Brightness - Use P (for NEOPIXEL only) * - * Always sets all 3 or 4 components. If a component is left out, set to 0. - * If brightness is left out, no value changed + * Always sets all 3 or 4 components unless the K flag is specified. + * If a component is left out, set to 0. + * If brightness is left out, no value changed. * * With NEOPIXEL_LED: * I Set the NeoPixel index to affect. Default: All + * K Keep all unspecified values unchanged instead of setting to 0. * * With NEOPIXEL2_SEPARATE: * S The NeoPixel strip to set. Default: All. @@ -51,16 +53,19 @@ * M150 P ; Set LED full brightness * M150 I1 R ; Set NEOPIXEL index 1 to red * M150 S1 I1 R ; Set SEPARATE index 1 to red + * M150 K R127 ; Set LED red to 50% without changing blue or green */ void GcodeSuite::M150() { + int32_t old_color = 0; + #if ENABLED(NEOPIXEL_LED) const pixel_index_t index = parser.intval('I', -1); #if ENABLED(NEOPIXEL2_SEPARATE) int8_t brightness = neo.brightness(), unit = parser.intval('S', -1); switch (unit) { case -1: neo2.neoindex = index; // fall-thru - case 0: neo.neoindex = index; break; - case 1: neo2.neoindex = index; brightness = neo2.brightness(); break; + case 0: neo.neoindex = index; old_color = parser.seen('K') ? neo.pixel_color(index >= 0 ? index : 0) : 0; break; + case 1: neo2.neoindex = index; brightness = neo2.brightness(); old_color = parser.seen('K') ? neo2.pixel_color(index >= 0 ? index : 0) : 0; break; } #else const uint8_t brightness = neo.brightness(); @@ -69,10 +74,10 @@ void GcodeSuite::M150() { #endif const LEDColor color = LEDColor( - parser.seen('R') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('U') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : 0 - OPTARG(HAS_WHITE_LED, parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0) + parser.seen('R') ? (parser.has_value() ? parser.value_byte() : 255) : (old_color >> 16) & 0xFF, + parser.seen('U') ? (parser.has_value() ? parser.value_byte() : 255) : (old_color >> 8) & 0xFF, + parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : old_color & 0xFF + OPTARG(HAS_WHITE_LED, parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : (old_color >> 24) & 0xFF) OPTARG(NEOPIXEL_LED, parser.seen('P') ? (parser.has_value() ? parser.value_byte() : 255) : brightness) ); From a1704c10b977d31d2bb90cafe4935f3bdbfc3c89 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 6 Aug 2022 00:57:37 -0500 Subject: [PATCH 48/54] =?UTF-8?q?=F0=9F=A9=B9=20G0/G1=20S=20seen=20=3D>=20?= =?UTF-8?q?seenval?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/gcode.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 0cae1573bc..bbfe561ffe 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -233,7 +233,7 @@ void GcodeSuite::get_destination_from_command() { if (WITHIN(parser.codenum, 1, TERN(ARC_SUPPORT, 3, 1)) || TERN0(BEZIER_CURVE_SUPPORT, parser.codenum == 5)) { planner.laser_inline.status.isPowered = true; if (parser.seen('I')) cutter.set_enabled(true); // This is set for backward LightBurn compatibility. - if (parser.seen('S')) { + if (parser.seenval('S')) { const float v = parser.value_float(), u = TERN(LASER_POWER_TRAP, v, cutter.power_to_range(v)); cutter.menuPower = cutter.unitPower = u; From a0462eb01738516561ea9356ebcafcb523782457 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Fri, 5 Aug 2022 22:59:56 -0700 Subject: [PATCH 49/54] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20AUTO=5FFAN=5FPIN=20s?= =?UTF-8?q?anity=20check=20(#24593)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index cab8641e8a..bdcd1d3fce 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2170,13 +2170,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS */ #if HAS_AUTO_FAN #if HAS_FAN0 - #if E0_AUTO_FAN_PIN == FAN_PIN + #if PIN_EXISTS(E0_AUTO_FAN) && E0_AUTO_FAN_PIN == FAN_PIN #error "You cannot set E0_AUTO_FAN_PIN equal to FAN_PIN." - #elif E1_AUTO_FAN_PIN == FAN_PIN + #elif PIN_EXISTS(E1_AUTO_FAN) && E1_AUTO_FAN_PIN == FAN_PIN #error "You cannot set E1_AUTO_FAN_PIN equal to FAN_PIN." - #elif E2_AUTO_FAN_PIN == FAN_PIN + #elif PIN_EXISTS(E2_AUTO_FAN) && E2_AUTO_FAN_PIN == FAN_PIN #error "You cannot set E2_AUTO_FAN_PIN equal to FAN_PIN." - #elif E3_AUTO_FAN_PIN == FAN_PIN + #elif PIN_EXISTS(E3_AUTO_FAN) && E3_AUTO_FAN_PIN == FAN_PIN #error "You cannot set E3_AUTO_FAN_PIN equal to FAN_PIN." #endif #endif From b02c3258b56f73ae6cff17d7e47c9e1fba7c91cd Mon Sep 17 00:00:00 2001 From: Mark Date: Sat, 6 Aug 2022 14:14:58 +0800 Subject: [PATCH 50/54] =?UTF-8?q?=E2=9C=A8=20Bed=20Distance=20Sensor=20(#2?= =?UTF-8?q?4554)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 9 + Marlin/src/MarlinCore.cpp | 11 ++ Marlin/src/core/utility.cpp | 1 + Marlin/src/feature/babystep.cpp | 12 ++ Marlin/src/feature/babystep.h | 4 + Marlin/src/feature/bedlevel/bdl/bdl.cpp | 195 ++++++++++++++++++++ Marlin/src/feature/bedlevel/bdl/bdl.h | 36 ++++ Marlin/src/gcode/calibrate/G28.cpp | 8 +- Marlin/src/gcode/gcode.cpp | 4 + Marlin/src/gcode/gcode.h | 7 + Marlin/src/gcode/probe/M102.cpp | 57 ++++++ Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/inc/SanityCheck.h | 4 +- Marlin/src/inc/Warnings.cpp | 7 + Marlin/src/module/endstops.cpp | 13 +- Marlin/src/module/endstops.h | 5 + Marlin/src/module/probe.cpp | 6 + Marlin/src/module/stepper.cpp | 4 + Marlin/src/module/stepper/indirection.h | 2 +- Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h | 6 + buildroot/tests/PANDA_PI_V29 | 19 ++ ini/features.ini | 2 + ini/stm32f1.ini | 3 +- platformio.ini | 1 + 24 files changed, 409 insertions(+), 9 deletions(-) create mode 100644 Marlin/src/feature/bedlevel/bdl/bdl.cpp create mode 100644 Marlin/src/feature/bedlevel/bdl/bdl.h create mode 100644 Marlin/src/gcode/probe/M102.cpp create mode 100755 buildroot/tests/PANDA_PI_V29 diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 9259468374..84e4f49e59 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1886,6 +1886,15 @@ #define LEVELING_BED_TEMP 50 #endif +/** + * Bed Distance Sensor + * + * Measures the distance from bed to nozzle with accuracy of 0.01mm. + * For information about this sensor https://github.com/markniu/Bed_Distance_sensor + * Uses I2C port, so it requires I2C library markyue/Panda_SoftMasterI2C. + */ +//#define BD_SENSOR + /** * Enable detailed logging of G28, G29, M48, etc. * Turn on with the command 'M111 S32'. diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 921c3c60bc..1e2e6c6483 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -121,6 +121,10 @@ #include "feature/bltouch.h" #endif +#if ENABLED(BD_SENSOR) + #include "feature/bedlevel/bdl/bdl.h" +#endif + #if ENABLED(POLL_JOG) #include "feature/joystick.h" #endif @@ -779,6 +783,9 @@ void idle(bool no_stepper_sleep/*=false*/) { if (++idle_depth > 5) SERIAL_ECHOLNPGM("idle() call depth: ", idle_depth); #endif + // Bed Distance Sensor task + TERN_(BD_SENSOR, bdl.process()); + // Core Marlin activities manage_inactivity(no_stepper_sleep); @@ -1632,6 +1639,10 @@ void setup() { SETUP_RUN(test_tmc_connection()); #endif + #if ENABLED(BD_SENSOR) + SETUP_RUN(bdl.init(I2C_BD_SDA_PIN, I2C_BD_SCL_PIN, I2C_BD_DELAY)); + #endif + marlin_state = MF_RUNNING; SETUP_LOG("setup() completed."); diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index e4fd525924..64f083e197 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -70,6 +70,7 @@ void safe_delay(millis_t ms) { TERN_(NOZZLE_AS_PROBE, "NOZZLE_AS_PROBE") TERN_(FIX_MOUNTED_PROBE, "FIX_MOUNTED_PROBE") TERN_(HAS_Z_SERVO_PROBE, TERN(BLTOUCH, "BLTOUCH", "SERVO PROBE")) + TERN_(BD_SENSOR, "BD_SENSOR") TERN_(TOUCH_MI_PROBE, "TOUCH_MI_PROBE") TERN_(Z_PROBE_SLED, "Z_PROBE_SLED") TERN_(Z_PROBE_ALLEN_KEY, "Z_PROBE_ALLEN_KEY") diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp index 54ad9588f4..2e3d6a9fd2 100644 --- a/Marlin/src/feature/babystep.cpp +++ b/Marlin/src/feature/babystep.cpp @@ -54,6 +54,18 @@ void Babystep::add_mm(const AxisEnum axis, const_float_t mm) { add_steps(axis, mm * planner.settings.axis_steps_per_mm[axis]); } +#if ENABLED(BD_SENSOR) + void Babystep::set_mm(const AxisEnum axis, const_float_t mm) { + //if (DISABLED(BABYSTEP_WITHOUT_HOMING) && axes_should_home(_BV(axis))) return; + const int16_t distance = mm * planner.settings.axis_steps_per_mm[axis]; + accum = distance; // Count up babysteps for the UI + steps[BS_AXIS_IND(axis)] = distance; + TERN_(BABYSTEP_DISPLAY_TOTAL, axis_total[BS_TOTAL_IND(axis)] = distance); + TERN_(BABYSTEP_ALWAYS_AVAILABLE, gcode.reset_stepper_timeout()); + TERN_(INTEGRATED_BABYSTEPPING, if (has_steps()) stepper.initiateBabystepping()); + } +#endif + void Babystep::add_steps(const AxisEnum axis, const int16_t distance) { if (DISABLED(BABYSTEP_WITHOUT_HOMING) && axes_should_home(_BV(axis))) return; diff --git a/Marlin/src/feature/babystep.h b/Marlin/src/feature/babystep.h index 5693afb4fc..bbf0c5a260 100644 --- a/Marlin/src/feature/babystep.h +++ b/Marlin/src/feature/babystep.h @@ -63,6 +63,10 @@ public: static void add_steps(const AxisEnum axis, const int16_t distance); static void add_mm(const AxisEnum axis, const_float_t mm); + #if ENABLED(BD_SENSOR) + static void set_mm(const AxisEnum axis, const_float_t mm); + #endif + static bool has_steps() { return steps[BS_AXIS_IND(X_AXIS)] || steps[BS_AXIS_IND(Y_AXIS)] || steps[BS_AXIS_IND(Z_AXIS)]; } diff --git a/Marlin/src/feature/bedlevel/bdl/bdl.cpp b/Marlin/src/feature/bedlevel/bdl/bdl.cpp new file mode 100644 index 0000000000..0668eb705c --- /dev/null +++ b/Marlin/src/feature/bedlevel/bdl/bdl.cpp @@ -0,0 +1,195 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(BD_SENSOR) + +#include "../../../MarlinCore.h" +#include "../../../gcode/gcode.h" +#include "../../../module/settings.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" +#include "../../../module/stepper.h" +#include "../../../module/probe.h" +#include "../../../module/temperature.h" +#include "../../../module/endstops.h" +#include "../../babystep.h" + +// I2C software Master library for segment bed heating and bed distance sensor +#include + +#include "bdl.h" +BDS_Leveling bdl; + +//#define DEBUG_OUT_BD + +// M102 S-5 Read raw Calibrate data +// M102 S-6 Start Calibrate +// M102 S4 Set the adjustable Z height value (e.g., 'M102 S4' means it will do adjusting while the Z height <= 0.4mm , disable with 'M102 S0'.) +// M102 S-1 Read sensor information + +#define MAX_BD_HEIGHT 4.0f +#define CMD_START_READ_CALIBRATE_DATA 1017 +#define CMD_END_READ_CALIBRATE_DATA 1018 +#define CMD_START_CALIBRATE 1019 +#define CMD_END_CALIBRATE 1021 +#define CMD_READ_VERSION 1016 + +I2C_SegmentBED BD_I2C_SENSOR; + +#define BD_SENSOR_I2C_ADDR 0x3C + +int8_t BDS_Leveling::config_state; +uint8_t BDS_Leveling::homing; + +void BDS_Leveling::echo_name() { SERIAL_ECHOPGM("Bed Distance Leveling"); } + +void BDS_Leveling::init(uint8_t _sda, uint8_t _scl, uint16_t delay_s) { + int ret = BD_I2C_SENSOR.i2c_init(_sda, _scl, BD_SENSOR_I2C_ADDR, delay_s); + if (ret != 1) SERIAL_ECHOLNPGM("BD_I2C_SENSOR Init Fail return code:", ret); + config_state = 0; +} + +float BDS_Leveling::read() { + const uint16_t tmp = BD_I2C_SENSOR.BD_i2c_read(); + float BD_z = NAN; + if (BD_I2C_SENSOR.BD_Check_OddEven(tmp) && (tmp & 0x3FF) < 1020) + BD_z = (tmp & 0x3FF) / 100.0f; + return BD_z; +} + +void BDS_Leveling::process() { + //if (config_state == 0) return; + static millis_t next_check_ms = 0; // starting at T=0 + static float z_pose = 0.0f; + const millis_t ms = millis(); + if (ELAPSED(ms, next_check_ms)) { // timed out (or first run) + next_check_ms = ms + (config_state < 0 ? 1000 : 100); // check at 1Hz or 10Hz + + unsigned short tmp = 0; + const float cur_z = planner.get_axis_position_mm(Z_AXIS); //current_position.z + static float old_cur_z = cur_z, + old_buf_z = current_position.z; + + tmp = BD_I2C_SENSOR.BD_i2c_read(); + if (BD_I2C_SENSOR.BD_Check_OddEven(tmp) && (tmp & 0x3FF) < 1020) { + const float z_sensor = (tmp & 0x3FF) / 100.0f; + if (cur_z < 0) config_state = 0; + //float abs_z = current_position.z > cur_z ? (current_position.z - cur_z) : (cur_z - current_position.z); + if ( cur_z < config_state * 0.1f + && config_state > 0 + && old_cur_z == cur_z + && old_buf_z == current_position.z + && z_sensor < (MAX_BD_HEIGHT) + ) { + babystep.set_mm(Z_AXIS, cur_z - z_sensor); + #if ENABLED(DEBUG_OUT_BD) + SERIAL_ECHOLNPGM("BD:", z_sensor, ", Z:", cur_z, "|", current_position.z); + #endif + } + else { + babystep.set_mm(Z_AXIS, 0); + //if (old_cur_z <= cur_z) Z_DIR_WRITE(!INVERT_Z_DIR); + stepper.set_directions(); + } + old_cur_z = cur_z; + old_buf_z = current_position.z; + endstops.bdp_state_update(z_sensor <= 0.01f); + //endstops.update(); + } + else + stepper.set_directions(); + + #if ENABLED(DEBUG_OUT_BD) + SERIAL_ECHOLNPGM("BD:", tmp & 0x3FF, ", Z:", cur_z, "|", current_position.z); + if (BD_I2C_SENSOR.BD_Check_OddEven(tmp) == 0) SERIAL_ECHOLNPGM("errorCRC"); + #endif + + if ((tmp & 0x3FF) > 1020) { + BD_I2C_SENSOR.BD_i2c_stop(); + safe_delay(10); + } + + // read raw calibrate data + if (config_state == -5) { + BD_I2C_SENSOR.BD_i2c_write(CMD_START_READ_CALIBRATE_DATA); + safe_delay(1000); + + for (int i = 0; i < MAX_BD_HEIGHT * 10; i++) { + tmp = BD_I2C_SENSOR.BD_i2c_read(); + SERIAL_ECHOLNPGM("Calibrate data:", i, ",", tmp & 0x3FF, ", check:", BD_I2C_SENSOR.BD_Check_OddEven(tmp)); + safe_delay(500); + } + config_state = 0; + BD_I2C_SENSOR.BD_i2c_write(CMD_END_READ_CALIBRATE_DATA); + safe_delay(500); + } + else if (config_state <= -6) { // Start Calibrate + safe_delay(100); + if (config_state == -6) { + //BD_I2C_SENSOR.BD_i2c_write(1019); // begin calibrate + //delay(1000); + gcode.stepper_inactive_time = SEC_TO_MS(60 * 5); + gcode.process_subcommands_now(F("M17 Z")); + gcode.process_subcommands_now(F("G1 Z0.0")); + z_pose = 0; + safe_delay(1000); + BD_I2C_SENSOR.BD_i2c_write(CMD_START_CALIBRATE); // Begin calibrate + SERIAL_ECHOLNPGM("Begin calibrate"); + safe_delay(2000); + config_state = -7; + } + else if (planner.get_axis_position_mm(Z_AXIS) < 10.0f) { + if (z_pose >= MAX_BD_HEIGHT) { + BD_I2C_SENSOR.BD_i2c_write(CMD_END_CALIBRATE); // End calibrate + SERIAL_ECHOLNPGM("End calibrate data"); + z_pose = 7; + config_state = 0; + safe_delay(1000); + } + else { + float tmp_k = 0; + char tmp_1[30]; + sprintf_P(tmp_1, PSTR("G1 Z%d.%d"), int(z_pose), int(int(z_pose * 10) % 10)); + gcode.process_subcommands_now(tmp_1); + + SERIAL_ECHO(tmp_1); + SERIAL_ECHOLNPGM(" ,Z:", current_position.z); + + while (tmp_k < (z_pose - 0.1f)) { + tmp_k = planner.get_axis_position_mm(Z_AXIS); + safe_delay(1); + } + safe_delay(800); + tmp = (z_pose + 0.0001f) * 10; + BD_I2C_SENSOR.BD_i2c_write(tmp); + SERIAL_ECHOLNPGM("w:", tmp, ",Zpose:", z_pose); + z_pose += 0.1001f; + //queue.enqueue_now_P(PSTR("G90")); + } + } + } + } +} + +#endif // BD_SENSOR diff --git a/Marlin/src/feature/bedlevel/bdl/bdl.h b/Marlin/src/feature/bedlevel/bdl/bdl.h new file mode 100644 index 0000000000..6307b1ab28 --- /dev/null +++ b/Marlin/src/feature/bedlevel/bdl/bdl.h @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ +#pragma once + +#include + +class BDS_Leveling { +public: + static int8_t config_state; + static uint8_t homing; + static void echo_name(); + static void init(uint8_t _sda, uint8_t _scl, uint16_t delay_s); + static void process(); + static float read(); +}; + +extern BDS_Leveling bdl; diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index e22e3cb5f8..a6dff2d75a 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -36,6 +36,10 @@ #include "../../feature/bedlevel/bedlevel.h" #endif +#if ENABLED(BD_SENSOR) + #include "../../feature/bedlevel/bdl/bdl.h" +#endif + #if ENABLED(SENSORLESS_HOMING) #include "../../feature/tmc_util.h" #endif @@ -202,7 +206,9 @@ void GcodeSuite::G28() { DEBUG_SECTION(log_G28, "G28", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) log_machine_info(); - /* + TERN_(BD_SENSOR, bdl.config_state = 0); + + /** * Set the laser power to false to stop the planner from processing the current power setting. */ #if ENABLED(LASER_FEATURE) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index bbfe561ffe..405e2d460c 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -577,6 +577,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 100: M100(); break; // M100: Free Memory Report #endif + #if ENABLED(BD_SENSOR) + case 102: M102(); break; // M102: Configure Bed Distance Sensor + #endif + #if HAS_EXTRUDERS case 104: M104(); break; // M104: Set hot end temperature case 109: M109(); break; // M109: Wait for hotend temperature to reach target diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 135cfc7f43..2b15706395 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -132,6 +132,8 @@ * * M100 - Watch Free Memory (for debugging) (Requires M100_FREE_MEMORY_WATCHER) * + * M102 - Configure Bed Distance Sensor. (Requires BD_SENSOR) + * * M104 - Set extruder target temp. * M105 - Report current temperatures. * M106 - Set print fan speed. @@ -705,6 +707,11 @@ private: static void M100(); #endif + #if ENABLED(BD_SENSOR) + static void M102(); + static void M102_report(const bool forReplay=true); + #endif + #if HAS_EXTRUDERS static void M104_M109(const bool isM109); FORCE_INLINE static void M104() { M104_M109(false); } diff --git a/Marlin/src/gcode/probe/M102.cpp b/Marlin/src/gcode/probe/M102.cpp new file mode 100644 index 0000000000..b70c9aed18 --- /dev/null +++ b/Marlin/src/gcode/probe/M102.cpp @@ -0,0 +1,57 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ + +/** + * M102.cpp - Configure Bed Distance Sensor + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(BD_SENSOR) + +#include "../gcode.h" +#include "../../feature/bedlevel/bdl/bdl.h" + +/** + * M102: Configure the Bed Distance Sensor + * + * M102 S<10ths> : Set adjustable Z height in 10ths of a mm (e.g., 'M102 S4' enables adjusting for Z <= 0.4mm.) + * M102 S0 : Disable adjustable Z height. + * + * Negative S values are commands: + * M102 S-1 : Read sensor information + * M102 S-5 : Read raw Calibration data + * M102 S-6 : Start Calibration + */ +void GcodeSuite::M102() { + if (parser.seenval('S')) + bdl.config_state = parser.value_int(); + else + M102_report(); +} + +void GcodeSuite::M102_report(const bool forReplay/*=true*/) { + report_heading(forReplay, F("Bed Distance Sensor")); + SERIAL_ECHOLNPGM(" M102 S", bdl.config_state); +} + +#endif // BD_SENSOR diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index a6be04e237..c1c174da46 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1103,7 +1103,7 @@ #if ANY(TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, SOLENOID_PROBE, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4, MAG_MOUNTED_PROBE) #define HAS_STOWABLE_PROBE 1 #endif -#if ANY(HAS_STOWABLE_PROBE, HAS_Z_SERVO_PROBE, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE) +#if ANY(HAS_STOWABLE_PROBE, HAS_Z_SERVO_PROBE, FIX_MOUNTED_PROBE, BD_SENSOR, NOZZLE_AS_PROBE) #define HAS_BED_PROBE 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index bdcd1d3fce..ff8730d07b 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1660,8 +1660,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS */ #if 1 < 0 \ + (DISABLED(BLTOUCH) && HAS_Z_SERVO_PROBE) \ - + COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4, MAG_MOUNTED_PROBE) - #error "Please enable only one probe option: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, MAGLEV4, MAG_MOUNTED_PROBE or Z Servo." + + COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, BD_SENSOR, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4, MAG_MOUNTED_PROBE) + #error "Please enable only one probe option: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, BD_SENSOR, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, MAGLEV4, MAG_MOUNTED_PROBE or Z Servo." #endif #if HAS_BED_PROBE diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 054a006aff..e665ac5bca 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -773,3 +773,10 @@ #if MB(BTT_BTT002_V1_0, EINSY_RAMBO) && DISABLED(NO_MK3_FAN_PINS_WARNING) #warning "Define MK3_FAN_PINS to swap hotend and part cooling fan pins. (Define NO_MK3_FAN_PINS_WARNING to suppress this warning.)" #endif + +/** + * BD Sensor should always include BABYSTEPPING + */ +#if ENABLED(BD_SENSOR) && DISABLED(BABYSTEPPING) + #warning "BABYSTEPPING is recommended with BD_SENSOR." +#endif diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 1ee4b92b5f..33c94ae357 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -63,6 +63,13 @@ bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.l volatile Endstops::endstop_mask_t Endstops::hit_state; Endstops::endstop_mask_t Endstops::live_state = 0; +#if ENABLED(BD_SENSOR) + bool Endstops::bdp_state; // = false + #define READ_ENDSTOP(P) ((P == Z_MIN_PIN) ? bdp_state : READ(P)) +#else + #define READ_ENDSTOP(P) READ(P) +#endif + #if ENDSTOP_NOISE_THRESHOLD Endstops::endstop_mask_t Endstops::validated_live_state; uint8_t Endstops::endstop_poll_count; @@ -566,7 +573,7 @@ static void print_es_state(const bool is_hit, FSTR_P const flabel=nullptr) { void __O2 Endstops::report_states() { TERN_(BLTOUCH, bltouch._set_SW_mode()); SERIAL_ECHOLNPGM(STR_M119_REPORT); - #define ES_REPORT(S) print_es_state(READ(S##_PIN) != S##_ENDSTOP_INVERTING, F(STR_##S)) + #define ES_REPORT(S) print_es_state(READ_ENDSTOP(S##_PIN) != S##_ENDSTOP_INVERTING, F(STR_##S)) #if HAS_X_MIN ES_REPORT(X_MIN); #endif @@ -703,7 +710,7 @@ void Endstops::update() { #endif // Macros to update / copy the live_state - #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX))) + #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ_ENDSTOP(_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) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_YX) @@ -1434,7 +1441,7 @@ void Endstops::update() { static uint8_t local_LED_status = 0; uint16_t live_state_local = 0; - #define ES_GET_STATE(S) if (READ(S##_PIN)) SBI(live_state_local, S) + #define ES_GET_STATE(S) if (READ_ENDSTOP(S##_PIN)) SBI(live_state_local, S) #if HAS_X_MIN ES_GET_STATE(X_MIN); diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 9e411adbda..bffa7fdc39 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -166,6 +166,11 @@ class Endstops { */ static void update(); + #if ENABLED(BD_SENSOR) + static bool bdp_state; + static void bdp_state_update(const bool z_state) { bdp_state = z_state; } + #endif + /** * Get Endstop hit state. */ diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index cc6b521fe1..3baef31479 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -44,6 +44,10 @@ #include "../feature/bedlevel/bedlevel.h" #endif +#if ENABLED(BD_SENSOR) + #include "../feature/bedlevel/bdl/bdl.h" +#endif + #if ENABLED(DELTA) #include "delta.h" #endif @@ -878,6 +882,8 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai // Move the probe to the starting XYZ do_blocking_move_to(npos, feedRate_t(XY_PROBE_FEEDRATE_MM_S)); + TERN_(BD_SENSOR, return bdl.read()); + float measured_z = NAN; if (!deploy()) { measured_z = run_z_probe(sanity_check) + offset.z; diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index b759d97098..beea674ced 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -97,6 +97,10 @@ Stepper stepper; // Singleton #include "../MarlinCore.h" #include "../HAL/shared/Delay.h" +#if ENABLED(BD_SENSOR) + #include "../feature/bedlevel/bdl/bdl.h" +#endif + #if ENABLED(INTEGRATED_BABYSTEPPING) #include "../feature/babystep.h" #endif diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 3f21530af7..e9a9aa7de9 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -981,7 +981,7 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #if HAS_Z_AXIS #define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); } - #define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); } + #define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); TERN_(BD_SENSOR, bdl.config_state = 0); } #else #define ENABLE_AXIS_Z() NOOP #define DISABLE_AXIS_Z() NOOP diff --git a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h index 5a82fbcd6d..ed602d8d01 100644 --- a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h +++ b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h @@ -38,6 +38,12 @@ #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif +#if ENABLED(BD_SENSOR) + #define I2C_BD_SDA_PIN PC6 + #define I2C_BD_SCL_PIN PB2 + #define I2C_BD_DELAY 10 // (seconds) +#endif + // // Servos // diff --git a/buildroot/tests/PANDA_PI_V29 b/buildroot/tests/PANDA_PI_V29 new file mode 100755 index 0000000000..a176e571ba --- /dev/null +++ b/buildroot/tests/PANDA_PI_V29 @@ -0,0 +1,19 @@ +#!/usr/bin/env bash +# +# Build tests for PANDA_PI_V29 +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +restore_configs +opt_set MOTHERBOARD BOARD_PANDA_PI_V29 SERIAL_PORT -1 \ + Z_CLEARANCE_DEPLOY_PROBE 0 Z_CLEARANCE_BETWEEN_PROBES 1 Z_CLEARANCE_MULTI_PROBE 1 +opt_enable BD_SENSOR AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING BABYSTEPPING +exec_test $1 $2 "Panda Pi V29 | BD Sensor | ABL-B" "$3" + +# clean up +restore_configs diff --git a/ini/features.ini b/ini/features.ini index b6a07c76df..2f26aa2523 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -99,6 +99,8 @@ HAS_MCP3426_ADC = src_filter=+ + AUTO_BED_LEVELING_(3POINT|(BI)?LINEAR) = src_filter=+ X_AXIS_TWIST_COMPENSATION = src_filter=+ + + +BD_SENSOR = markyue/Panda_SoftMasterI2C + src_filter=+ + MESH_BED_LEVELING = src_filter=+ + AUTO_BED_LEVELING_UBL = src_filter=+ + UBL_HILBERT_CURVE = src_filter=+ diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index d68704216f..1e29ea6de5 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -83,7 +83,8 @@ build_flags = ${common_STM32F103RC_variant.build_flags} -DTIMER_SERVO=TIM1 board_build.offset = 0x5000 board_upload.offset_address = 0x08005000 - +lib_deps = + markyue/Panda_SoftMasterI2C@1.0.3 # # MKS Robin (STM32F103ZET6) # Uses HAL STM32 to support Marlin UI for TFT screen with optional touch panel diff --git a/platformio.ini b/platformio.ini index 4f5598f6af..751543c8a3 100644 --- a/platformio.ini +++ b/platformio.ini @@ -103,6 +103,7 @@ default_src_filter = + - - + - - - - - + - - - - - - - From 7f2a8362517181cde5b98bf88aa48821355f7692 Mon Sep 17 00:00:00 2001 From: ExtNeon <33217029+ExtNeon@users.noreply.github.com> Date: Sat, 6 Aug 2022 23:37:03 +0000 Subject: [PATCH 51/54] =?UTF-8?q?=E2=9C=A8=20SD=20Endstop=20Abort=20G-Code?= =?UTF-8?q?=20(#24461)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 3 +++ Marlin/src/module/endstops.cpp | 4 ++++ 2 files changed, 7 insertions(+) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 921d36b7a8..b1a7662e71 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1589,6 +1589,9 @@ * Endstops must be activated for this option to work. */ //#define SD_ABORT_ON_ENDSTOP_HIT + #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) + //#define SD_ABORT_ON_ENDSTOP_HIT_GCODE "G28XY" // G-code to run on endstop hit (e.g., "G28XY" or "G27") + #endif //#define SD_REPRINT_LAST_SELECTED_FILE // On print completion open the LCD Menu and select the same file diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 33c94ae357..f4fbda747b 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -551,6 +551,10 @@ void Endstops::event_handler() { card.abortFilePrintNow(); quickstop_stepper(); thermalManager.disable_all_heaters(); + #ifdef SD_ABORT_ON_ENDSTOP_HIT_GCODE + queue.clear(); + queue.inject(F(SD_ABORT_ON_ENDSTOP_HIT_GCODE)); + #endif print_job_timer.stop(); } #endif From 8192cc12d33fb860fff55ea68f5df9c9058b0293 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 6 Aug 2022 18:38:12 -0500 Subject: [PATCH 52/54] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20config=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 4 ++-- Marlin/Configuration_adv.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 84e4f49e59..2c16b8fb53 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -551,8 +551,8 @@ // Resistor values when using MAX31865 sensors (-5) on TEMP_SENSOR_0 / 1 #if TEMP_SENSOR_IS_MAX_TC(0) - #define MAX31865_SENSOR_OHMS_0 100 // (Ω) Typically 100 or 1000 (PT100 or PT1000) - #define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for Adafruit PT100; 4300 for Adafruit PT1000 + #define MAX31865_SENSOR_OHMS_0 100 // (Ω) Typically 100 or 1000 (PT100 or PT1000) + #define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for Adafruit PT100; 4300 for Adafruit PT1000 #endif #if TEMP_SENSOR_IS_MAX_TC(1) #define MAX31865_SENSOR_OHMS_1 100 diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index b1a7662e71..e5d23526db 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -318,7 +318,7 @@ * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set * below 2. */ - #define WATCH_TEMP_PERIOD 20 // Seconds + #define WATCH_TEMP_PERIOD 40 // Seconds #define WATCH_TEMP_INCREASE 2 // Degrees Celsius #endif From 398cae762506a43eb27a815f10bee6e2821c6c5f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 6 Aug 2022 18:39:05 -0500 Subject: [PATCH 53/54] =?UTF-8?q?=F0=9F=94=96=20Version=202.1.1?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Version.h | 4 ++-- Marlin/src/inc/Version.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index f6e4635c8f..d9ec298ede 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "2.1" +//#define SHORT_BUILD_VERSION "2.1.1" /** * Verbose version identifier which should contain a reference to the location @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-06-04" +//#define STRING_DISTRIBUTION_DATE "2022-08-06" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7abbeac785..7fcaee1345 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -25,7 +25,7 @@ * Release version. Leave the Marlin version or apply a custom scheme. */ #ifndef SHORT_BUILD_VERSION - #define SHORT_BUILD_VERSION "2.1" + #define SHORT_BUILD_VERSION "2.1.1" #endif /** @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-06-04" + #define STRING_DISTRIBUTION_DATE "2022-08-06" #endif /** From 419a145fa30dc01315d5b6b69f76253b21bd7a9b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 Aug 2022 20:42:12 -0500 Subject: [PATCH 54/54] =?UTF-8?q?=F0=9F=94=A8=20Update=20schema=20export?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 +- buildroot/share/PlatformIO/scripts/schema.py | 5 ++--- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e5d23526db..6ec969474d 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -48,7 +48,7 @@ * 3 = schema.json - The entire configuration schema. (13 = pattern groups) * 4 = schema.yml - The entire configuration schema. */ -//#define CONFIG_EXPORT // :[1:'JSON', 2:'config.ini', 3:'schema.json', 4:'schema.yml'] +//#define CONFIG_EXPORT 2 // :[1:'JSON', 2:'config.ini', 3:'schema.json', 4:'schema.yml'] //=========================================================================== //============================= Thermal Settings ============================ diff --git a/buildroot/share/PlatformIO/scripts/schema.py b/buildroot/share/PlatformIO/scripts/schema.py index 767748757e..2c20f49dee 100755 --- a/buildroot/share/PlatformIO/scripts/schema.py +++ b/buildroot/share/PlatformIO/scripts/schema.py @@ -95,7 +95,7 @@ def extract(): # Regex for #define NAME [VALUE] [COMMENT] with sanitized line defgrep = re.compile(r'^(//)?\s*(#define)\s+([A-Za-z0-9_]+)\s*(.*?)\s*(//.+)?$') # Defines to ignore - ignore = ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION', 'CONFIG_EXPORT') + ignore = ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION', 'CONFIG_EXAMPLES_DIR', 'CONFIG_EXPORT') # Start with unknown state state = Parse.NORMAL # Serial ID @@ -294,8 +294,6 @@ def extract(): 'sid': sid } - if val != '': define_info['value'] = val - # Type is based on the value if val == '': value_type = 'switch' @@ -318,6 +316,7 @@ def extract(): else 'array' if val[0] == '{' \ else '' + if val != '': define_info['value'] = val if value_type != '': define_info['type'] = value_type # Join up accumulated conditions with &&