Skip to content
Snippets Groups Projects
Marlin.cpp 119 KiB
Newer Older
  • Learn to ignore specific revisions
  •  * Marlin 3D Printer Firmware
    
    Scott Lahteine's avatar
    Scott Lahteine committed
     * Copyright (C) 2016, 2017 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 <http://www.gnu.org/licenses/>.
    
     * About Marlin
     *
     * This firmware is a mashup between Sprinter and grbl.
     *  - https://github.com/kliment/Sprinter
    
     *  - https://github.com/simen/grbl
    
    #include "Marlin.h"
    
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    #include "lcd/ultralcd.h"
    
    #include "module/motion.h"
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    #include "module/planner.h"
    #include "module/stepper.h"
    #include "module/endstops.h"
    #include "module/temperature.h"
    #include "sd/cardreader.h"
    #include "module/configuration_store.h"
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include <pins_arduino.h>
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    #include <math.h>
    #include "libs/nozzle.h"
    #include "libs/duration_t.h"
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    #include "gcode/parser.h"
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    #if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER)
      #include "libs/buzzer.h"
    #endif
    
    
    #if HAS_ABL
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "libs/vector_3.h"
    
      #if ENABLED(AUTO_BED_LEVELING_LINEAR)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
        #include "libs/least_squares_fit.h"
    
      #endif
    #elif ENABLED(MESH_BED_LEVELING)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "feature/mbl/mesh_bed_leveling.h"
    
    #if (ENABLED(SWITCHING_EXTRUDER) && !DONT_SWITCH) || ENABLED(SWITCHING_NOZZLE)
      #include "module/tool_change.h"
    #endif
    
    
    #if ENABLED(BEZIER_CURVE_SUPPORT)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "module/planner_bezier.h"
    
    #if ENABLED(MAX7219_DEBUG)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "feature/Max7219_Debug_LEDs.h"
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    #if HAS_COLOR_LEDS
      #include "feature/leds/leds.h"
    
    dot-bob's avatar
    dot-bob committed
    #endif
    
    
    #if HAS_SERVOS
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "HAL/servo.h"
    
    #endif
    
    #if HAS_DIGIPOTSS
      #include <SPI.h>
    #endif
    
    #if ENABLED(DAC_STEPPER_CURRENT)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "feature/dac/stepper_dac.h"
    
    #endif
    
    #if ENABLED(EXPERIMENTAL_I2CBUS)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "feature/twibus.h"
    
    #if ENABLED(I2C_POSITION_ENCODERS)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "feature/I2CPositionEncoder.h"
    
    #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "HAL/HAL_endstop_interrupts.h"
    
    #if ENABLED(M100_FREE_MEMORY_WATCHER)
    
      void M100_dump_routine(const char * const title, const char *start, const char *end);
    
    Richard Wackerbarth's avatar
    Richard Wackerbarth committed
    #endif
    
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      CardReader card;
    
    #if ENABLED(EXPERIMENTAL_I2CBUS)
      TWIBus i2c;
    #endif
    
    
    #if ENABLED(G38_PROBE_TARGET)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      bool G38_move = false,
           G38_endstop_hit = false;
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    #if ENABLED(AUTO_BED_LEVELING_UBL)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #include "feature/ubl/ubl.h"
    
      extern bool defer_return_to_status;
    
      unified_bed_leveling ubl;
    
      #define UBL_MESH_VALID !( ( ubl.z_values[0][0] == ubl.z_values[0][1] && ubl.z_values[0][1] == ubl.z_values[0][2] \
                               && ubl.z_values[1][0] == ubl.z_values[1][1] && ubl.z_values[1][1] == ubl.z_values[1][2] \
                               && ubl.z_values[2][0] == ubl.z_values[2][1] && ubl.z_values[2][1] == ubl.z_values[2][2] \
                               && ubl.z_values[0][0] == 0 && ubl.z_values[1][0] == 0 && ubl.z_values[2][0] == 0 )  \
                               || isnan(ubl.z_values[0][0]))
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    #endif
    
    
    #if ENABLED(SENSORLESS_HOMING)
      #include "feature/tmc2130.h"
    #endif
    
    
    bool Running = true;
    
    
    /**
     * axis_homed
     *   Flags that each linear axis was homed.
     *   XYZ on cartesian, ABC on delta, ABZ on SCARA.
     *
     * axis_known_position
     *   Flags that the position is known in each linear axis. Set when homed.
     *   Cleared whenever a stepper powers off, potentially losing its position.
     */
    bool axis_homed[XYZ] = { false }, axis_known_position[XYZ] = { false };
    
    #if ENABLED(TEMPERATURE_UNITS_SUPPORT)
      TempUnit input_temp_units = TEMPUNIT_C;
    #endif
    
    
    /**
     * Feed rates are often configured with mm/m
     * but the planner and stepper like mm/s units.
     */
    
    static const float homing_feedrate_mm_s[] PROGMEM = {
    
      #if ENABLED(DELTA)
    
        MMM_TO_MMS(HOMING_FEEDRATE_Z), MMM_TO_MMS(HOMING_FEEDRATE_Z),
    
        MMM_TO_MMS(HOMING_FEEDRATE_XY), MMM_TO_MMS(HOMING_FEEDRATE_XY),
    
      MMM_TO_MMS(HOMING_FEEDRATE_Z), 0
    
    FORCE_INLINE float homing_feedrate(const AxisEnum a) { return pgm_read_float(&homing_feedrate_mm_s[a]); }
    
    
    static float saved_feedrate_mm_s;
    
    int16_t feedrate_percentage = 100, saved_feedrate_percentage,
    
        flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100);
    
    // Initialized by settings.load()
    
    float filament_size[EXTRUDERS], volumetric_multiplier[EXTRUDERS];
    
    #if HAS_WORKSPACE_OFFSET
      #if HAS_POSITION_SHIFT
        // The distance that XYZ has been offset by G92. Reset by G28.
        float position_shift[XYZ] = { 0 };
      #endif
      #if HAS_HOME_OFFSET
        // This offset is added to the configured home position.
        // Set by M206, M428, or menu item. Saved to EEPROM.
        float home_offset[XYZ] = { 0 };
      #endif
      #if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
        // The above two are combined to save on computes
        float workspace_offset[XYZ] = { 0 };
      #endif
    
    #if FAN_COUNT > 0
    
      int16_t fanSpeeds[FAN_COUNT] = { 0 };
    
      #if ENABLED(PROBING_FANS_OFF)
        bool fans_paused = false;
        int16_t paused_fanSpeeds[FAN_COUNT] = { 0 };
      #endif
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    // For M109 and M190, this flag may be cleared (by M108) to exit the wait loop
    
    volatile bool wait_for_heatup = true;
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    // For M0/M1, this flag may be cleared (by M108) to exit the wait-for-user loop
    
    #if HAS_RESUME_CONTINUE
    
      volatile bool wait_for_user = false;
    
    // Inactivity shutdown
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    millis_t previous_cmd_ms = 0;
    static millis_t max_inactive_time = 0;
    
    static millis_t stepper_inactive_time = (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL;
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    
    // Print Job Timer
    
    João Brázio's avatar
    João Brázio committed
    #if ENABLED(PRINTCOUNTER)
      PrintCounter print_job_timer = PrintCounter();
    #else
      Stopwatch print_job_timer = Stopwatch();
    #endif
    
    #if HAS_BED_PROBE
    
      float zprobe_zoffset; // Initialized by settings.load()
    
      float xy_probe_feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED);
      #define XY_PROBE_FEEDRATE_MM_S xy_probe_feedrate_mm_s
    
    #elif defined(XY_PROBE_SPEED)
    
      #define XY_PROBE_FEEDRATE_MM_S MMM_TO_MMS(XY_PROBE_SPEED)
    
      #define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE()
    
    #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
    
      #if ENABLED(DELTA)
        #define ADJUST_DELTA(V) \
          if (planner.abl_enabled) { \
            const float zadj = bilinear_z_offset(V); \
            delta[A_AXIS] += zadj; \
            delta[B_AXIS] += zadj; \
            delta[C_AXIS] += zadj; \
          }
      #else
        #define ADJUST_DELTA(V) if (planner.abl_enabled) { delta[Z_AXIS] += bilinear_z_offset(V); }
      #endif
    
    #elif IS_KINEMATIC
      #define ADJUST_DELTA(V) NOOP
    #endif
    
    
    #if ENABLED(Z_DUAL_ENDSTOPS)
    
    // Extruder offsets
    
    #if HOTENDS > 1
    
      float hotend_offset[XYZ][HOTENDS]; // Initialized by settings.load()
    
    #if HAS_Z_SERVO_ENDSTOP
    
      const int z_servo_angle[2] = Z_SERVO_ANGLES;
    
      uint8_t baricuda_valve_pressure = 0,
              baricuda_e_to_p_pressure = 0;
    
    #if HAS_POWER_SWITCH
      bool powersupply_on =
    
        #if ENABLED(PS_DEFAULT_OFF)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
          false
        #else
    
    Scott Lahteine's avatar
    Scott Lahteine committed
        #endif
      ;
    
      float delta[ABC],
            endstop_adj[ABC] = { 0 };
    
    
      // Initialized by settings.load()
    
      float delta_radius,
    
            delta_tower_angle_trim[2],
    
            delta_tower[ABC][2],
            delta_diagonal_rod,
    
            delta_calibration_radius,
    
            delta_diagonal_rod_2_tower[ABC],
            delta_segments_per_second,
    
            delta_clip_start_height = Z_MAX_POS;
    
    
      float delta_safe_distance_from_top();
    
    #if ENABLED(AUTO_BED_LEVELING_BILINEAR)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      int bilinear_grid_spacing[2], bilinear_start[2];
    
      float bilinear_grid_factor[2],
            z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
    
    #if IS_SCARA
      // Float constants for SCARA calculations
      const float L1 = SCARA_LINKAGE_1, L2 = SCARA_LINKAGE_2,
                  L1_2 = sq(float(L1)), L1_2_2 = 2.0 * L1_2,
                  L2_2 = sq(float(L2));
    
    
      float delta_segments_per_second = SCARA_SEGMENTS_PER_SECOND,
    
            delta[ABC];
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    float cartes[XYZ] = { 0 };
    
    
    #if ENABLED(FILAMENT_WIDTH_SENSOR)
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      bool filament_sensor = false;                                 // M405 turns on filament sensor control. M406 turns it off.
      float filament_width_nominal = DEFAULT_NOMINAL_FILAMENT_DIA,  // Nominal filament width. Change with M404.
    
            filament_width_meas = DEFAULT_MEASURED_FILAMENT_DIA;    // Measured filament diameter
    
      uint8_t meas_delay_cm = MEASUREMENT_DELAY_CM,                 // Distance delay setting
              measurement_delay[MAX_MEASUREMENT_DELAY + 1];         // Ring buffer to delayed measurement. Store extruder factor after subtracting 100
      int8_t filwidth_delay_index[2] = { 0, -1 };                   // Indexes into ring buffer
    
    #if ENABLED(FILAMENT_RUNOUT_SENSOR)
    
      static bool filament_ran_out = false;
    
    #if ENABLED(ADVANCED_PAUSE_FEATURE)
      AdvancedPauseMenuResponse advanced_pause_menu_response;
    
    #if ENABLED(MIXING_EXTRUDER)
    
      float mixing_factor[MIXING_STEPPERS]; // Reciprocal of mix proportion. 0.0 = off, otherwise >= 1.0.
    
      #if MIXING_VIRTUAL_TOOLS > 1
        float mixing_virtual_tool_mix[MIXING_VIRTUAL_TOOLS][MIXING_STEPPERS];
      #endif
    #endif
    
    
      HAL_SERVO_LIB servo[NUM_SERVOS];
    
      #define MOVE_SERVO(I, P) servo[I].move(P)
    
      #if HAS_Z_SERVO_ENDSTOP
        #define DEPLOY_Z_SERVO() MOVE_SERVO(Z_ENDSTOP_SERVO_NR, z_servo_angle[0])
        #define STOW_Z_SERVO() MOVE_SERVO(Z_ENDSTOP_SERVO_NR, z_servo_angle[1])
      #endif
    
    blddk's avatar
    blddk committed
    #ifdef CHDK
    
      millis_t chdkHigh = 0;
    
      bool chdkActive = false;
    
    blddk's avatar
    blddk committed
    #endif
    
    
    #if ENABLED(PID_EXTRUSION_SCALING)
    
      int lpq_len = 20;
    #endif
    
    
    #if ENABLED(HOST_KEEPALIVE_FEATURE)
    
      MarlinBusyState busy_state = NOT_BUSY;
    
      static millis_t next_busy_signal_ms = 0;
    
      uint8_t host_keepalive_interval = DEFAULT_KEEPALIVE_INTERVAL;
    
      #define host_keepalive() NOOP
    #endif
    
    #if ENABLED(I2C_POSITION_ENCODERS)
      I2CPositionEncodersMgr I2CPEM;
      uint8_t blockBufferIndexRef = 0;
      millis_t lastUpdateMillis;
    #endif
    
    
    #if ENABLED(CNC_WORKSPACE_PLANES)
      static WorkspacePlane workspace_plane = PLANE_XY;
    #endif
    
    
    jbrazio's avatar
    jbrazio committed
    /**
     * ***************************************************************************
     * ******************************** FUNCTIONS ********************************
     * ***************************************************************************
     */
    
    void stop();
    
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    void get_cartesian_from_steppers();
    
    void set_current_from_steppers_for_axis(const AxisEnum axis);
    
    #if ENABLED(BEZIER_CURVE_SUPPORT)
      void plan_cubic_move(const float offset[4]);
    #endif
    
    
    void report_current_position();
    
    #if ENABLED(DIGIPOT_I2C)
    
      extern void digipot_i2c_set_current(uint8_t channel, float current);
    
      extern void digipot_i2c_init();
    #endif
    
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    void setup_killpin() {
    
      #if HAS_KILL
    
        SET_INPUT_PULLUP(KILL_PIN);
    
    #if ENABLED(FILAMENT_RUNOUT_SENSOR)
    
      void setup_filrunoutpin() {
    
        #if ENABLED(ENDSTOPPULLUP_FIL_RUNOUT)
    
          SET_INPUT_PULLUP(FIL_RUNOUT_PIN);
        #else
          SET_INPUT(FIL_RUNOUT_PIN);
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    void setup_powerhold() {
    
      #if HAS_SUICIDE
    
        OUT_WRITE(SUICIDE_PIN, HIGH);
    
      #if HAS_POWER_SWITCH
    
        #if ENABLED(PS_DEFAULT_OFF)
    
          OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP);
    
          OUT_WRITE(PS_ON_PIN, PS_ON_AWAKE);
        #endif
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    void suicide() {
    
      #if HAS_SUICIDE
    
        OUT_WRITE(SUICIDE_PIN, LOW);
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    void servo_init() {
    
      #if NUM_SERVOS >= 1 && HAS_SERVO_0
    
        servo[0].attach(SERVO0_PIN);
    
    AnHardt's avatar
    AnHardt committed
        servo[0].detach(); // Just set up the pin. We don't have a position yet. Don't move to a random position.
    
      #if NUM_SERVOS >= 2 && HAS_SERVO_1
    
        servo[1].attach(SERVO1_PIN);
    
    AnHardt's avatar
    AnHardt committed
        servo[1].detach();
    
      #if NUM_SERVOS >= 3 && HAS_SERVO_2
    
        servo[2].attach(SERVO2_PIN);
    
    AnHardt's avatar
    AnHardt committed
        servo[2].detach();
    
      #if NUM_SERVOS >= 4 && HAS_SERVO_3
    
        servo[3].attach(SERVO3_PIN);
    
    AnHardt's avatar
    AnHardt committed
        servo[3].detach();
    
      #if HAS_Z_SERVO_ENDSTOP
    
    AnHardt's avatar
    AnHardt committed
        /**
    
         * Set position of Z Servo Endstop
    
    AnHardt's avatar
    AnHardt committed
         *
         * The servo might be deployed and positioned too low to stow
         * when starting up the machine or rebooting the board.
         * There's no way to know where the nozzle is positioned until
         * homing has been done - no homing with z-probe without init!
         *
         */
    
        STOW_Z_SERVO();
    
    /**
     * Stepper Reset (RigidBoard, et.al.)
     */
    #if HAS_STEPPER_RESET
      void disableStepperDrivers() {
    
        OUT_WRITE(STEPPER_RESET_PIN, LOW);  // drive it down to hold in reset motor driver chips
    
      void enableStepperDrivers() { SET_INPUT(STEPPER_RESET_PIN); }  // set to input, which allows it to be pulled high by pullups
    
    #if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0
    
    
      void i2c_on_receive(int bytes) { // just echo all bytes received to serial
        i2c.receive(bytes);
      }
    
      void i2c_on_request() {          // just send dummy data for now
    
        i2c.reply("Hello World!\n");
    
    #if HAS_WORKSPACE_OFFSET || ENABLED(DUAL_X_CARRIAGE)
    
      /**
       * Software endstops can be used to monitor the open end of
       * an axis that has a hardware endstop on the other end. Or
       * they can prevent axes from moving past endstops and grinding.
       *
       * To keep doing their job as the coordinate system changes,
       * the software endstop positions must be refreshed to remain
       * at the same positions relative to the machine.
       */
      void update_software_endstops(const AxisEnum axis) {
    
        const float offs = 0.0
          #if HAS_HOME_OFFSET
            + home_offset[axis]
          #endif
          #if HAS_POSITION_SHIFT
            + position_shift[axis]
          #endif
        ;
    
        #if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
          workspace_offset[axis] = offs;
        #endif
    
        #if ENABLED(DUAL_X_CARRIAGE)
          if (axis == X_AXIS) {
    
            // In Dual X mode hotend_offset[X] is T1's home position
            float dual_max_x = max(hotend_offset[X_AXIS][1], X2_MAX_POS);
    
            if (active_extruder != 0) {
              // T1 can move from X2_MIN_POS to X2_MAX_POS or X2 home position (whichever is larger)
              soft_endstop_min[X_AXIS] = X2_MIN_POS + offs;
              soft_endstop_max[X_AXIS] = dual_max_x + offs;
            }
            else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) {
              // In Duplication Mode, T0 can move as far left as X_MIN_POS
              // but not so far to the right that T1 would move past the end
              soft_endstop_min[X_AXIS] = base_min_pos(X_AXIS) + offs;
              soft_endstop_max[X_AXIS] = min(base_max_pos(X_AXIS), dual_max_x - duplicate_extruder_x_offset) + offs;
            }
            else {
              // In other modes, T0 can move from X_MIN_POS to X_MAX_POS
              soft_endstop_min[axis] = base_min_pos(axis) + offs;
              soft_endstop_max[axis] = base_max_pos(axis) + offs;
            }
    
        #elif ENABLED(DELTA)
          soft_endstop_min[axis] = base_min_pos(axis) + (axis == Z_AXIS ? 0 : offs);
          soft_endstop_max[axis] = base_max_pos(axis) + offs;
    
        #else
          soft_endstop_min[axis] = base_min_pos(axis) + offs;
          soft_endstop_max[axis] = base_max_pos(axis) + offs;
        #endif
    
        #if ENABLED(DEBUG_LEVELING_FEATURE)
          if (DEBUGGING(LEVELING)) {
            SERIAL_ECHOPAIR("For ", axis_codes[axis]);
    
              SERIAL_ECHOPAIR(" axis:\n home_offset = ", home_offset[axis]);
    
            #endif
            #if HAS_POSITION_SHIFT
    
              SERIAL_ECHOPAIR("\n position_shift = ", position_shift[axis]);
            #endif
            SERIAL_ECHOPAIR("\n soft_endstop_min = ", soft_endstop_min[axis]);
            SERIAL_ECHOLNPAIR("\n soft_endstop_max = ", soft_endstop_max[axis]);
          }
        #endif
    
        #if ENABLED(DELTA)
          if (axis == Z_AXIS)
            delta_clip_start_height = soft_endstop_max[axis] - delta_safe_distance_from_top();
        #endif
      }
    
    #endif // HAS_WORKSPACE_OFFSET || DUAL_X_CARRIAGE
    
      /**
       * Change the home offset for an axis, update the current
       * position and the software endstops to retain the same
       * relative distance to the new home.
       *
       * Since this changes the current_position, code should
       * call sync_plan_position soon after this.
       */
    
      static void set_home_offset(const AxisEnum axis, const float v) {
    
        current_position[axis] += v - home_offset[axis];
        home_offset[axis] = v;
        update_software_endstops(axis);
      }
    
    #endif // HAS_M206_COMMAND
    
    /**
     * Set an axis' current position to its home position (after homing).
     *
     * For Core and Cartesian robots this applies one-to-one when an
     * individual axis has been homed.
     *
     * DELTA should wait until all homing is done before setting the XYZ
     * current_position to home, because homing is a single operation.
     * In the case where the axis positions are already known and previously
     * homed, DELTA could home to X or Y individually by moving either one
     * to the center. However, homing Z always homes XY and Z.
     *
     * SCARA should wait until all XY homing is done before setting the XY
     * current_position to home, because neither X nor Y is at home until
     * both are at home. Z can however be homed individually.
    
     * Callers must sync the planner position after calling this!
    
    static void set_axis_is_at_home(const AxisEnum axis) {
    
      #if ENABLED(DEBUG_LEVELING_FEATURE)
        if (DEBUGGING(LEVELING)) {
    
          SERIAL_ECHOPAIR(">>> set_axis_is_at_home(", axis_codes[axis]);
    
          SERIAL_CHAR(')');
    
          SERIAL_EOL();
    
      axis_known_position[axis] = axis_homed[axis] = true;
    
    
        position_shift[axis] = 0;
        update_software_endstops(axis);
      #endif
    
      #if ENABLED(DUAL_X_CARRIAGE)
    
        if (axis == X_AXIS && (active_extruder == 1 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) {
          current_position[X_AXIS] = x_home_pos(active_extruder);
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #endif
    
    
    Scott Lahteine's avatar
    Scott Lahteine committed
      #if ENABLED(MORGAN_SCARA)
    
        /**
         * Morgan SCARA homes XY at the same time
         */
    
        if (axis == X_AXIS || axis == Y_AXIS) {
    
    Scott Lahteine's avatar
    Scott Lahteine committed
          float homeposition[XYZ];
    
          LOOP_XYZ(i) homeposition[i] = LOGICAL_POSITION(base_home_pos((AxisEnum)i), i);
    
    Scott Lahteine's avatar
    Scott Lahteine committed
          // SERIAL_ECHOPAIR("homeposition X:", homeposition[X_AXIS]);
          // SERIAL_ECHOLNPAIR(" Y:", homeposition[Y_AXIS]);
    
    Scott Lahteine's avatar
    Scott Lahteine committed
           * Get Home position SCARA arm angles using inverse kinematics,
           * and calculate homing offset using forward kinematics
    
    jbrazio's avatar
    jbrazio committed
           */
    
          inverse_kinematics(homeposition);
    
    Scott Lahteine's avatar
    Scott Lahteine committed
          forward_kinematics_SCARA(delta[A_AXIS], delta[B_AXIS]);
    
    Scott Lahteine's avatar
    Scott Lahteine committed
          // SERIAL_ECHOPAIR("Cartesian X:", cartes[X_AXIS]);
          // SERIAL_ECHOLNPAIR(" Y:", cartes[Y_AXIS]);
    
    Scott Lahteine's avatar
    Scott Lahteine committed
          current_position[axis] = LOGICAL_POSITION(cartes[axis], axis);
    
    jbrazio's avatar
    jbrazio committed
          /**
           * SCARA home positions are based on configuration since the actual
           * limits are determined by the inverse kinematic transform.
           */
    
    Scott Lahteine's avatar
    Scott Lahteine committed
          soft_endstop_min[axis] = base_min_pos(axis); // + (cartes[axis] - base_home_pos(axis));
          soft_endstop_max[axis] = base_max_pos(axis); // + (cartes[axis] - base_home_pos(axis));
    
    Scott Lahteine's avatar
    Scott Lahteine committed
        }
    
        current_position[axis] = LOGICAL_POSITION(base_home_pos(axis), axis);
    
      /**
       * Z Probe Z Homing? Account for the probe's Z offset.
       */
      #if HAS_BED_PROBE && Z_HOME_DIR < 0
    
        if (axis == Z_AXIS) {
    
          #if HOMING_Z_WITH_PROBE
    
            current_position[Z_AXIS] -= zprobe_zoffset;
    
            #if ENABLED(DEBUG_LEVELING_FEATURE)
              if (DEBUGGING(LEVELING)) {
                SERIAL_ECHOLNPGM("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***");
                SERIAL_ECHOLNPAIR("> zprobe_zoffset = ", zprobe_zoffset);
              }
    
    
          #elif ENABLED(DEBUG_LEVELING_FEATURE)
    
            if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("*** Z HOMED TO ENDSTOP (Z_MIN_PROBE_ENDSTOP) ***");
    
    
      #if ENABLED(DEBUG_LEVELING_FEATURE)
        if (DEBUGGING(LEVELING)) {
    
            SERIAL_ECHOPAIR("> home_offset[", axis_codes[axis]);
            SERIAL_ECHOLNPAIR("] = ", home_offset[axis]);
          #endif
    
          DEBUG_POS("", current_position);
    
          SERIAL_ECHOPAIR("<<< set_axis_is_at_home(", axis_codes[axis]);
    
          SERIAL_CHAR(')');
    
          SERIAL_EOL();
    
    
      #if ENABLED(I2C_POSITION_ENCODERS)
        I2CPEM.homed(axis);
      #endif
    
     * Some planner shorthand inline functions
    
    inline float get_homing_bump_feedrate(const AxisEnum axis) {
    
    Bob-the-Kuhn's avatar
    Bob-the-Kuhn committed
      static const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR;
    
      uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]);
    
        SERIAL_ECHO_START();
    
        SERIAL_ECHOLNPGM("Warning: Homing Bump Divisor < 1");
    
      return homing_feedrate(axis) / hbd;
    
    /**
     *  Plan a move to (X, Y, Z) and set the current_position
     *  The final current_position may not be the one that was requested
     */
    
    void do_blocking_move_to(const float &lx, const float &ly, const float &lz, const float &fr_mm_s/*=0.0*/) {
    
      const float old_feedrate_mm_s = feedrate_mm_s;
    
      #if ENABLED(DEBUG_LEVELING_FEATURE)
    
        if (DEBUGGING(LEVELING)) print_xyz(PSTR(">>> do_blocking_move_to"), NULL, lx, ly, lz);
    
        if (!position_is_reachable_xy(lx, ly)) return;
    
    oldmcg's avatar
    oldmcg committed
    
    
        feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S;
    
        set_destination_to_current();          // sync destination at the start
    
    
        #if ENABLED(DEBUG_LEVELING_FEATURE)
    
          if (DEBUGGING(LEVELING)) DEBUG_POS("set_destination_to_current", destination);
    
        // when in the danger zone
        if (current_position[Z_AXIS] > delta_clip_start_height) {
    
          if (lz > delta_clip_start_height) {   // staying in the danger zone
            destination[X_AXIS] = lx;           // move directly (uninterpolated)
            destination[Y_AXIS] = ly;
            destination[Z_AXIS] = lz;
    
            prepare_uninterpolated_move_to_destination(); // set_current_to_destination
    
            #if ENABLED(DEBUG_LEVELING_FEATURE)
    
              if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position);
    
            destination[Z_AXIS] = delta_clip_start_height;
    
            prepare_uninterpolated_move_to_destination(); // set_current_to_destination
    
            #if ENABLED(DEBUG_LEVELING_FEATURE)
    
              if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position);
    
        if (lz > current_position[Z_AXIS]) {    // raising?
          destination[Z_AXIS] = lz;
    
          prepare_uninterpolated_move_to_destination();   // set_current_to_destination
    
          #if ENABLED(DEBUG_LEVELING_FEATURE)
    
            if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position);
    
        destination[X_AXIS] = lx;
        destination[Y_AXIS] = ly;
    
        prepare_move_to_destination();         // set_current_to_destination
    
        #if ENABLED(DEBUG_LEVELING_FEATURE)
    
          if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position);
    
        if (lz < current_position[Z_AXIS]) {    // lowering?
          destination[Z_AXIS] = lz;
    
          prepare_uninterpolated_move_to_destination();   // set_current_to_destination
    
          #if ENABLED(DEBUG_LEVELING_FEATURE)
    
            if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position);
    
        if (!position_is_reachable_xy(lx, ly)) return;
    
    oldmcg's avatar
    oldmcg committed
    
    
        set_destination_to_current();
    
        // If Z needs to raise, do it before moving XY
    
        if (destination[Z_AXIS] < lz) {
          destination[Z_AXIS] = lz;
    
          prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS));
    
        destination[X_AXIS] = lx;
        destination[Y_AXIS] = ly;
    
        prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S);
    
    
        // If Z needs to lower, do it after moving XY
    
        if (destination[Z_AXIS] > lz) {
          destination[Z_AXIS] = lz;
    
          prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS));
    
        // If Z needs to raise, do it before moving XY
    
        if (current_position[Z_AXIS] < lz) {
    
          feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS);
    
          current_position[Z_AXIS] = lz;
    
          line_to_current_position();
    
        feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S;
    
        current_position[X_AXIS] = lx;
        current_position[Y_AXIS] = ly;
    
        line_to_current_position();
    
        // If Z needs to lower, do it after moving XY
    
        if (current_position[Z_AXIS] > lz) {
    
          feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS);
    
          current_position[Z_AXIS] = lz;
    
          line_to_current_position();
        }
    
      feedrate_mm_s = old_feedrate_mm_s;
    
    
      #if ENABLED(DEBUG_LEVELING_FEATURE)
        if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to");
      #endif
    
    void do_blocking_move_to_x(const float &lx, const float &fr_mm_s/*=0.0*/) {
      do_blocking_move_to(lx, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_s);
    
    void do_blocking_move_to_z(const float &lz, const float &fr_mm_s/*=0.0*/) {
      do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], lz, fr_mm_s);
    
    void do_blocking_move_to_xy(const float &lx, const float &ly, const float &fr_mm_s/*=0.0*/) {
      do_blocking_move_to(lx, ly, current_position[Z_AXIS], fr_mm_s);
    
    //
    // Prepare to do endstop or probe moves
    // with custom feedrates.
    //
    //  - Save current feedrates
    //  - Reset the rate multiplier
    //  - Reset the command timeout
    //  - Enable the endstops (for endstop moves)
    //
    static void setup_for_endstop_or_probe_move() {
      #if ENABLED(DEBUG_LEVELING_FEATURE)
        if (DEBUGGING(LEVELING)) DEBUG_POS("setup_for_endstop_or_probe_move", current_position);
      #endif
    
      saved_feedrate_mm_s = feedrate_mm_s;
    
      saved_feedrate_percentage = feedrate_percentage;
      feedrate_percentage = 100;
    
      gcode.refresh_cmd_timeout();
    
    }
    
    static void clean_up_after_endstop_or_probe_move() {
      #if ENABLED(DEBUG_LEVELING_FEATURE)
        if (DEBUGGING(LEVELING)) DEBUG_POS("clean_up_after_endstop_or_probe_move", current_position);
      #endif
    
      feedrate_mm_s = saved_feedrate_mm_s;
    
      feedrate_percentage = saved_feedrate_percentage;
    
      gcode.refresh_cmd_timeout();
    
       * Raise Z to a minimum height to make room for a probe to move
    
      inline void do_probe_raise(const float z_raise) {
    
        #if ENABLED(DEBUG_LEVELING_FEATURE)
          if (DEBUGGING(LEVELING)) {
            SERIAL_ECHOPAIR("do_probe_raise(", z_raise);
    
            SERIAL_CHAR(')');
    
            SERIAL_EOL();
    
        float z_dest = z_raise;
    
        if (zprobe_zoffset < 0) z_dest -= zprobe_zoffset;
    
        if (z_dest > current_position[Z_AXIS])
    
          do_blocking_move_to_z(z_dest);
    
    #endif // HAS_BED_PROBE
    
    Scott Lahteine's avatar
    Scott Lahteine committed
    #if HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) || ENABLED(DELTA_AUTO_CALIBRATION)
    
    
      bool axis_unhomed_error(const bool x/*=true*/, const bool y/*=true*/, const bool z/*=true*/) {
    
        #if ENABLED(HOME_AFTER_DEACTIVATE)
          const bool xx = x && !axis_known_position[X_AXIS],
                     yy = y && !axis_known_position[Y_AXIS],
                     zz = z && !axis_known_position[Z_AXIS];
        #else
          const bool xx = x && !axis_homed[X_AXIS],
                     yy = y && !axis_homed[Y_AXIS],
                     zz = z && !axis_homed[Z_AXIS];
        #endif
    
    João Brázio's avatar
    João Brázio committed
        if (xx || yy || zz) {
    
          SERIAL_ECHO_START();
    
    João Brázio's avatar
    João Brázio committed
          SERIAL_ECHOPGM(MSG_HOME " ");
          if (xx) SERIAL_ECHOPGM(MSG_X);
          if (yy) SERIAL_ECHOPGM(MSG_Y);
          if (zz) SERIAL_ECHOPGM(MSG_Z);
          SERIAL_ECHOLNPGM(" " MSG_FIRST);
    
          #if ENABLED(ULTRA_LCD)
    
            lcd_status_printf_P(0, PSTR(MSG_HOME " %s%s%s " MSG_FIRST), xx ? MSG_X : "", yy ? MSG_Y : "", zz ? MSG_Z : "");
    
    João Brázio's avatar
    João Brázio committed
          #endif
          return true;
        }
        return false;
    
    João Brázio's avatar
    João Brázio committed
    #endif
    
    #if ENABLED(Z_PROBE_SLED)
    
      #ifndef SLED_DOCKING_OFFSET
        #define SLED_DOCKING_OFFSET 0
      #endif
    
      /**
       * Method to dock/undock a sled designed by Charles Bell.
       *
    
    AnHardt's avatar
    AnHardt committed
       * stow[in]     If false, move to MAX_X and engage the solenoid
       *              If true, move to MAX_X and release the solenoid
    
    AnHardt's avatar
    AnHardt committed
      static void dock_sled(bool stow) {
    
        #if ENABLED(DEBUG_LEVELING_FEATURE)
          if (DEBUGGING(LEVELING)) {
    
    AnHardt's avatar
    AnHardt committed
            SERIAL_ECHOPAIR("dock_sled(", stow);
    
            SERIAL_CHAR(')');
    
            SERIAL_EOL();
    
    AnHardt's avatar
    AnHardt committed
        // Dock sled a bit closer to ensure proper capturing
        do_blocking_move_to_x(X_MAX_POS + SLED_DOCKING_OFFSET - ((stow) ? 1 : 0));
    
    
        #if HAS_SOLENOID_1 && DISABLED(EXT_SOLENOID)
          WRITE(SOL1_PIN, !stow); // switch solenoid
    
    #elif ENABLED(Z_PROBE_ALLEN_KEY)
    
    
      FORCE_INLINE void do_blocking_move_to(const float logical[XYZ], const float &fr_mm_s) {
        do_blocking_move_to(logical[X_AXIS], logical[Y_AXIS], logical[Z_AXIS], fr_mm_s);
      }
    
    
      void run_deploy_moves_script() {
        #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Z)
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_X
            #define Z_PROBE_ALLEN_KEY_DEPLOY_1_X current_position[X_AXIS]
          #endif
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_Y
            #define Z_PROBE_ALLEN_KEY_DEPLOY_1_Y current_position[Y_AXIS]
          #endif
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_Z
            #define Z_PROBE_ALLEN_KEY_DEPLOY_1_Z current_position[Z_AXIS]
          #endif
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE
            #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0
          #endif
    
          const float deploy_1[] = { Z_PROBE_ALLEN_KEY_DEPLOY_1_X, Z_PROBE_ALLEN_KEY_DEPLOY_1_Y, Z_PROBE_ALLEN_KEY_DEPLOY_1_Z };
          do_blocking_move_to(deploy_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE));
    
        #endif
        #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Z)
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_X
            #define Z_PROBE_ALLEN_KEY_DEPLOY_2_X current_position[X_AXIS]
          #endif
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_Y
            #define Z_PROBE_ALLEN_KEY_DEPLOY_2_Y current_position[Y_AXIS]
          #endif
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_Z
            #define Z_PROBE_ALLEN_KEY_DEPLOY_2_Z current_position[Z_AXIS]
          #endif
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE
            #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0
          #endif
    
          const float deploy_2[] = { Z_PROBE_ALLEN_KEY_DEPLOY_2_X, Z_PROBE_ALLEN_KEY_DEPLOY_2_Y, Z_PROBE_ALLEN_KEY_DEPLOY_2_Z };
          do_blocking_move_to(deploy_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE));
    
        #endif
        #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Z)
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_X
            #define Z_PROBE_ALLEN_KEY_DEPLOY_3_X current_position[X_AXIS]
          #endif
          #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_Y
            #define Z_PROBE_ALLEN_KEY_DEPLOY_3_Y current_position[Y_AXIS]
          #endif