Marlin_Firmware/Marlin/Marlin_main.cpp

8871 lines
280 KiB
C++
Raw Normal View History

/**
2016-03-24 13:01:20 -05:00
* Marlin 3D Printer Firmware
* Copyright (C) 2016 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/>.
2016-03-24 13:01:20 -05:00
*
*/
/**
*
* About Marlin
*
* This firmware is a mashup between Sprinter and grbl.
* - https://github.com/kliment/Sprinter
* - https://github.com/simen/grbl/tree
*
* It has preliminary support for Matthew Roberts advance algorithm
* - http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
*/
2012-11-21 13:53:56 -06:00
#include "Marlin.h"
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#include "vector_3.h"
#if ENABLED(AUTO_BED_LEVELING_GRID)
#include "qr_solve.h"
#endif
#endif // AUTO_BED_LEVELING_FEATURE
#if ENABLED(MESH_BED_LEVELING)
2015-03-15 04:43:26 -05:00
#include "mesh_bed_leveling.h"
2015-04-03 17:31:35 -05:00
#endif
2015-03-15 04:43:26 -05:00
#if ENABLED(BEZIER_CURVE_SUPPORT)
#include "planner_bezier.h"
#endif
#include "ultralcd.h"
#include "planner.h"
#include "stepper.h"
#include "endstops.h"
#include "temperature.h"
#include "cardreader.h"
2015-04-25 23:04:54 -05:00
#include "configuration_store.h"
#include "language.h"
#include "pins_arduino.h"
#include "math.h"
#include "nozzle.h"
2016-07-23 21:13:35 -05:00
#include "duration_t.h"
#include "types.h"
2015-10-13 05:57:36 -05:00
#if ENABLED(USE_WATCHDOG)
#include "watchdog.h"
#endif
#if ENABLED(BLINKM)
2015-04-25 23:04:54 -05:00
#include "blinkm.h"
#include "Wire.h"
2013-10-20 02:55:15 -05:00
#endif
2013-09-10 04:18:29 -05:00
#if HAS_SERVOS
#include "servo.h"
#endif
#if HAS_DIGIPOTSS
#include <SPI.h>
2012-11-21 13:53:56 -06:00
#endif
2016-03-19 21:03:17 -05:00
#if ENABLED(DAC_STEPPER_CURRENT)
#include "stepper_dac.h"
#endif
#if ENABLED(EXPERIMENTAL_I2CBUS)
#include "twibus.h"
#endif
2015-04-13 19:17:36 -05:00
/**
* Look here for descriptions of G-codes:
* - http://linuxcnc.org/handbook/gcode/g-code.html
* - http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
*
* Help us document these G-codes online:
* - https://github.com/MarlinFirmware/Marlin/wiki/G-Code-in-Marlin
2015-04-13 19:17:36 -05:00
* - http://reprap.org/wiki/G-code
*
* -----------------
2015-04-13 19:17:36 -05:00
* Implemented Codes
* -----------------
2015-04-13 19:17:36 -05:00
*
* "G" Codes
*
* G0 -> G1
* G1 - Coordinated Movement X Y Z E
* G2 - CW ARC
* G3 - CCW ARC
* G4 - Dwell S<seconds> or P<milliseconds>
* G5 - Cubic B-spline with XYZE destination and IJPQ offsets
* G10 - Retract filament according to settings of M207
* G11 - Retract recover filament according to settings of M208
* G12 - Clean tool
* G20 - Set input units to inches
* G21 - Set input units to millimeters
2015-04-13 19:17:36 -05:00
* G28 - Home one or more axes
* G29 - Detailed Z probe, probes the bed at 3 or more points. Will fail if you haven't homed yet.
* G30 - Single Z probe, probes bed at current XY location.
2015-04-13 19:17:36 -05:00
* G31 - Dock sled (Z_PROBE_SLED only)
* G32 - Undock sled (Z_PROBE_SLED only)
* G90 - Use Absolute Coordinates
* G91 - Use Relative Coordinates
* G92 - Set current position to coordinates given
*
* "M" Codes
*
* M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
* M1 - Same as M0
* M17 - Enable/Power all stepper motors
* M18 - Disable all stepper motors; same as M84
* M20 - List SD card
* M21 - Init SD card
* M22 - Release SD card
* M23 - Select SD file (M23 filename.g)
* M24 - Start/resume SD print
* M25 - Pause SD print
* M26 - Set SD position in bytes (M26 S12345)
* M27 - Report SD print status
* M28 - Start SD write (M28 filename.g)
* M29 - Stop SD write
* M30 - Delete file from SD (M30 filename.g)
* M31 - Output time since last M109 or SD card start to serial
* M32 - Select file and start SD print (Can be used _while_ printing from SD card files):
* syntax "M32 /path/filename#", or "M32 S<startpos bytes> !filename#"
* Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include).
* The '#' is necessary when calling from within sd files, as it stops buffer prereading
2015-05-17 19:36:32 -05:00
* M33 - Get the longname version of a path
2015-04-13 19:17:36 -05:00
* M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used.
* M48 - Measure Z_Probe repeatability. M48 [P # of points] [X position] [Y position] [V_erboseness #] [E_ngage Probe] [L # of legs of travel]
2016-04-28 09:40:24 -05:00
* M75 - Start the print job timer
* M76 - Pause the print job timer
* M77 - Stop the print job timer
* M78 - Show statistical information about the print jobs
2015-04-13 19:17:36 -05:00
* M80 - Turn on Power Supply
* M81 - Turn off Power Supply
* M82 - Set E codes absolute (default)
* M83 - Set E codes relative while in Absolute Coordinates (G90) mode
* M84 - Disable steppers until next move,
* or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
* M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
* M92 - Set planner.axis_steps_per_mm - same syntax as G92
2015-04-13 19:17:36 -05:00
* M104 - Set extruder target temp
* M105 - Read current temp
* M106 - Fan on
* M107 - Fan off
* M108 - Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature.
2015-04-13 19:17:36 -05:00
* M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating
* Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling
* IF AUTOTEMP is enabled, S<mintemp> B<maxtemp> F<factor>. Exit autotemp by any M109 without F
2015-06-23 22:46:25 -05:00
* M110 - Set the current line number
* M111 - Set debug flags with S<mask>. See flag bits defined in enum.h.
2015-04-13 19:17:36 -05:00
* M112 - Emergency stop
2016-04-06 19:31:49 -05:00
* M113 - Get or set the timeout interval for Host Keepalive "busy" messages
2015-04-13 19:17:36 -05:00
* M114 - Output current position to serial port
* M115 - Capabilities string
2015-05-17 07:00:09 -05:00
* M117 - Display a message on the controller screen
2015-04-13 19:17:36 -05:00
* M119 - Output Endstop status to serial port
* M120 - Enable endstop detection
* M121 - Disable endstop detection
* M126 - Solenoid Air Valve Open (BariCUDA support by jmil)
* M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
* M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
* M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
* M140 - Set bed target temp
* M145 - Set the heatup state H<hotend> B<bed> F<fan speed> for S<material> (0=PLA, 1=ABS)
* M149 - Set temperature units
2015-04-13 19:17:36 -05:00
* M150 - Set BlinkM Color Output R: Red<0-255> U(!): Green<0-255> B: Blue<0-255> over i2c, G for green does not work.
* M163 - Set a single proportion for a mixing extruder. Requires MIXING_EXTRUDER.
* M164 - Save the mix as a virtual extruder. Requires MIXING_EXTRUDER and MIXING_VIRTUAL_TOOLS.
* M165 - Set the proportions for a mixing extruder. Use parameters ABCDHI to set the mixing factors. Requires MIXING_EXTRUDER.
2015-04-13 19:17:36 -05:00
* M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
* Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
* M200 - Set filament diameter, D<diameter>, setting E axis units to cubic. (Use S0 to revert to linear units.)
2015-04-13 19:17:36 -05:00
* M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
* M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
* M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in units/sec
* M204 - Set default acceleration: P for Printing moves, R for Retract only (no X, Y, Z) moves and T for Travel (non printing) moves (ex. M204 P800 T3000 R9000) in units/sec^2
* M205 - Set advanced settings. Current units apply:
S<print> T<travel> minimum speeds
B<minimum segment time>
X<max xy jerk>, Z<max Z jerk>, E<max E jerk>
2015-04-13 19:17:36 -05:00
* M206 - Set additional homing offset
* M207 - Set Retract Length: S<length>, Feedrate: F<units/min>, and Z lift: Z<distance>
* M208 - Set Recover (unretract) Additional (!) Length: S<length> and Feedrate: F<units/min>
* M209 - Turn Automatic Retract Detection on/off: S<bool> (For slicers that don't support G10/11).
Every normal extrude-only move will be classified as retract depending on the direction.
* M211 - Enable, Disable, and/or Report software endstops: [S<bool>]
* M218 - Set a tool offset: T<index> X<offset> Y<offset>
* M220 - Set Feedrate Percentage: S<percent> ("FR" on your LCD)
* M221 - Set Flow Percentage: S<percent>
2015-04-13 19:17:36 -05:00
* M226 - Wait until the specified pin reaches the state required: P<pin number> S<pin state>
* M240 - Trigger a camera to take a photograph
* M250 - Set LCD contrast C<contrast value> (value 0..63)
* M280 - Set servo position absolute. P: servo index, S: angle or microseconds
* M300 - Play beep sound S<frequency Hz> P<duration ms>
* M301 - Set PID parameters P I and D
* M302 - Allow cold extrudes, or set the minimum extrude S<temperature>.
* M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
* M304 - Set bed PID parameters P I and D
* M380 - Activate solenoid on active extruder
* M381 - Disable all solenoids
* M400 - Finish all moves
* M401 - Lower Z probe if present
* M402 - Raise Z probe if present
* M404 - Display or set the Nominal Filament Width: [ N<diameter> ]
* M405 - Enable Filament Sensor extrusion control. Optional delay between sensor and extruder: D<cm>
* M406 - Disable Filament Sensor extrusion control
* M407 - Display measured filament diameter in millimeters
2015-04-19 01:12:29 -05:00
* M410 - Quickstop. Abort all the planned moves
* M420 - Enable/Disable Mesh Leveling (with current values) S1=enable S0=disable
* M421 - Set a single Z coordinate in the Mesh Leveling grid. X<units> Y<units> Z<units>
2015-04-29 20:26:16 -05:00
* M428 - Set the home_offset logically based on the current_position
2015-04-13 19:17:36 -05:00
* M500 - Store parameters in EEPROM
* M501 - Read parameters from EEPROM (if you need reset them after you changed them temporarily).
* M502 - Revert to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
* M503 - Print the current settings (from memory not from EEPROM). Use S0 to leave off headings.
* M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
* M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
* M665 - Set delta configurations: L<diagonal rod> R<delta radius> S<segments/s>
* M666 - Set delta endstop adjustment
* M605 - Set dual x-carriage movement mode: S<mode> [ X<duplication x-offset> R<duplication temp offset> ]
* M851 - Set Z probe's Z offset in current units. (Negative values apply to probes that extend below the nozzle.)
2015-04-13 19:17:36 -05:00
* M907 - Set digital trimpot motor current using axis codes.
* M908 - Control digital trimpot directly.
* M909 - DAC_STEPPER_CURRENT: Print digipot/DAC current value
* M910 - DAC_STEPPER_CURRENT: Commit digipot/DAC value to external EEPROM via I2C
2015-04-13 19:17:36 -05:00
* M350 - Set microstepping mode.
* M351 - Toggle MS1 MS2 pins directly.
*
* ************ SCARA Specific - This can change to suit future G-code regulations
* M360 - SCARA calibration: Move to cal-position ThetaA (0 deg calibration)
* M361 - SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree)
* M362 - SCARA calibration: Move to cal-position PsiA (0 deg calibration)
* M363 - SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree)
* M364 - SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position)
* M365 - SCARA calibration: Scaling factor, X, Y, Z axis
* ************* SCARA End ***************
*
2015-05-19 06:25:15 -05:00
* ************ Custom codes - This can change to suit future G-code regulations
2015-07-18 18:59:12 -05:00
* M100 - Watch Free Memory (For Debugging Only)
2015-04-13 19:17:36 -05:00
* M928 - Start SD logging (M928 filename.g) - ended by M29
* M999 - Restart after being stopped by error
*
* "T" Codes
*
* T0-T3 - Select a tool by index (usually an extruder) [ F<units/min> ]
*
2015-04-13 19:17:36 -05:00
*/
#if ENABLED(M100_FREE_MEMORY_WATCHER)
2015-07-18 18:59:12 -05:00
void gcode_M100();
2015-07-05 19:42:13 -05:00
#endif
#if ENABLED(SDSUPPORT)
CardReader card;
#endif
#if ENABLED(EXPERIMENTAL_I2CBUS)
TWIBus i2c;
#endif
2015-04-08 02:56:19 -05:00
bool Running = true;
uint8_t marlin_debug_flags = DEBUG_NONE;
2015-04-08 03:05:39 -05:00
float current_position[NUM_AXIS] = { 0.0 };
2015-04-08 02:56:19 -05:00
static float destination[NUM_AXIS] = { 0.0 };
2016-08-20 22:38:32 -05:00
bool axis_known_position[XYZ] = { false };
bool axis_homed[XYZ] = { false };
2015-04-08 02:56:19 -05:00
static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0;
2015-04-13 19:17:36 -05:00
static char command_queue[BUFSIZE][MAX_CMD_SIZE];
static char* current_command, *current_command_args;
static uint8_t cmd_queue_index_r = 0,
cmd_queue_index_w = 0,
commands_in_queue = 0;
2015-04-08 02:56:19 -05:00
#if ENABLED(INCH_MODE_SUPPORT)
float linear_unit_factor = 1.0;
float volumetric_unit_factor = 1.0;
#endif
#if ENABLED(TEMPERATURE_UNITS_SUPPORT)
TempUnit input_temp_units = TEMPUNIT_C;
#endif
2016-07-15 20:49:34 -05:00
/**
* Feed rates are often configured with mm/m
* but the planner and stepper like mm/s units.
*/
const float homing_feedrate_mm_s[] = {
2016-07-19 19:11:57 -05:00
#if ENABLED(DELTA)
MMM_TO_MMS(HOMING_FEEDRATE_Z), MMM_TO_MMS(HOMING_FEEDRATE_Z),
2016-07-19 19:11:57 -05:00
#else
MMM_TO_MMS(HOMING_FEEDRATE_XY), MMM_TO_MMS(HOMING_FEEDRATE_XY),
2016-07-19 19:11:57 -05:00
#endif
MMM_TO_MMS(HOMING_FEEDRATE_Z), 0
2016-07-19 19:11:57 -05:00
};
static float feedrate_mm_s = MMM_TO_MMS(1500.0), saved_feedrate_mm_s;
2016-07-15 20:49:34 -05:00
int feedrate_percentage = 100, saved_feedrate_percentage;
bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
2016-08-18 22:13:47 -05:00
int flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100);
bool volumetric_enabled = false;
float filament_size[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_NOMINAL_FILAMENT_DIA);
float volumetric_multiplier[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0);
2016-04-18 01:13:07 -05:00
// The distance that XYZ has been offset by G92. Reset by G28.
2016-08-20 22:38:32 -05:00
float position_shift[XYZ] = { 0 };
2016-04-18 01:13:07 -05:00
// This offset is added to the configured home position.
// Set by M206, M428, or menu item. Saved to EEPROM.
2016-08-20 22:38:32 -05:00
float home_offset[XYZ] = { 0 };
// Software Endstops are based on the configured limits.
#if ENABLED(min_software_endstops) || ENABLED(max_software_endstops)
bool soft_endstops_enabled = true;
#endif
float soft_endstop_min[XYZ] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS },
soft_endstop_max[XYZ] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS };
2015-04-08 02:56:19 -05:00
2016-03-05 20:27:45 -06:00
#if FAN_COUNT > 0
int fanSpeeds[FAN_COUNT] = { 0 };
#endif
2016-04-18 01:13:07 -05:00
// The active extruder (tool). Set with T<extruder> command.
2015-04-03 17:45:41 -05:00
uint8_t active_extruder = 0;
2016-04-18 01:13:07 -05:00
// Relative Mode. Enable with G91, disable with G90.
static bool relative_mode = false;
2016-07-06 21:59:19 -05:00
volatile bool wait_for_heatup = true;
2015-04-08 02:56:19 -05:00
2015-04-03 17:45:41 -05:00
const char errormagic[] PROGMEM = "Error:";
const char echomagic[] PROGMEM = "echo:";
const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
2015-04-08 02:56:19 -05:00
2015-04-03 17:45:41 -05:00
static int serial_count = 0;
2016-04-18 01:13:07 -05:00
// GCode parameter pointer used by code_seen(), code_value_float(), etc.
2016-04-18 01:13:07 -05:00
static char* seen_pointer;
// Next Immediate GCode Command pointer. NULL if none.
const char* queued_commands_P = NULL;
2015-04-03 17:45:41 -05:00
const int sensitive_pins[] = SENSITIVE_PINS; ///< Sensitive pin list for M42
2016-04-18 01:13:07 -05:00
2015-04-03 17:45:41 -05:00
// Inactivity shutdown
2015-04-12 20:07:08 -05:00
millis_t previous_cmd_ms = 0;
static millis_t max_inactive_time = 0;
2016-04-10 17:55:12 -05:00
static millis_t stepper_inactive_time = (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL;
2016-04-18 01:13:07 -05:00
// Print Job Timer
2016-04-26 20:13:27 -05:00
#if ENABLED(PRINTCOUNTER)
PrintCounter print_job_timer = PrintCounter();
#else
Stopwatch print_job_timer = Stopwatch();
#endif
2016-04-18 01:13:07 -05:00
2016-08-01 23:10:53 -05:00
// Buzzer - I2C on the LCD or a BEEPER_PIN
#if ENABLED(LCD_USE_I2C_BUZZER)
#define BUZZ(d,f) lcd_buzz(d, f)
#elif HAS_BUZZER
Buzzer buzzer;
#define BUZZ(d,f) buzzer.tone(d, f)
#else
#define BUZZ(d,f) NOOP
2016-06-04 14:29:01 -05:00
#endif
2015-04-03 23:43:30 -05:00
static uint8_t target_extruder;
2015-04-03 17:45:41 -05:00
2016-06-14 20:05:20 -05:00
#if HAS_BED_PROBE
float zprobe_zoffset = Z_PROBE_OFFSET_FROM_EXTRUDER;
#endif
2016-07-15 20:49:34 -05:00
#define PLANNER_XY_FEEDRATE() (min(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]))
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
float xy_probe_feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED);
bool bed_leveling_in_progress = false;
#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)
2016-06-22 04:22:43 -05:00
#else
#define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE()
2015-04-03 17:45:41 -05:00
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
2015-04-03 17:45:41 -05:00
float z_endstop_adj = 0;
#endif
// Extruder offsets
2016-05-26 19:43:20 -05:00
#if HOTENDS > 1
float hotend_offset[][HOTENDS] = {
HOTEND_OFFSET_X,
HOTEND_OFFSET_Y
#ifdef HOTEND_OFFSET_Z
, HOTEND_OFFSET_Z
#endif
};
#endif
#if HAS_Z_SERVO_ENDSTOP
2016-06-13 22:18:24 -05:00
const int z_servo_angle[2] = Z_SERVO_ANGLES;
#endif
#if ENABLED(BARICUDA)
2016-04-18 01:12:15 -05:00
int baricuda_valve_pressure = 0;
int baricuda_e_to_p_pressure = 0;
#endif
#if ENABLED(FWRETRACT)
bool autoretract_enabled = false;
bool retracted[EXTRUDERS] = { false };
bool retracted_swap[EXTRUDERS] = { false };
float retract_length = RETRACT_LENGTH;
float retract_length_swap = RETRACT_LENGTH_SWAP;
2016-06-22 05:27:31 -05:00
float retract_feedrate_mm_s = RETRACT_FEEDRATE;
float retract_zlift = RETRACT_ZLIFT;
float retract_recover_length = RETRACT_RECOVER_LENGTH;
float retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP;
2016-07-15 20:49:34 -05:00
float retract_recover_feedrate_mm_s = RETRACT_RECOVER_FEEDRATE;
2015-01-23 16:13:06 -06:00
#endif // FWRETRACT
#if ENABLED(ULTIPANEL) && HAS_POWER_SWITCH
2015-08-05 06:40:36 -05:00
bool powersupply =
#if ENABLED(PS_DEFAULT_OFF)
false
#else
true
#endif
;
#endif
#if ENABLED(DELTA)
#define TOWER_1 X_AXIS
#define TOWER_2 Y_AXIS
#define TOWER_3 Z_AXIS
2016-08-20 22:38:32 -05:00
float delta[ABC];
float cartesian_position[XYZ] = { 0 };
2015-04-03 18:46:56 -05:00
#define SIN_60 0.8660254037844386
#define COS_60 0.5
2016-08-20 22:38:32 -05:00
float endstop_adj[ABC] = { 0 };
2015-04-03 18:46:56 -05:00
// these are the default values, can be overriden with M665
float delta_radius = DELTA_RADIUS;
float delta_tower1_x = -SIN_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_1); // front left tower
float delta_tower1_y = -COS_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_1);
float delta_tower2_x = SIN_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_2); // front right tower
float delta_tower2_y = -COS_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_2);
float delta_tower3_x = 0; // back middle tower
float delta_tower3_y = (delta_radius + DELTA_RADIUS_TRIM_TOWER_3);
2015-04-03 18:46:56 -05:00
float delta_diagonal_rod = DELTA_DIAGONAL_ROD;
float delta_diagonal_rod_trim_tower_1 = DELTA_DIAGONAL_ROD_TRIM_TOWER_1;
float delta_diagonal_rod_trim_tower_2 = DELTA_DIAGONAL_ROD_TRIM_TOWER_2;
float delta_diagonal_rod_trim_tower_3 = DELTA_DIAGONAL_ROD_TRIM_TOWER_3;
float delta_diagonal_rod_2_tower_1 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_1);
float delta_diagonal_rod_2_tower_2 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_2);
float delta_diagonal_rod_2_tower_3 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_3);
2015-04-03 18:46:56 -05:00
float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
float delta_clip_start_height = Z_MAX_POS;
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
2015-04-03 18:46:56 -05:00
int delta_grid_spacing[2] = { 0, 0 };
float bed_level[AUTO_BED_LEVELING_GRID_POINTS][AUTO_BED_LEVELING_GRID_POINTS];
2015-04-03 17:45:41 -05:00
#endif
float delta_safe_distance_from_top();
2015-04-03 18:46:56 -05:00
#else
2015-04-03 17:45:41 -05:00
static bool home_all_axis = true;
#endif
#if ENABLED(SCARA)
2015-05-12 06:18:15 -05:00
float delta_segments_per_second = SCARA_SEGMENTS_PER_SECOND;
2016-08-20 22:38:32 -05:00
float delta[ABC];
float axis_scaling[ABC] = { 1, 1, 1 }; // Build size scaling, default to 1
2015-04-03 18:46:56 -05:00
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
//Variables for Filament Sensor input
float filament_width_nominal = DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404
bool filament_sensor = false; //M405 turns on filament_sensor control, M406 turns it off
float filament_width_meas = DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter
2016-03-28 22:04:34 -05:00
int8_t measurement_delay[MAX_MEASUREMENT_DELAY + 1]; //ring buffer to delay measurement store extruder factor after subtracting 100
int filwidth_delay_index1 = 0; //index into ring buffer
int filwidth_delay_index2 = -1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized
int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting
#endif
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
2016-04-18 01:16:49 -05:00
static bool filament_ran_out = false;
#endif
#if ENABLED(FILAMENT_CHANGE_FEATURE)
FilamentChangeMenuResponse filament_change_menu_response;
#endif
#if ENABLED(MIXING_EXTRUDER)
float mixing_factor[MIXING_STEPPERS];
#if MIXING_VIRTUAL_TOOLS > 1
float mixing_virtual_tool_mix[MIXING_VIRTUAL_TOOLS][MIXING_STEPPERS];
#endif
#endif
2016-02-20 19:35:35 -06:00
static bool send_ok[BUFSIZE];
#if HAS_SERVOS
Servo servo[NUM_SERVOS];
2016-06-12 17:35:01 -05:00
#define MOVE_SERVO(I, P) servo[I].move(P)
2016-06-22 16:04:23 -05:00
#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
#endif
#ifdef CHDK
2016-04-10 17:55:12 -05:00
millis_t chdkHigh = 0;
boolean chdkActive = false;
#endif
#if ENABLED(PID_EXTRUSION_SCALING)
2015-08-30 21:04:30 -05:00
int lpq_len = 20;
#endif
#if ENABLED(HOST_KEEPALIVE_FEATURE)
static MarlinBusyState busy_state = NOT_BUSY;
2016-04-10 17:55:12 -05:00
static millis_t next_busy_signal_ms = 0;
uint8_t host_keepalive_interval = DEFAULT_KEEPALIVE_INTERVAL;
#define KEEPALIVE_STATE(n) do{ busy_state = n; }while(0)
#else
#define host_keepalive() ;
#define KEEPALIVE_STATE(n) ;
#endif // HOST_KEEPALIVE_FEATURE
2016-03-26 22:36:36 -05:00
/**
* ***************************************************************************
* ******************************** FUNCTIONS ********************************
* ***************************************************************************
*/
2016-04-18 02:05:22 -05:00
void stop();
void get_available_commands();
void process_next_command();
void prepare_move_to_destination();
2016-07-23 15:11:18 -05:00
void set_current_from_steppers_for_axis(AxisEnum axis);
#if ENABLED(ARC_SUPPORT)
void plan_arc(float target[NUM_AXIS], float* offset, uint8_t clockwise);
#endif
#if ENABLED(BEZIER_CURVE_SUPPORT)
void plan_cubic_move(const float offset[4]);
#endif
2016-08-05 10:17:06 -05:00
void serial_echopair_P(const char* s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
2016-07-15 03:57:02 -05:00
void serial_echopair_P(const char* s_P, char v) { serialprintPGM(s_P); SERIAL_CHAR(v); }
void serial_echopair_P(const char* s_P, int v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_P(const char* s_P, long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_P(const char* s_P, float v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_P(const char* s_P, double v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_P(const char* s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void tool_change(const uint8_t tmp_extruder, const float fr_mm_s=0.0, bool no_move=false);
static void report_current_position();
#if ENABLED(DEBUG_LEVELING_FEATURE)
void print_xyz(const char* prefix, const char* suffix, const float x, const float y, const float z) {
serialprintPGM(prefix);
SERIAL_ECHOPAIR("(", x);
SERIAL_ECHOPAIR(", ", y);
SERIAL_ECHOPAIR(", ", z);
SERIAL_ECHOPGM(")");
if (suffix) serialprintPGM(suffix);
else SERIAL_EOL;
}
void print_xyz(const char* prefix, const char* suffix, const float xyz[]) {
print_xyz(prefix, suffix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]);
}
2016-04-14 02:00:21 -05:00
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
void print_xyz(const char* prefix, const char* suffix, const vector_3 &xyz) {
print_xyz(prefix, suffix, xyz.x, xyz.y, xyz.z);
2016-04-14 02:00:21 -05:00
}
#endif
#define DEBUG_POS(SUFFIX,VAR) do { \
print_xyz(PSTR(STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0)
#endif
/**
* sync_plan_position
* Set planner / stepper positions to the cartesian current_position.
* The stepper code translates these coordinates into step units.
* Allows translation between steps and millimeters for cartesian & core robots
*/
inline void sync_plan_position() {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position", current_position);
#endif
planner.set_position_mm(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
}
inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
#if ENABLED(DELTA) || ENABLED(SCARA)
inline void sync_plan_position_delta() {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position_delta", current_position);
#endif
2016-07-21 17:46:22 -05:00
inverse_kinematics(current_position);
2016-05-31 17:39:37 -05:00
planner.set_position_mm(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
}
#define SYNC_PLAN_POSITION_KINEMATIC() sync_plan_position_delta()
#else
#define SYNC_PLAN_POSITION_KINEMATIC() sync_plan_position()
#endif
#if ENABLED(SDSUPPORT)
#include "SdFatUtil.h"
int freeMemory() { return SdFatUtil::FreeRam(); }
#else
extern "C" {
extern unsigned int __bss_end;
extern unsigned int __heap_start;
extern void* __brkval;
int freeMemory() {
int free_memory;
if ((int)__brkval == 0)
free_memory = ((int)&free_memory) - ((int)&__bss_end);
else
free_memory = ((int)&free_memory) - ((int)__brkval);
return free_memory;
}
}
#endif //!SDSUPPORT
#if ENABLED(DIGIPOT_I2C)
extern void digipot_i2c_set_current(int channel, float current);
extern void digipot_i2c_init();
#endif
2015-04-13 19:17:36 -05:00
/**
* Inject the next "immediate" command, when possible.
* Return true if any immediate commands remain to inject.
2015-04-13 19:17:36 -05:00
*/
2015-04-03 17:31:35 -05:00
static bool drain_queued_commands_P() {
if (queued_commands_P != NULL) {
size_t i = 0;
char c, cmd[30];
strncpy_P(cmd, queued_commands_P, sizeof(cmd) - 1);
cmd[sizeof(cmd) - 1] = '\0';
while ((c = cmd[i]) && c != '\n') i++; // find the end of this gcode command
cmd[i] = '\0';
if (enqueue_and_echo_command(cmd)) { // success?
if (c) // newline char?
queued_commands_P += i + 1; // advance to the next command
else
queued_commands_P = NULL; // nul char? no more commands
}
}
return (queued_commands_P != NULL); // return whether any more remain
}
2015-04-13 19:17:36 -05:00
/**
* Record one or many commands to run from program memory.
* Aborts the current queue, if any.
* Note: drain_queued_commands_P() must be called repeatedly to drain the commands afterwards
*/
2016-02-20 19:35:35 -06:00
void enqueue_and_echo_commands_P(const char* pgcode) {
2015-04-13 19:17:36 -05:00
queued_commands_P = pgcode;
drain_queued_commands_P(); // first command executed asap (when possible)
}
void clear_command_queue() {
cmd_queue_index_r = cmd_queue_index_w;
commands_in_queue = 0;
}
2015-04-13 19:17:36 -05:00
/**
2016-02-20 19:35:35 -06:00
* Once a new command is in the ring buffer, call this to commit it
2015-04-13 19:17:36 -05:00
*/
2016-02-20 19:35:35 -06:00
inline void _commit_command(bool say_ok) {
send_ok[cmd_queue_index_w] = say_ok;
2015-04-13 19:17:36 -05:00
cmd_queue_index_w = (cmd_queue_index_w + 1) % BUFSIZE;
commands_in_queue++;
2016-02-20 19:35:35 -06:00
}
/**
* Copy a command directly into the main command buffer, from RAM.
* Returns true if successfully adds the command
*/
inline bool _enqueuecommand(const char* cmd, bool say_ok=false) {
if (*cmd == ';' || commands_in_queue >= BUFSIZE) return false;
strcpy(command_queue[cmd_queue_index_w], cmd);
_commit_command(say_ok);
return true;
}
void enqueue_and_echo_command_now(const char* cmd) {
while (!enqueue_and_echo_command(cmd)) idle();
}
2016-02-20 19:35:35 -06:00
/**
* Enqueue with Serial Echo
*/
bool enqueue_and_echo_command(const char* cmd, bool say_ok/*=false*/) {
if (_enqueuecommand(cmd, say_ok)) {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_Enqueueing);
SERIAL_ECHO(cmd);
SERIAL_ECHOLNPGM("\"");
return true;
}
return false;
}
2015-04-13 19:17:36 -05:00
void setup_killpin() {
2015-04-03 17:31:35 -05:00
#if HAS_KILL
SET_INPUT(KILL_PIN);
2015-04-03 17:31:35 -05:00
WRITE(KILL_PIN, HIGH);
#endif
}
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
void setup_filrunoutpin() {
2016-06-19 21:25:09 -05:00
pinMode(FIL_RUNOUT_PIN, INPUT);
#if ENABLED(ENDSTOPPULLUP_FIL_RUNOUT)
2016-06-19 21:25:09 -05:00
WRITE(FIL_RUNOUT_PIN, HIGH);
2015-04-03 17:31:35 -05:00
#endif
}
#endif
// Set home pin
2015-04-13 19:17:36 -05:00
void setup_homepin(void) {
2015-04-03 17:31:35 -05:00
#if HAS_HOME
SET_INPUT(HOME_PIN);
WRITE(HOME_PIN, HIGH);
#endif
}
2015-04-13 19:17:36 -05:00
void setup_photpin() {
2015-04-03 17:31:35 -05:00
#if HAS_PHOTOGRAPH
2015-03-03 02:48:20 -06:00
OUT_WRITE(PHOTOGRAPH_PIN, LOW);
#endif
}
2015-04-13 19:17:36 -05:00
void setup_powerhold() {
2015-04-03 17:31:35 -05:00
#if HAS_SUICIDE
2015-03-03 02:48:20 -06:00
OUT_WRITE(SUICIDE_PIN, HIGH);
#endif
#if HAS_POWER_SWITCH
#if ENABLED(PS_DEFAULT_OFF)
2015-03-03 02:48:20 -06:00
OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP);
#else
2015-03-03 02:48:20 -06:00
OUT_WRITE(PS_ON_PIN, PS_ON_AWAKE);
#endif
#endif
}
2015-04-13 19:17:36 -05:00
void suicide() {
2015-04-03 17:31:35 -05:00
#if HAS_SUICIDE
2015-03-03 02:48:20 -06:00
OUT_WRITE(SUICIDE_PIN, LOW);
#endif
}
2015-04-13 19:17:36 -05:00
void servo_init() {
2015-04-03 17:31:35 -05:00
#if NUM_SERVOS >= 1 && HAS_SERVO_0
servo[0].attach(SERVO0_PIN);
2015-07-24 04:38:15 -05:00
servo[0].detach(); // Just set up the pin. We don't have a position yet. Don't move to a random position.
#endif
2015-04-03 17:31:35 -05:00
#if NUM_SERVOS >= 2 && HAS_SERVO_1
servo[1].attach(SERVO1_PIN);
2015-07-24 04:38:15 -05:00
servo[1].detach();
#endif
2015-04-03 17:31:35 -05:00
#if NUM_SERVOS >= 3 && HAS_SERVO_2
servo[2].attach(SERVO2_PIN);
2015-07-24 04:38:15 -05:00
servo[2].detach();
#endif
2015-04-03 17:31:35 -05:00
#if NUM_SERVOS >= 4 && HAS_SERVO_3
servo[3].attach(SERVO3_PIN);
2015-07-24 04:38:15 -05:00
servo[3].detach();
#endif
#if HAS_Z_SERVO_ENDSTOP
2015-12-03 07:19:29 -06:00
/**
2016-06-13 22:18:24 -05:00
* Set position of Z Servo Endstop
2015-12-03 07:19:29 -06:00
*
* 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!
*
*/
2016-06-13 22:18:24 -05:00
STOW_Z_SERVO();
#endif
#if HAS_BED_PROBE
endstops.enable_z_probe(false);
#endif
}
2015-07-10 20:15:24 -05:00
/**
* Stepper Reset (RigidBoard, et.al.)
*/
#if HAS_STEPPER_RESET
void disableStepperDrivers() {
pinMode(STEPPER_RESET_PIN, OUTPUT);
digitalWrite(STEPPER_RESET_PIN, LOW); // drive it down to hold in reset motor driver chips
}
void enableStepperDrivers() { pinMode(STEPPER_RESET_PIN, INPUT); } // set to input, which allows it to be pulled high by pullups
#endif
2016-08-11 01:04:18 -05:00
#if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0
2016-08-11 19:57:22 -05:00
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
2016-08-13 20:06:10 -05:00
i2c.reply("Hello World!\n");
2016-08-11 01:04:18 -05:00
}
#endif
2015-04-13 19:17:36 -05:00
/**
* Marlin entry-point: Set up before the program loop
* - Set up the kill pin, filament runout, power hold
* - Start the serial port
* - Print startup messages and diagnostics
* - Get EEPROM or default settings
* - Initialize managers for:
* temperature
* planner
* watchdog
* stepper
* photo pin
* servos
* LCD controller
* Digipot I2C
* Z probe sled
* status LEDs
*/
void setup() {
#ifdef DISABLE_JTAG
// Disable JTAG on AT90USB chips to free up pins for IO
MCUCR = 0x80;
MCUCR = 0x80;
#endif
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
setup_filrunoutpin();
#endif
setup_killpin();
setup_powerhold();
2015-07-10 20:15:24 -05:00
#if HAS_STEPPER_RESET
disableStepperDrivers();
#endif
MYSERIAL.begin(BAUDRATE);
SERIAL_PROTOCOLLNPGM("start");
SERIAL_ECHO_START;
// Check startup - does nothing if bootloader sets MCUSR to 0
byte mcu = MCUSR;
if (mcu & 1) SERIAL_ECHOLNPGM(MSG_POWERUP);
if (mcu & 2) SERIAL_ECHOLNPGM(MSG_EXTERNAL_RESET);
if (mcu & 4) SERIAL_ECHOLNPGM(MSG_BROWNOUT_RESET);
if (mcu & 8) SERIAL_ECHOLNPGM(MSG_WATCHDOG_RESET);
if (mcu & 32) SERIAL_ECHOLNPGM(MSG_SOFTWARE_RESET);
MCUSR = 0;
SERIAL_ECHOPGM(MSG_MARLIN);
SERIAL_ECHOLNPGM(" " SHORT_BUILD_VERSION);
2015-05-14 16:56:04 -05:00
#ifdef STRING_DISTRIBUTION_DATE
#ifdef STRING_CONFIG_H_AUTHOR
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_CONFIGURATION_VER);
2015-05-14 16:56:04 -05:00
SERIAL_ECHOPGM(STRING_DISTRIBUTION_DATE);
SERIAL_ECHOPGM(MSG_AUTHOR);
SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
SERIAL_ECHOPGM("Compiled: ");
SERIAL_ECHOLNPGM(__DATE__);
2015-01-23 16:13:06 -06:00
#endif // STRING_CONFIG_H_AUTHOR
2015-05-14 16:56:04 -05:00
#endif // STRING_DISTRIBUTION_DATE
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_FREE_MEMORY);
SERIAL_ECHO(freeMemory());
SERIAL_ECHOPGM(MSG_PLANNER_BUFFER_BYTES);
SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
2016-02-20 19:35:35 -06:00
// Send "ok" after commands by default
for (int8_t i = 0; i < BUFSIZE; i++) send_ok[i] = true;
// Load data from EEPROM if available (or use defaults)
// This also updates variables in the planner, elsewhere
Config_RetrieveSettings();
// Initialize current position based on home_offset
memcpy(current_position, home_offset, sizeof(home_offset));
2015-10-13 05:57:36 -05:00
// Vital to init stepper/planner equivalent for current_position
SYNC_PLAN_POSITION_KINEMATIC();
thermalManager.init(); // Initialize temperature loop
2015-10-13 05:57:36 -05:00
#if ENABLED(USE_WATCHDOG)
watchdog_init();
#endif
stepper.init(); // Initialize stepper, this enables interrupts!
setup_photpin();
servo_init();
2015-04-03 17:31:35 -05:00
#if HAS_CONTROLLERFAN
SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
#endif
2015-07-10 20:15:24 -05:00
#if HAS_STEPPER_RESET
enableStepperDrivers();
#endif
#if ENABLED(DIGIPOT_I2C)
digipot_i2c_init();
#endif
#if ENABLED(DAC_STEPPER_CURRENT)
dac_init();
#endif
2016-07-30 04:01:46 -05:00
#if ENABLED(Z_PROBE_SLED) && PIN_EXISTS(SLED)
pinMode(SLED_PIN, OUTPUT);
digitalWrite(SLED_PIN, LOW); // turn it off
#endif // Z_PROBE_SLED
setup_homepin();
2015-08-05 06:40:36 -05:00
#ifdef STAT_LED_RED
pinMode(STAT_LED_RED, OUTPUT);
digitalWrite(STAT_LED_RED, LOW); // turn it off
#endif
#ifdef STAT_LED_BLUE
pinMode(STAT_LED_BLUE, OUTPUT);
digitalWrite(STAT_LED_BLUE, LOW); // turn it off
2015-08-05 06:40:36 -05:00
#endif
lcd_init();
#if ENABLED(SHOW_BOOTSCREEN)
#if ENABLED(DOGLCD)
safe_delay(BOOTSCREEN_TIMEOUT);
#elif ENABLED(ULTRA_LCD)
bootscreen();
lcd_init();
#endif
#endif
#if ENABLED(MIXING_EXTRUDER) && MIXING_VIRTUAL_TOOLS > 1
// Initialize mixing to 100% color 1
for (uint8_t i = 0; i < MIXING_STEPPERS; i++)
mixing_factor[i] = (i == 0) ? 1 : 0;
for (uint8_t t = 0; t < MIXING_VIRTUAL_TOOLS; t++)
for (uint8_t i = 0; i < MIXING_STEPPERS; i++)
mixing_virtual_tool_mix[t][i] = mixing_factor[i];
#endif
2016-08-11 01:04:18 -05:00
#if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0
2016-08-11 19:57:22 -05:00
i2c.onReceive(i2c_on_receive);
i2c.onRequest(i2c_on_request);
2016-08-11 01:04:18 -05:00
#endif
}
2015-04-13 19:17:36 -05:00
/**
* The main Marlin program loop
*
* - Save or log commands to SD
* - Process available commands (if not saving)
* - Call heater manager
* - Call inactivity manager
* - Call endstop manager
* - Call LCD update
*/
2015-04-03 17:31:35 -05:00
void loop() {
if (commands_in_queue < BUFSIZE) get_available_commands();
2015-04-03 17:31:35 -05:00
#if ENABLED(SDSUPPORT)
2015-04-03 17:31:35 -05:00
card.checkautostart(false);
#endif
2015-04-03 17:31:35 -05:00
2015-04-13 19:17:36 -05:00
if (commands_in_queue) {
#if ENABLED(SDSUPPORT)
2015-04-13 19:17:36 -05:00
2015-04-03 17:31:35 -05:00
if (card.saving) {
char* command = command_queue[cmd_queue_index_r];
2015-04-13 19:17:36 -05:00
if (strstr_P(command, PSTR("M29"))) {
// M29 closes the file
card.closefile();
SERIAL_PROTOCOLLNPGM(MSG_FILE_SAVED);
ok_to_send();
2015-04-13 19:17:36 -05:00
}
else {
// Write the string from the read buffer to SD
card.write_command(command);
2015-04-03 17:31:35 -05:00
if (card.logging)
process_next_command(); // The card is saving because it's logging
else
ok_to_send();
}
}
else
process_next_command();
2015-04-13 19:17:36 -05:00
#else
2015-04-13 19:17:36 -05:00
process_next_command();
2015-04-13 19:17:36 -05:00
2015-04-03 17:31:35 -05:00
#endif // SDSUPPORT
2015-04-13 19:17:36 -05:00
// The queue may be reset by a command handler or by code invoked by idle() within a handler
if (commands_in_queue) {
--commands_in_queue;
cmd_queue_index_r = (cmd_queue_index_r + 1) % BUFSIZE;
}
}
endstops.report_state();
2015-05-26 22:08:21 -05:00
idle();
}
void gcode_line_error(const char* err, bool doFlush = true) {
SERIAL_ERROR_START;
serialprintPGM(err);
SERIAL_ERRORLN(gcode_LastN);
//Serial.println(gcode_N);
if (doFlush) FlushSerialRequestResend();
serial_count = 0;
}
inline void get_serial_commands() {
2016-02-20 19:35:35 -06:00
static char serial_line_buffer[MAX_CMD_SIZE];
static boolean serial_comment_mode = false;
// If the command buffer is empty for too long,
// send "wait" to indicate Marlin is still waiting.
2016-02-20 19:35:35 -06:00
#if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0
static millis_t last_command_time = 0;
millis_t ms = millis();
2016-04-10 17:55:12 -05:00
if (commands_in_queue == 0 && !MYSERIAL.available() && ELAPSED(ms, last_command_time + NO_TIMEOUTS)) {
SERIAL_ECHOLNPGM(MSG_WAIT);
last_command_time = ms;
}
#endif
2015-05-16 22:59:04 -05:00
2016-03-26 22:36:36 -05:00
/**
* Loop while serial characters are incoming and the queue is not full
*/
2015-05-16 22:59:04 -05:00
while (commands_in_queue < BUFSIZE && MYSERIAL.available() > 0) {
2016-02-20 19:35:35 -06:00
char serial_char = MYSERIAL.read();
2015-04-13 19:17:36 -05:00
2016-03-26 22:36:36 -05:00
/**
* If the character ends the line
*/
2016-02-20 19:35:35 -06:00
if (serial_char == '\n' || serial_char == '\r') {
2015-05-16 22:59:04 -05:00
2016-02-20 19:35:35 -06:00
serial_comment_mode = false; // end of line == end of comment
if (!serial_count) continue; // skip empty lines
2015-04-12 20:07:08 -05:00
2016-02-20 19:35:35 -06:00
serial_line_buffer[serial_count] = 0; // terminate string
serial_count = 0; //reset buffer
2015-04-12 20:07:08 -05:00
2016-02-20 19:35:35 -06:00
char* command = serial_line_buffer;
2015-04-12 20:07:08 -05:00
while (*command == ' ') command++; // skip any leading spaces
char* npos = (*command == 'N') ? command : NULL; // Require the N parameter to start the line
char* apos = strchr(command, '*');
2015-05-17 07:00:09 -05:00
if (npos) {
boolean M110 = strstr_P(command, PSTR("M110")) != NULL;
if (M110) {
char* n2pos = strchr(command + 4, 'N');
if (n2pos) npos = n2pos;
}
2015-05-17 07:00:09 -05:00
gcode_N = strtol(npos + 1, NULL, 10);
if (gcode_N != gcode_LastN + 1 && !M110) {
gcode_line_error(PSTR(MSG_ERR_LINE_NO));
return;
}
2015-05-17 07:00:09 -05:00
if (apos) {
byte checksum = 0, count = 0;
2015-04-13 19:17:36 -05:00
while (command[count] != '*') checksum ^= command[count++];
2015-05-17 07:00:09 -05:00
if (strtol(apos + 1, NULL, 10) != checksum) {
gcode_line_error(PSTR(MSG_ERR_CHECKSUM_MISMATCH));
return;
}
// if no errors, continue parsing
}
2016-03-08 04:25:11 -06:00
else {
gcode_line_error(PSTR(MSG_ERR_NO_CHECKSUM));
return;
}
gcode_LastN = gcode_N;
// if no errors, continue parsing
}
2015-05-17 07:00:09 -05:00
else if (apos) { // No '*' without 'N'
gcode_line_error(PSTR(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM), false);
return;
}
2015-04-12 20:07:08 -05:00
2015-05-17 07:00:09 -05:00
// Movement commands alert when stopped
if (IsStopped()) {
char* gpos = strchr(command, 'G');
2015-05-17 07:00:09 -05:00
if (gpos) {
int codenum = strtol(gpos + 1, NULL, 10);
switch (codenum) {
case 0:
case 1:
case 2:
case 3:
2015-04-12 20:07:08 -05:00
SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
LCD_MESSAGEPGM(MSG_STOPPED);
2015-05-17 07:00:09 -05:00
break;
}
2015-08-05 06:40:36 -05:00
}
}
#if DISABLED(EMERGENCY_PARSER)
// If command was e-stop process now
if (strcmp(command, "M108") == 0) wait_for_heatup = false;
if (strcmp(command, "M112") == 0) kill(PSTR(MSG_KILLED));
if (strcmp(command, "M410") == 0) { quickstop_stepper(); }
#endif
2016-02-20 19:35:35 -06:00
#if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0
last_command_time = ms;
#endif
2016-02-20 19:35:35 -06:00
// Add the command to the queue
_enqueuecommand(serial_line_buffer, true);
}
else if (serial_count >= MAX_CMD_SIZE - 1) {
// Keep fetching, but ignore normal characters beyond the max length
// The command will be injected when EOL is reached
}
2015-04-12 20:07:08 -05:00
else if (serial_char == '\\') { // Handle escapes
2016-02-20 19:35:35 -06:00
if (MYSERIAL.available() > 0) {
2015-04-12 20:07:08 -05:00
// if we have one more character, copy it over
serial_char = MYSERIAL.read();
if (!serial_comment_mode) serial_line_buffer[serial_count++] = serial_char;
2015-04-12 20:07:08 -05:00
}
// otherwise do nothing
}
2016-02-20 19:35:35 -06:00
else { // it's not a newline, carriage return or escape char
if (serial_char == ';') serial_comment_mode = true;
if (!serial_comment_mode) serial_line_buffer[serial_count++] = serial_char;
}
2016-02-20 19:35:35 -06:00
} // queue has space, serial has data
}
#if ENABLED(SDSUPPORT)
inline void get_sdcard_commands() {
2016-02-20 19:35:35 -06:00
static bool stop_buffering = false,
sd_comment_mode = false;
if (!card.sdprinting) return;
2015-04-12 20:07:08 -05:00
2016-03-26 22:36:36 -05:00
/**
* '#' stops reading from SD to the buffer prematurely, so procedural
* macro calls are possible. If it occurs, stop_buffering is triggered
* and the buffer is run dry; this character _can_ occur in serial com
* due to checksums, however, no checksums are used in SD printing.
*/
2015-04-12 20:07:08 -05:00
2015-04-13 19:17:36 -05:00
if (commands_in_queue == 0) stop_buffering = false;
2015-04-12 20:07:08 -05:00
2016-02-20 19:35:35 -06:00
uint16_t sd_count = 0;
bool card_eof = card.eof();
while (commands_in_queue < BUFSIZE && !card_eof && !stop_buffering) {
2015-04-12 20:07:08 -05:00
int16_t n = card.get();
2016-02-20 19:35:35 -06:00
char sd_char = (char)n;
card_eof = card.eof();
if (card_eof || n == -1
|| sd_char == '\n' || sd_char == '\r'
|| ((sd_char == '#' || sd_char == ':') && !sd_comment_mode)
2015-04-12 20:07:08 -05:00
) {
2016-02-20 19:35:35 -06:00
if (card_eof) {
2015-04-12 20:07:08 -05:00
SERIAL_PROTOCOLLNPGM(MSG_FILE_PRINTED);
card.printingHasFinished();
card.checkautostart(true);
}
2016-06-19 19:14:56 -05:00
else if (n == -1) {
SERIAL_ERROR_START;
SERIAL_ECHOLNPGM(MSG_SD_ERR_READ);
}
2016-02-20 19:35:35 -06:00
if (sd_char == '#') stop_buffering = true;
2016-02-20 19:35:35 -06:00
sd_comment_mode = false; //for new command
if (!sd_count) continue; //skip empty lines
command_queue[cmd_queue_index_w][sd_count] = '\0'; //terminate string
sd_count = 0; //clear buffer
_commit_command(false);
}
else if (sd_count >= MAX_CMD_SIZE - 1) {
2016-03-26 22:36:36 -05:00
/**
* Keep fetching, but ignore normal characters beyond the max length
* The command will be injected when EOL is reached
*/
2015-04-12 20:07:08 -05:00
}
else {
2016-02-20 19:35:35 -06:00
if (sd_char == ';') sd_comment_mode = true;
if (!sd_comment_mode) command_queue[cmd_queue_index_w][sd_count++] = sd_char;
2015-04-12 20:07:08 -05:00
}
}
}
#endif // SDSUPPORT
/**
* Add to the circular command queue the next command from:
* - The command-injection queue (queued_commands_P)
* - The active serial input (usually USB)
* - The SD card file being actively printed
*/
void get_available_commands() {
// if any immediate commands remain, don't get other commands yet
if (drain_queued_commands_P()) return;
get_serial_commands();
#if ENABLED(SDSUPPORT)
get_sdcard_commands();
#endif
}
inline bool code_has_value() {
2015-04-24 22:43:16 -05:00
int i = 1;
2015-05-17 07:00:09 -05:00
char c = seen_pointer[i];
2016-02-09 20:03:13 -06:00
while (c == ' ') c = seen_pointer[++i];
2015-05-17 07:00:09 -05:00
if (c == '-' || c == '+') c = seen_pointer[++i];
if (c == '.') c = seen_pointer[++i];
return NUMERIC(c);
}
inline float code_value_float() {
float ret;
char* e = strchr(seen_pointer, 'E');
if (e) {
*e = 0;
ret = strtod(seen_pointer + 1, NULL);
*e = 'E';
}
else
ret = strtod(seen_pointer + 1, NULL);
return ret;
}
inline unsigned long code_value_ulong() { return strtoul(seen_pointer + 1, NULL, 10); }
inline long code_value_long() { return strtol(seen_pointer + 1, NULL, 10); }
2015-04-03 23:43:30 -05:00
inline int code_value_int() { return (int)strtol(seen_pointer + 1, NULL, 10); }
inline uint16_t code_value_ushort() { return (uint16_t)strtoul(seen_pointer + 1, NULL, 10); }
inline uint8_t code_value_byte() { return (uint8_t)(constrain(strtol(seen_pointer + 1, NULL, 10), 0, 255)); }
inline bool code_value_bool() { return code_value_byte() > 0; }
#if ENABLED(INCH_MODE_SUPPORT)
inline void set_input_linear_units(LinearUnit units) {
switch (units) {
case LINEARUNIT_INCH:
linear_unit_factor = 25.4;
break;
case LINEARUNIT_MM:
default:
linear_unit_factor = 1.0;
break;
}
volumetric_unit_factor = pow(linear_unit_factor, 3.0);
}
inline float axis_unit_factor(int axis) {
return (axis == E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor);
}
inline float code_value_linear_units() { return code_value_float() * linear_unit_factor; }
inline float code_value_axis_units(int axis) { return code_value_float() * axis_unit_factor(axis); }
2016-06-16 13:24:11 -05:00
inline float code_value_per_axis_unit(int axis) { return code_value_float() / axis_unit_factor(axis); }
#else
inline float code_value_linear_units() { return code_value_float(); }
2016-06-16 13:24:11 -05:00
inline float code_value_axis_units(int axis) { UNUSED(axis); return code_value_float(); }
inline float code_value_per_axis_unit(int axis) { UNUSED(axis); return code_value_float(); }
#endif
#if ENABLED(TEMPERATURE_UNITS_SUPPORT)
inline void set_input_temp_units(TempUnit units) { input_temp_units = units; }
2016-06-04 14:29:01 -05:00
float code_value_temp_abs() {
switch (input_temp_units) {
case TEMPUNIT_C:
return code_value_float();
case TEMPUNIT_F:
return (code_value_float() - 32) * 0.5555555556;
case TEMPUNIT_K:
return code_value_float() - 272.15;
default:
return code_value_float();
}
}
float code_value_temp_diff() {
switch (input_temp_units) {
case TEMPUNIT_C:
case TEMPUNIT_K:
return code_value_float();
case TEMPUNIT_F:
return code_value_float() * 0.5555555556;
default:
return code_value_float();
}
}
#else
float code_value_temp_abs() { return code_value_float(); }
float code_value_temp_diff() { return code_value_float(); }
#endif
FORCE_INLINE millis_t code_value_millis() { return code_value_ulong(); }
inline millis_t code_value_millis_from_seconds() { return code_value_float() * 1000; }
bool code_seen(char code) {
2015-07-07 01:09:14 -05:00
seen_pointer = strchr(current_command_args, code);
return (seen_pointer != NULL); // Return TRUE if the code-letter was found
}
/**
* Set target_extruder from the T parameter or the active_extruder
*
* Returns TRUE if the target is invalid
*/
bool get_target_extruder_from_command(int code) {
if (code_seen('T')) {
if (code_value_byte() >= EXTRUDERS) {
SERIAL_ECHO_START;
SERIAL_CHAR('M');
SERIAL_ECHO(code);
SERIAL_ECHOLNPAIR(" " MSG_INVALID_EXTRUDER " ", code_value_byte());
return true;
}
target_extruder = code_value_byte();
}
else
target_extruder = active_extruder;
return false;
}
#define DEFINE_PGM_READ_ANY(type, reader) \
static inline type pgm_read_any(const type *p) \
{ return pgm_read_##reader##_near(p); }
DEFINE_PGM_READ_ANY(float, float);
DEFINE_PGM_READ_ANY(signed char, byte);
#define XYZ_CONSTS_FROM_CONFIG(type, array, CONFIG) \
2016-08-20 22:38:32 -05:00
static const PROGMEM type array##_P[XYZ] = \
{ X_##CONFIG, Y_##CONFIG, Z_##CONFIG }; \
static inline type array(int axis) \
{ return pgm_read_any(&array##_P[axis]); }
2015-04-13 19:58:47 -05:00
XYZ_CONSTS_FROM_CONFIG(float, base_min_pos, MIN_POS);
XYZ_CONSTS_FROM_CONFIG(float, base_max_pos, MAX_POS);
XYZ_CONSTS_FROM_CONFIG(float, base_home_pos, HOME_POS);
XYZ_CONSTS_FROM_CONFIG(float, max_length, MAX_LENGTH);
XYZ_CONSTS_FROM_CONFIG(float, home_bump_mm, HOME_BUMP_MM);
XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
2016-07-20 12:30:10 -05:00
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
bool extruder_duplication_enabled = false; // Used in Dual X mode 2
#endif
#if ENABLED(DUAL_X_CARRIAGE)
#define DXC_FULL_CONTROL_MODE 0
#define DXC_AUTO_PARK_MODE 1
#define DXC_DUPLICATION_MODE 2
static int dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
static float x_home_pos(int extruder) {
if (extruder == 0)
2016-07-24 18:34:01 -05:00
return LOGICAL_X_POSITION(base_home_pos(X_AXIS));
else
2016-03-26 22:36:36 -05:00
/**
* In dual carriage mode the extruder offset provides an override of the
* second X-carriage offset when homed - otherwise X2_HOME_POS is used.
* This allow soft recalibration of the second extruder offset position
* without firmware reflash (through the M218 command).
*/
2016-05-26 19:43:20 -05:00
return (hotend_offset[X_AXIS][1] > 0) ? hotend_offset[X_AXIS][1] : X2_HOME_POS;
}
static int x_home_dir(int extruder) {
return (extruder == 0) ? X_HOME_DIR : X2_HOME_DIR;
}
static float inactive_extruder_x_pos = X2_MAX_POS; // used in mode 0 & 1
2016-07-24 18:34:31 -05:00
static bool active_extruder_parked = false; // used in mode 1 & 2
static float raised_parked_position[NUM_AXIS]; // used in mode 1
static millis_t delayed_move_time = 0; // used in mode 1
static float duplicate_extruder_x_offset = DEFAULT_DUPLICATION_X_OFFSET; // used in mode 2
2016-07-24 18:34:31 -05:00
static float duplicate_extruder_temp_offset = 0; // used in mode 2
#endif //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(AxisEnum axis) {
float offs = LOGICAL_POSITION(0, axis);
#if ENABLED(DUAL_X_CARRIAGE)
if (axis == X_AXIS) {
2016-05-26 19:43:20 -05:00
float dual_max_x = max(hotend_offset[X_AXIS][1], X2_MAX_POS);
if (active_extruder != 0) {
soft_endstop_min[X_AXIS] = X2_MIN_POS + offs;
soft_endstop_max[X_AXIS] = dual_max_x + offs;
return;
}
else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) {
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;
return;
}
}
else
#endif
{
soft_endstop_min[axis] = base_min_pos(axis) + offs;
soft_endstop_max[axis] = base_max_pos(axis) + offs;
}
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOPAIR("For ", axis_codes[axis]);
SERIAL_ECHOPAIR(" axis:\n home_offset = ", home_offset[axis]);
SERIAL_ECHOPAIR("\n position_shift = ", position_shift[axis]);
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
}
/**
* 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(AxisEnum axis, float v) {
current_position[axis] += v - home_offset[axis];
home_offset[axis] = v;
update_software_endstops(axis);
}
static void set_axis_is_at_home(AxisEnum axis) {
2016-04-05 20:30:53 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
2016-08-19 01:09:03 -05:00
SERIAL_ECHOPAIR(">>> set_axis_is_at_home(", axis_codes[axis]);
2016-06-27 21:33:37 -05:00
SERIAL_ECHOLNPGM(")");
2016-04-05 20:30:53 -05:00
}
#endif
position_shift[axis] = 0;
#if ENABLED(DUAL_X_CARRIAGE)
if (axis == X_AXIS && (active_extruder != 0 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) {
if (active_extruder != 0)
current_position[X_AXIS] = x_home_pos(active_extruder);
else
2016-07-24 18:34:01 -05:00
current_position[X_AXIS] = LOGICAL_X_POSITION(base_home_pos(X_AXIS));
update_software_endstops(X_AXIS);
return;
}
#endif
#if ENABLED(SCARA)
2015-08-05 06:40:36 -05:00
2015-04-23 20:16:44 -05:00
if (axis == X_AXIS || axis == Y_AXIS) {
2016-08-20 22:38:32 -05:00
float homeposition[XYZ];
2016-07-23 15:07:23 -05:00
LOOP_XYZ(i) homeposition[i] = LOGICAL_POSITION(base_home_pos(i), i);
// SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
// SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]);
2016-03-26 22:36:36 -05:00
/**
* Works out real Homeposition angles using inverse kinematics,
* and calculates homing offset using forward kinematics
*/
2016-07-21 17:46:22 -05:00
inverse_kinematics(homeposition);
forward_kinematics_SCARA(delta);
2015-08-05 06:40:36 -05:00
// SERIAL_ECHOPAIR("Delta X=", delta[X_AXIS]);
// SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]);
2015-08-05 06:40:36 -05:00
current_position[axis] = LOGICAL_POSITION(delta[axis], axis);
2015-08-05 06:40:36 -05:00
2016-03-26 22:36:36 -05:00
/**
* SCARA home positions are based on configuration since the actual
* limits are determined by the inverse kinematic transform.
*/
soft_endstop_min[axis] = base_min_pos(axis); // + (delta[axis] - base_home_pos(axis));
soft_endstop_max[axis] = base_max_pos(axis); // + (delta[axis] - base_home_pos(axis));
}
2015-04-23 20:16:44 -05:00
else
#endif
{
current_position[axis] = LOGICAL_POSITION(base_home_pos(axis), axis);
update_software_endstops(axis);
if (axis == Z_AXIS) {
#if HAS_BED_PROBE && Z_HOME_DIR < 0
#if DISABLED(Z_MIN_PROBE_ENDSTOP)
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);
}
#endif
#elif ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING))
SERIAL_ECHOLNPGM("*** Z HOMED TO ENDSTOP (Z_MIN_PROBE_ENDSTOP) ***");
#endif
#endif
}
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOPAIR("> home_offset[", axis_codes[axis]);
SERIAL_ECHOLNPAIR("] = ", home_offset[axis]);
DEBUG_POS("", current_position);
2015-08-05 06:40:36 -05:00
}
2015-07-09 18:57:44 -05:00
#endif
2015-04-23 20:16:44 -05:00
}
2016-04-05 20:30:53 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
2016-08-19 01:09:03 -05:00
SERIAL_ECHOPAIR("<<< set_axis_is_at_home(", axis_codes[axis]);
2016-04-05 20:30:53 -05:00
SERIAL_ECHOLNPGM(")");
}
#endif
2016-08-27 19:53:02 -05:00
axis_known_position[axis] = axis_homed[axis] = true;
}
/**
* Some planner shorthand inline functions
*/
inline float get_homing_bump_feedrate(AxisEnum axis) {
const int homing_bump_divisor[] = HOMING_BUMP_DIVISOR;
int hbd = homing_bump_divisor[axis];
if (hbd < 1) {
hbd = 10;
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Warning: Homing Bump Divisor < 1");
}
return homing_feedrate_mm_s[axis] / hbd;
}
2016-04-13 04:33:22 -05:00
//
// line_to_current_position
// Move the planner to the current position from wherever it last moved
// (or from wherever it has been told it is located).
//
inline void line_to_current_position() {
planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate_mm_s, active_extruder);
}
inline void line_to_z(float zPosition) {
planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate_mm_s, active_extruder);
}
2016-04-13 04:33:22 -05:00
//
// line_to_destination
// Move the planner, not necessarily synced with current_position
//
inline void line_to_destination(float fr_mm_s) {
planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], fr_mm_s, active_extruder);
}
inline void line_to_destination() { line_to_destination(feedrate_mm_s); }
inline void set_current_to_destination() { memcpy(current_position, destination, sizeof(current_position)); }
inline void set_destination_to_current() { memcpy(destination, current_position, sizeof(destination)); }
#if ENABLED(DELTA)
/**
* Calculate delta, start a line, and set current_position to destination
*/
void prepare_move_to_destination_raw() {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_move_to_destination_raw", destination);
#endif
refresh_cmd_timeout();
2016-07-21 17:46:22 -05:00
inverse_kinematics(destination);
planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], MMS_SCALED(feedrate_mm_s), active_extruder);
set_current_to_destination();
}
#endif
/**
* 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 &x, const float &y, const float &z, const float &fr_mm_s /*=0.0*/) {
float old_feedrate_mm_s = feedrate_mm_s;
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) print_xyz(PSTR(">>> do_blocking_move_to"), NULL, x, y, z);
#endif
#if ENABLED(DELTA)
feedrate_mm_s = (fr_mm_s != 0.0) ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S;
2016-07-22 16:18:08 -05:00
set_destination_to_current(); // sync destination at the start
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("set_destination_to_current", destination);
#endif
// when in the danger zone
if (current_position[Z_AXIS] > delta_clip_start_height) {
2016-07-22 16:18:08 -05:00
if (z > delta_clip_start_height) { // staying in the danger zone
destination[X_AXIS] = x; // move directly (uninterpolated)
destination[Y_AXIS] = y;
destination[Z_AXIS] = z;
2016-07-22 16:18:08 -05:00
prepare_move_to_destination_raw(); // set_current_to_destination
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position);
#endif
return;
2016-07-22 16:18:08 -05:00
}
else {
destination[Z_AXIS] = delta_clip_start_height;
2016-07-22 16:18:08 -05:00
prepare_move_to_destination_raw(); // set_current_to_destination
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position);
#endif
}
}
2016-07-22 16:18:08 -05:00
if (z > current_position[Z_AXIS]) { // raising?
destination[Z_AXIS] = z;
2016-07-22 16:18:08 -05:00
prepare_move_to_destination_raw(); // set_current_to_destination
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position);
#endif
}
2016-07-22 16:18:08 -05:00
destination[X_AXIS] = x;
destination[Y_AXIS] = y;
2016-07-22 16:18:08 -05:00
prepare_move_to_destination(); // set_current_to_destination
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position);
#endif
2016-07-22 16:18:08 -05:00
if (z < current_position[Z_AXIS]) { // lowering?
destination[Z_AXIS] = z;
2016-07-22 16:18:08 -05:00
prepare_move_to_destination_raw(); // set_current_to_destination
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position);
#endif
}
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to");
#endif
#else
// If Z needs to raise, do it before moving XY
if (current_position[Z_AXIS] < z) {
feedrate_mm_s = (fr_mm_s != 0.0) ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS];
current_position[Z_AXIS] = z;
line_to_current_position();
}
feedrate_mm_s = (fr_mm_s != 0.0) ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S;
current_position[X_AXIS] = x;
current_position[Y_AXIS] = y;
line_to_current_position();
// If Z needs to lower, do it after moving XY
if (current_position[Z_AXIS] > z) {
feedrate_mm_s = (fr_mm_s != 0.0) ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS];
current_position[Z_AXIS] = z;
line_to_current_position();
}
#endif
stepper.synchronize();
feedrate_mm_s = old_feedrate_mm_s;
}
void do_blocking_move_to_x(const float &x, const float &fr_mm_s/*=0.0*/) {
do_blocking_move_to(x, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_s);
}
void do_blocking_move_to_z(const float &z, const float &fr_mm_s/*=0.0*/) {
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z, fr_mm_s);
}
void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s/*=0.0*/) {
do_blocking_move_to(x, y, 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;
2016-07-15 20:49:34 -05:00
saved_feedrate_percentage = feedrate_percentage;
feedrate_percentage = 100;
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;
2016-07-15 20:49:34 -05:00
feedrate_percentage = saved_feedrate_percentage;
refresh_cmd_timeout();
}
#if HAS_BED_PROBE
/**
* Raise Z to a minimum height to make room for a probe to move
*/
inline void do_probe_raise(float z_raise) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOPAIR("do_probe_raise(", z_raise);
SERIAL_ECHOLNPGM(")");
}
#endif
2016-07-24 18:34:01 -05:00
float z_dest = LOGICAL_Z_POSITION(z_raise);
if (z_dest > current_position[Z_AXIS])
do_blocking_move_to_z(z_dest);
}
#endif //HAS_BED_PROBE
2016-07-16 05:57:35 -05:00
#if ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || ENABLED(Z_SAFE_HOMING) || HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE)
static bool axis_unhomed_error(const bool x, const bool y, const bool z) {
const bool xx = x && !axis_homed[X_AXIS],
yy = y && !axis_homed[Y_AXIS],
zz = z && !axis_homed[Z_AXIS];
if (xx || yy || zz) {
SERIAL_ECHO_START;
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)
char message[3 * (LCD_WIDTH) + 1] = ""; // worst case is kana.utf with up to 3*LCD_WIDTH+1
strcat_P(message, PSTR(MSG_HOME " "));
if (xx) strcat_P(message, PSTR(MSG_X));
if (yy) strcat_P(message, PSTR(MSG_Y));
if (zz) strcat_P(message, PSTR(MSG_Z));
strcat_P(message, PSTR(" " MSG_FIRST));
lcd_setstatus(message);
#endif
return true;
}
return false;
2016-06-22 16:03:22 -05:00
}
2016-07-16 05:57:35 -05:00
#endif
2016-06-22 16:03:22 -05:00
2016-06-20 17:50:51 -05:00
#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.
*
* stow[in] If false, move to MAX_X and engage the solenoid
* If true, move to MAX_X and release the solenoid
2016-06-20 17:50:51 -05:00
*/
static void dock_sled(bool stow) {
2016-06-20 17:50:51 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOPAIR("dock_sled(", stow);
2016-06-20 17:50:51 -05:00
SERIAL_ECHOLNPGM(")");
}
#endif
// Dock sled a bit closer to ensure proper capturing
do_blocking_move_to_x(X_MAX_POS + SLED_DOCKING_OFFSET - ((stow) ? 1 : 0));
2016-07-30 04:01:46 -05:00
#if PIN_EXISTS(SLED)
digitalWrite(SLED_PIN, !stow); // switch solenoid
#endif
2016-06-20 17:50:51 -05:00
}
#endif // Z_PROBE_SLED
#if ENABLED(Z_PROBE_ALLEN_KEY)
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
do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_1_X, Z_PROBE_ALLEN_KEY_DEPLOY_1_Y, Z_PROBE_ALLEN_KEY_DEPLOY_1_Z, 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
do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_2_X, Z_PROBE_ALLEN_KEY_DEPLOY_2_Y, Z_PROBE_ALLEN_KEY_DEPLOY_2_Z, 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
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_Z
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Z current_position[Z_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0
#endif
do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_3_X, Z_PROBE_ALLEN_KEY_DEPLOY_3_Y, Z_PROBE_ALLEN_KEY_DEPLOY_3_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE));
#endif
#if defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Z)
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_X
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_X current_position[X_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_Y
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_Y current_position[Y_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_Z
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_Z current_position[Z_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0
#endif
do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_4_X, Z_PROBE_ALLEN_KEY_DEPLOY_4_Y, Z_PROBE_ALLEN_KEY_DEPLOY_4_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE));
#endif
#if defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Z)
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_X
#define Z_PROBE_ALLEN_KEY_DEPLOY_5_X current_position[X_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_Y
#define Z_PROBE_ALLEN_KEY_DEPLOY_5_Y current_position[Y_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_Z
#define Z_PROBE_ALLEN_KEY_DEPLOY_5_Z current_position[Z_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE
#define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0
#endif
do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_5_X, Z_PROBE_ALLEN_KEY_DEPLOY_5_Y, Z_PROBE_ALLEN_KEY_DEPLOY_5_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE));
#endif
}
void run_stow_moves_script() {
#if defined(Z_PROBE_ALLEN_KEY_STOW_1_X) || defined(Z_PROBE_ALLEN_KEY_STOW_1_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_1_Z)
#ifndef Z_PROBE_ALLEN_KEY_STOW_1_X
#define Z_PROBE_ALLEN_KEY_STOW_1_X current_position[X_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_1_Y
#define Z_PROBE_ALLEN_KEY_STOW_1_Y current_position[Y_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_1_Z
#define Z_PROBE_ALLEN_KEY_STOW_1_Z current_position[Z_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE
#define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0
#endif
do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_1_X, Z_PROBE_ALLEN_KEY_STOW_1_Y, Z_PROBE_ALLEN_KEY_STOW_1_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE));
#endif
#if defined(Z_PROBE_ALLEN_KEY_STOW_2_X) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Z)
#ifndef Z_PROBE_ALLEN_KEY_STOW_2_X
#define Z_PROBE_ALLEN_KEY_STOW_2_X current_position[X_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_2_Y
#define Z_PROBE_ALLEN_KEY_STOW_2_Y current_position[Y_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_2_Z
#define Z_PROBE_ALLEN_KEY_STOW_2_Z current_position[Z_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE
#define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0
#endif
do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_2_X, Z_PROBE_ALLEN_KEY_STOW_2_Y, Z_PROBE_ALLEN_KEY_STOW_2_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE));
#endif
#if defined(Z_PROBE_ALLEN_KEY_STOW_3_X) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Z)
#ifndef Z_PROBE_ALLEN_KEY_STOW_3_X
#define Z_PROBE_ALLEN_KEY_STOW_3_X current_position[X_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_3_Y
#define Z_PROBE_ALLEN_KEY_STOW_3_Y current_position[Y_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_3_Z
#define Z_PROBE_ALLEN_KEY_STOW_3_Z current_position[Z_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE
#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0
#endif
do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_3_X, Z_PROBE_ALLEN_KEY_STOW_3_Y, Z_PROBE_ALLEN_KEY_STOW_3_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE));
#endif
#if defined(Z_PROBE_ALLEN_KEY_STOW_4_X) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Z)
#ifndef Z_PROBE_ALLEN_KEY_STOW_4_X
#define Z_PROBE_ALLEN_KEY_STOW_4_X current_position[X_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_4_Y
#define Z_PROBE_ALLEN_KEY_STOW_4_Y current_position[Y_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_4_Z
#define Z_PROBE_ALLEN_KEY_STOW_4_Z current_position[Z_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE
#define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0
#endif
do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_4_X, Z_PROBE_ALLEN_KEY_STOW_4_Y, Z_PROBE_ALLEN_KEY_STOW_4_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE));
#endif
#if defined(Z_PROBE_ALLEN_KEY_STOW_5_X) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Z)
#ifndef Z_PROBE_ALLEN_KEY_STOW_5_X
#define Z_PROBE_ALLEN_KEY_STOW_5_X current_position[X_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_5_Y
#define Z_PROBE_ALLEN_KEY_STOW_5_Y current_position[Y_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_5_Z
#define Z_PROBE_ALLEN_KEY_STOW_5_Z current_position[Z_AXIS]
#endif
#ifndef Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE
#define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0
#endif
do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_5_X, Z_PROBE_ALLEN_KEY_STOW_5_Y, Z_PROBE_ALLEN_KEY_STOW_5_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE));
#endif
}
#endif
2016-06-20 17:50:51 -05:00
#if HAS_BED_PROBE
// TRIGGERED_WHEN_STOWED_TEST can easily be extended to servo probes, ... if needed.
#if ENABLED(PROBE_IS_TRIGGERED_WHEN_STOWED_TEST)
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
#define _TRIGGERED_WHEN_STOWED_TEST (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING)
#else
#define _TRIGGERED_WHEN_STOWED_TEST (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING)
#endif
#endif
#define DEPLOY_PROBE() set_probe_deployed( true )
#define STOW_PROBE() set_probe_deployed( false )
// returns false for ok and true for failure
static bool set_probe_deployed(bool deploy) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
DEBUG_POS("set_probe_deployed", current_position);
SERIAL_ECHOLNPAIR("deploy: ", deploy);
}
#endif
if (endstops.z_probe_enabled == deploy) return false;
// Make room for probe
2016-08-03 22:51:05 -05:00
do_probe_raise(_Z_PROBE_DEPLOY_HEIGHT);
2016-06-20 17:50:51 -05:00
#if ENABLED(Z_PROBE_SLED)
if (axis_unhomed_error(true, false, false)) { stop(); return true; }
#elif ENABLED(Z_PROBE_ALLEN_KEY)
if (axis_unhomed_error(true, true, true )) { stop(); return true; }
#endif
float oldXpos = current_position[X_AXIS]; // save x position
float oldYpos = current_position[Y_AXIS]; // save y position
#ifdef _TRIGGERED_WHEN_STOWED_TEST
2016-08-06 16:24:05 -05:00
// If endstop is already false, the Z probe is deployed
2016-08-06 16:24:05 -05:00
if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { // closed after the probe specific actions.
// Would a goto be less ugly?
//while (!_TRIGGERED_WHEN_STOWED_TEST) idle(); // would offer the opportunity
// for a triggered when stowed manual probe.
2016-08-06 16:24:05 -05:00
if (!deploy) endstops.enable_z_probe(false); // Switch off triggered when stowed probes early
// otherwise an Allen-Key probe can't be stowed.
#endif
2016-08-06 16:24:05 -05:00
#if ENABLED(Z_PROBE_SLED)
dock_sled(!deploy);
#elif HAS_Z_SERVO_ENDSTOP
servo[Z_ENDSTOP_SERVO_NR].move(z_servo_angle[deploy ? 0 : 1]);
#elif ENABLED(Z_PROBE_ALLEN_KEY)
deploy ? run_deploy_moves_script() : run_stow_moves_script();
#endif
#ifdef _TRIGGERED_WHEN_STOWED_TEST
2016-08-06 16:24:05 -05:00
} // _TRIGGERED_WHEN_STOWED_TEST == deploy
if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { // State hasn't changed?
if (IsRunning()) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Z-Probe failed");
LCD_ALERTMESSAGEPGM("Err: ZPROBE");
}
stop();
return true;
2016-08-06 16:24:05 -05:00
} // _TRIGGERED_WHEN_STOWED_TEST == deploy
#endif
do_blocking_move_to(oldXpos, oldYpos, current_position[Z_AXIS]); // return to position before deploy
2016-08-27 19:53:02 -05:00
endstops.enable_z_probe(deploy);
return false;
}
2016-08-19 01:10:41 -05:00
static void do_probe_move(float z, float fr_mm_m) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS(">>> do_probe_move", current_position);
#endif
// Move down until probe triggered
do_blocking_move_to_z(LOGICAL_Z_POSITION(z), MMM_TO_MMS(fr_mm_m));
// Clear endstop flags
endstops.hit_on_purpose();
// Get Z where the steppers were interrupted
set_current_from_steppers_for_axis(Z_AXIS);
// Tell the planner where we actually are
SYNC_PLAN_POSITION_KINEMATIC();
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("<<< do_probe_move", current_position);
#endif
}
2016-06-21 17:14:04 -05:00
// Do a single Z probe and return with current_position[Z_AXIS]
// at the height where the probe triggered.
2016-06-22 18:52:32 -05:00
static float run_z_probe() {
2016-08-19 01:09:03 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS(">>> run_z_probe", current_position);
#endif
2016-06-21 17:14:04 -05:00
// Prevent stepper_inactive_time from running out and EXTRUDER_RUNOUT_PREVENT from extruding
2016-03-26 22:36:36 -05:00
refresh_cmd_timeout();
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
planner.bed_level_matrix.set_to_identity();
#endif
double bump probing as a feature Why double touch probing is not a good thing. It's widely believed we can get better __probing__ results when using a double touch when probing. Let's compare to double touch __homing__. Or better let's begin with single touch __homing__. We home to find out out position, so our position is unknown. To find the endstop we have to move into the direction of the endstop. The maximum way we have to move is a bit longer than the axis length. When we arrive at the endstop - when it triggers, the stepper pulses are stopped immediately. It's a sudden stop. No smooth deacceleration is possible. Depending on the speed and the moving mass we lose steps here. Only if we approached slow enough (below jerk speed?) we will not lose steps. Moving a complete axis length, that slow, takes for ever. To speed up homing, we now make the first approach faster, get a guess about our position, back up a bit and make a second slower approach to get a exact result without losing steps. What we do in double touch probing is the same. But the difference here is: a. we already know where we are b. if the first approach is to fast we will lose steps here to. But this time there is no second approach to set the position to 0. We are measuring only. The lost steps are permanent until we home the next time. So if you experienced permanently rising values in M48 you now know why. (Too fast, suddenly stopped, first approach) What can we do to improve probing? We can use the information about our current position. We can make a really fast, but deaccelerated, move to a place we know it is a bit before the trigger point. And then move the rest of the way really slow.
2016-07-29 20:00:49 -05:00
#if ENABLED(PROBE_DOUBLE_TOUCH)
2016-08-19 01:10:41 -05:00
// Do a first probe at the fast speed
do_probe_move(-(Z_MAX_LENGTH) - 10, Z_PROBE_SPEED_FAST);
// move up by the bump distance
do_blocking_move_to_z(current_position[Z_AXIS] + home_bump_mm(Z_AXIS), MMM_TO_MMS(Z_PROBE_SPEED_FAST));
double bump probing as a feature Why double touch probing is not a good thing. It's widely believed we can get better __probing__ results when using a double touch when probing. Let's compare to double touch __homing__. Or better let's begin with single touch __homing__. We home to find out out position, so our position is unknown. To find the endstop we have to move into the direction of the endstop. The maximum way we have to move is a bit longer than the axis length. When we arrive at the endstop - when it triggers, the stepper pulses are stopped immediately. It's a sudden stop. No smooth deacceleration is possible. Depending on the speed and the moving mass we lose steps here. Only if we approached slow enough (below jerk speed?) we will not lose steps. Moving a complete axis length, that slow, takes for ever. To speed up homing, we now make the first approach faster, get a guess about our position, back up a bit and make a second slower approach to get a exact result without losing steps. What we do in double touch probing is the same. But the difference here is: a. we already know where we are b. if the first approach is to fast we will lose steps here to. But this time there is no second approach to set the position to 0. We are measuring only. The lost steps are permanent until we home the next time. So if you experienced permanently rising values in M48 you now know why. (Too fast, suddenly stopped, first approach) What can we do to improve probing? We can use the information about our current position. We can make a really fast, but deaccelerated, move to a place we know it is a bit before the trigger point. And then move the rest of the way really slow.
2016-07-29 20:00:49 -05:00
#else
double bump probing as a feature Why double touch probing is not a good thing. It's widely believed we can get better __probing__ results when using a double touch when probing. Let's compare to double touch __homing__. Or better let's begin with single touch __homing__. We home to find out out position, so our position is unknown. To find the endstop we have to move into the direction of the endstop. The maximum way we have to move is a bit longer than the axis length. When we arrive at the endstop - when it triggers, the stepper pulses are stopped immediately. It's a sudden stop. No smooth deacceleration is possible. Depending on the speed and the moving mass we lose steps here. Only if we approached slow enough (below jerk speed?) we will not lose steps. Moving a complete axis length, that slow, takes for ever. To speed up homing, we now make the first approach faster, get a guess about our position, back up a bit and make a second slower approach to get a exact result without losing steps. What we do in double touch probing is the same. But the difference here is: a. we already know where we are b. if the first approach is to fast we will lose steps here to. But this time there is no second approach to set the position to 0. We are measuring only. The lost steps are permanent until we home the next time. So if you experienced permanently rising values in M48 you now know why. (Too fast, suddenly stopped, first approach) What can we do to improve probing? We can use the information about our current position. We can make a really fast, but deaccelerated, move to a place we know it is a bit before the trigger point. And then move the rest of the way really slow.
2016-07-29 20:00:49 -05:00
// move fast, close to the bed
float z = LOGICAL_Z_POSITION(home_bump_mm(Z_AXIS));
if (zprobe_zoffset < 0) z -= zprobe_zoffset;
do_blocking_move_to_z(z, MMM_TO_MMS(Z_PROBE_SPEED_FAST));
double bump probing as a feature Why double touch probing is not a good thing. It's widely believed we can get better __probing__ results when using a double touch when probing. Let's compare to double touch __homing__. Or better let's begin with single touch __homing__. We home to find out out position, so our position is unknown. To find the endstop we have to move into the direction of the endstop. The maximum way we have to move is a bit longer than the axis length. When we arrive at the endstop - when it triggers, the stepper pulses are stopped immediately. It's a sudden stop. No smooth deacceleration is possible. Depending on the speed and the moving mass we lose steps here. Only if we approached slow enough (below jerk speed?) we will not lose steps. Moving a complete axis length, that slow, takes for ever. To speed up homing, we now make the first approach faster, get a guess about our position, back up a bit and make a second slower approach to get a exact result without losing steps. What we do in double touch probing is the same. But the difference here is: a. we already know where we are b. if the first approach is to fast we will lose steps here to. But this time there is no second approach to set the position to 0. We are measuring only. The lost steps are permanent until we home the next time. So if you experienced permanently rising values in M48 you now know why. (Too fast, suddenly stopped, first approach) What can we do to improve probing? We can use the information about our current position. We can make a really fast, but deaccelerated, move to a place we know it is a bit before the trigger point. And then move the rest of the way really slow.
2016-07-29 20:00:49 -05:00
#endif
double bump probing as a feature Why double touch probing is not a good thing. It's widely believed we can get better __probing__ results when using a double touch when probing. Let's compare to double touch __homing__. Or better let's begin with single touch __homing__. We home to find out out position, so our position is unknown. To find the endstop we have to move into the direction of the endstop. The maximum way we have to move is a bit longer than the axis length. When we arrive at the endstop - when it triggers, the stepper pulses are stopped immediately. It's a sudden stop. No smooth deacceleration is possible. Depending on the speed and the moving mass we lose steps here. Only if we approached slow enough (below jerk speed?) we will not lose steps. Moving a complete axis length, that slow, takes for ever. To speed up homing, we now make the first approach faster, get a guess about our position, back up a bit and make a second slower approach to get a exact result without losing steps. What we do in double touch probing is the same. But the difference here is: a. we already know where we are b. if the first approach is to fast we will lose steps here to. But this time there is no second approach to set the position to 0. We are measuring only. The lost steps are permanent until we home the next time. So if you experienced permanently rising values in M48 you now know why. (Too fast, suddenly stopped, first approach) What can we do to improve probing? We can use the information about our current position. We can make a really fast, but deaccelerated, move to a place we know it is a bit before the trigger point. And then move the rest of the way really slow.
2016-07-29 20:00:49 -05:00
// move down slowly to find bed
do_probe_move(-(Z_MAX_LENGTH) - 10, Z_PROBE_SPEED_SLOW);
2016-06-27 21:33:37 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-08-19 01:09:03 -05:00
if (DEBUGGING(LEVELING)) DEBUG_POS("<<< run_z_probe", current_position);
#endif
2016-06-22 18:52:32 -05:00
return current_position[Z_AXIS];
}
2016-06-23 21:00:29 -05:00
//
// - Move to the given XY
// - Deploy the probe, if not already deployed
// - Probe the bed, get the Z position
// - Depending on the 'stow' flag
// - Stow the probe, or
// - Raise to the BETWEEN height
// - Return the probed Z position
//
static float probe_pt(float x, float y, bool stow = true, int verbose_level = 1) {
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2016-06-27 21:33:37 -05:00
SERIAL_ECHOPAIR(">>> probe_pt(", x);
SERIAL_ECHOPAIR(", ", y);
SERIAL_ECHOPAIR(", ", stow ? "stow" : "no stow");
SERIAL_ECHOLNPGM(")");
DEBUG_POS("", current_position);
2015-08-05 06:40:36 -05:00
}
2015-07-09 18:57:44 -05:00
#endif
float old_feedrate_mm_s = feedrate_mm_s;
// Ensure a minimum height before moving the probe
2016-08-03 22:51:05 -05:00
do_probe_raise(Z_PROBE_TRAVEL_HEIGHT);
// Move to the XY where we shall probe
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2016-06-25 19:59:03 -05:00
SERIAL_ECHOPAIR("> do_blocking_move_to_xy(", x - (X_PROBE_OFFSET_FROM_EXTRUDER));
2016-03-13 00:38:55 -06:00
SERIAL_ECHOPAIR(", ", y - (Y_PROBE_OFFSET_FROM_EXTRUDER));
2016-06-25 19:59:03 -05:00
SERIAL_ECHOLNPGM(")");
2015-08-05 06:40:36 -05:00
}
2015-07-09 18:57:44 -05:00
#endif
feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S;
2016-03-26 22:36:36 -05:00
do_blocking_move_to_xy(x - (X_PROBE_OFFSET_FROM_EXTRUDER), y - (Y_PROBE_OFFSET_FROM_EXTRUDER));
2016-06-23 21:00:29 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOPGM("> ");
2016-06-23 21:00:29 -05:00
#endif
if (DEPLOY_PROBE()) return NAN;
2016-06-22 18:52:32 -05:00
float measured_z = run_z_probe();
2016-06-23 21:00:29 -05:00
if (stow) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-06-27 21:16:21 -05:00
if (DEBUGGING(LEVELING)) SERIAL_ECHOPGM("> ");
#endif
if (STOW_PROBE()) return NAN;
}
else {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> do_probe_raise");
#endif
2016-08-03 22:51:05 -05:00
do_probe_raise(Z_PROBE_TRAVEL_HEIGHT);
}
if (verbose_level > 2) {
2015-05-17 03:49:52 -05:00
SERIAL_PROTOCOLPGM("Bed X: ");
SERIAL_PROTOCOL_F(x, 3);
SERIAL_PROTOCOLPGM(" Y: ");
SERIAL_PROTOCOL_F(y, 3);
SERIAL_PROTOCOLPGM(" Z: ");
SERIAL_PROTOCOL_F(measured_z, 3);
SERIAL_EOL;
}
2015-07-09 18:57:44 -05:00
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< probe_pt");
2015-07-09 18:57:44 -05:00
#endif
feedrate_mm_s = old_feedrate_mm_s;
return measured_z;
}
2016-06-23 21:00:29 -05:00
#endif // HAS_BED_PROBE
2016-06-22 16:03:22 -05:00
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_GRID)
#if DISABLED(DELTA)
static void set_bed_level_equation_lsq(double* plane_equation_coefficients) {
//planner.bed_level_matrix.debug("bed level before");
#if ENABLED(DEBUG_LEVELING_FEATURE)
planner.bed_level_matrix.set_to_identity();
if (DEBUGGING(LEVELING)) {
vector_3 uncorrected_position = planner.adjusted_position();
DEBUG_POS(">>> set_bed_level_equation_lsq", uncorrected_position);
DEBUG_POS(">>> set_bed_level_equation_lsq", current_position);
}
#endif
vector_3 planeNormal = vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1);
planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
vector_3 corrected_position = planner.adjusted_position();
current_position[X_AXIS] = corrected_position.x;
current_position[Y_AXIS] = corrected_position.y;
current_position[Z_AXIS] = corrected_position.z;
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("<<< set_bed_level_equation_lsq", corrected_position);
#endif
SYNC_PLAN_POSITION_KINEMATIC();
}
#endif // !DELTA
#else // !AUTO_BED_LEVELING_GRID
static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float z_at_pt_3) {
planner.bed_level_matrix.set_to_identity();
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
vector_3 uncorrected_position = planner.adjusted_position();
DEBUG_POS("set_bed_level_equation_3pts", uncorrected_position);
}
#endif
vector_3 pt1 = vector_3(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, z_at_pt_1);
vector_3 pt2 = vector_3(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, z_at_pt_2);
vector_3 pt3 = vector_3(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, z_at_pt_3);
vector_3 planeNormal = vector_3::cross(pt1 - pt2, pt3 - pt2).get_normal();
if (planeNormal.z < 0) {
planeNormal.x = -planeNormal.x;
planeNormal.y = -planeNormal.y;
planeNormal.z = -planeNormal.z;
}
planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
vector_3 corrected_position = planner.adjusted_position();
current_position[X_AXIS] = corrected_position.x;
current_position[Y_AXIS] = corrected_position.y;
current_position[Z_AXIS] = corrected_position.z;
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("set_bed_level_equation_3pts", corrected_position);
#endif
SYNC_PLAN_POSITION_KINEMATIC();
}
#endif // !AUTO_BED_LEVELING_GRID
#if ENABLED(DELTA)
/**
* All DELTA leveling in the Marlin uses NONLINEAR_BED_LEVELING
*/
static void extrapolate_one_point(int x, int y, int xdir, int ydir) {
if (bed_level[x][y] != 0.0) {
return; // Don't overwrite good values.
}
float a = 2 * bed_level[x + xdir][y] - bed_level[x + xdir * 2][y]; // Left to right.
float b = 2 * bed_level[x][y + ydir] - bed_level[x][y + ydir * 2]; // Front to back.
float c = 2 * bed_level[x + xdir][y + ydir] - bed_level[x + xdir * 2][y + ydir * 2]; // Diagonal.
float median = c; // Median is robust (ignores outliers).
if (a < b) {
if (b < c) median = b;
if (c < a) median = a;
2015-10-13 05:51:34 -05:00
}
else { // b <= a
if (c < b) median = b;
if (a < c) median = a;
}
bed_level[x][y] = median;
}
2016-03-26 22:36:36 -05:00
/**
* Fill in the unprobed points (corners of circular print surface)
* using linear extrapolation, away from the center.
*/
static void extrapolate_unprobed_bed_level() {
int half = (AUTO_BED_LEVELING_GRID_POINTS - 1) / 2;
for (int y = 0; y <= half; y++) {
for (int x = 0; x <= half; x++) {
if (x + y < 3) continue;
extrapolate_one_point(half - x, half - y, x > 1 ? +1 : 0, y > 1 ? +1 : 0);
extrapolate_one_point(half + x, half - y, x > 1 ? -1 : 0, y > 1 ? +1 : 0);
extrapolate_one_point(half - x, half + y, x > 1 ? +1 : 0, y > 1 ? -1 : 0);
extrapolate_one_point(half + x, half + y, x > 1 ? -1 : 0, y > 1 ? -1 : 0);
}
}
}
2016-03-26 22:36:36 -05:00
/**
* Print calibration results for plotting or manual frame adjustment.
*/
static void print_bed_level() {
for (int y = 0; y < AUTO_BED_LEVELING_GRID_POINTS; y++) {
for (int x = 0; x < AUTO_BED_LEVELING_GRID_POINTS; x++) {
SERIAL_PROTOCOL_F(bed_level[x][y], 2);
2015-04-03 23:43:30 -05:00
SERIAL_PROTOCOLCHAR(' ');
}
2015-04-03 23:43:30 -05:00
SERIAL_EOL;
}
}
2016-03-26 22:36:36 -05:00
/**
* Reset calibration results to zero.
*/
void reset_bed_level() {
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("reset_bed_level");
2015-07-09 18:57:44 -05:00
#endif
for (int y = 0; y < AUTO_BED_LEVELING_GRID_POINTS; y++) {
for (int x = 0; x < AUTO_BED_LEVELING_GRID_POINTS; x++) {
bed_level[x][y] = 0.0;
}
}
}
#endif // DELTA
#endif // AUTO_BED_LEVELING_FEATURE
2015-04-01 03:44:13 -05:00
/**
* Home an individual axis
*/
2016-08-19 01:11:41 -05:00
static void do_homing_move(AxisEnum axis, float where, float fr_mm_s = 0.0) {
2016-08-27 19:53:02 -05:00
current_position[axis] = 0;
sync_plan_position();
2016-08-19 01:11:41 -05:00
current_position[axis] = where;
2016-08-27 19:53:02 -05:00
planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], (fr_mm_s != 0.0) ? fr_mm_s : homing_feedrate_mm_s[axis], active_extruder);
2016-08-19 01:11:41 -05:00
stepper.synchronize();
2016-08-27 19:53:02 -05:00
endstops.hit_on_purpose();
2016-08-19 01:11:41 -05:00
}
2015-04-01 03:44:13 -05:00
#define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
static void homeaxis(AxisEnum axis) {
#define HOMEAXIS_DO(LETTER) \
((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))
2016-08-27 19:53:02 -05:00
if (!(axis == X_AXIS ? HOMEAXIS_DO(X) : axis == Y_AXIS ? HOMEAXIS_DO(Y) : axis == Z_AXIS ? HOMEAXIS_DO(Z) : false)) return;
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2016-08-19 01:09:03 -05:00
SERIAL_ECHOPAIR(">>> homeaxis(", axis_codes[axis]);
SERIAL_ECHOLNPGM(")");
2015-08-05 06:40:36 -05:00
}
2015-07-09 18:57:44 -05:00
#endif
int axis_home_dir =
#if ENABLED(DUAL_X_CARRIAGE)
(axis == X_AXIS) ? x_home_dir(active_extruder) :
#endif
home_dir(axis);
2016-03-30 19:19:54 -05:00
// Homing Z towards the bed? Deploy the Z probe or endstop.
#if HAS_BED_PROBE && Z_HOME_DIR < 0 && DISABLED(Z_MIN_PROBE_ENDSTOP)
if (axis == Z_AXIS) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOPGM("> ");
#endif
if (DEPLOY_PROBE()) return;
}
#endif
// Set a flag for Z motor locking
#if ENABLED(Z_DUAL_ENDSTOPS)
if (axis == Z_AXIS) stepper.set_homing_flag(true);
#endif
// Move towards the endstop until an endstop is triggered
2016-08-19 01:11:41 -05:00
do_homing_move(axis, 1.5 * max_length(axis) * axis_home_dir);
2015-04-01 03:44:13 -05:00
2016-08-27 19:53:02 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("> 1st Home", current_position[axis]);
#endif
// Move away from the endstop by the axis HOME_BUMP_MM
2016-08-19 01:11:41 -05:00
do_homing_move(axis, -home_bump_mm(axis) * axis_home_dir);
2015-04-01 03:44:13 -05:00
// Move slowly towards the endstop until triggered
2016-08-19 01:11:41 -05:00
do_homing_move(axis, 2 * home_bump_mm(axis) * axis_home_dir, get_homing_bump_feedrate(axis));
2015-07-09 18:57:44 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-08-27 19:53:02 -05:00
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("> 2nd Home", current_position[axis]);
#endif
2015-04-01 03:44:13 -05:00
#if ENABLED(Z_DUAL_ENDSTOPS)
if (axis == Z_AXIS) {
float adj = fabs(z_endstop_adj);
bool lockZ1;
if (axis_home_dir > 0) {
adj = -adj;
lockZ1 = (z_endstop_adj > 0);
}
else
lockZ1 = (z_endstop_adj < 0);
2015-04-01 03:44:13 -05:00
if (lockZ1) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
2015-04-01 03:44:13 -05:00
// Move to the adjusted endstop height
2016-08-19 01:11:41 -05:00
do_homing_move(axis, adj);
2015-04-01 03:44:13 -05:00
if (lockZ1) stepper.set_z_lock(false); else stepper.set_z2_lock(false);
stepper.set_homing_flag(false);
} // Z_AXIS
#endif
2016-08-27 19:53:02 -05:00
// Delta has already moved all three towers up in G28
// so here it re-homes each tower in turn.
// Delta homing treats the axes as normal linear axes.
#if ENABLED(DELTA)
2016-08-27 19:53:02 -05:00
// retrace by the amount specified in endstop_adj
if (endstop_adj[axis] * Z_HOME_DIR < 0) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
2016-08-27 19:53:02 -05:00
SERIAL_ECHOPAIR("> endstop_adj = ", endstop_adj[axis] * Z_HOME_DIR);
DEBUG_POS("", current_position);
}
#endif
2016-08-19 01:11:41 -05:00
do_homing_move(axis, endstop_adj[axis]);
}
2016-08-27 19:53:02 -05:00
#else
2015-04-01 03:44:13 -05:00
2016-08-27 19:53:02 -05:00
// Set the axis position to its home position (plus home offsets)
set_axis_is_at_home(axis);
sync_plan_position();
2015-07-09 18:57:44 -05:00
2016-08-27 19:53:02 -05:00
destination[axis] = current_position[axis];
2016-08-27 19:53:02 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("> AFTER set_axis_is_at_home", current_position);
#endif
#endif
2015-04-28 21:10:07 -05:00
// Put away the Z probe
#if HAS_BED_PROBE && Z_HOME_DIR < 0 && DISABLED(Z_MIN_PROBE_ENDSTOP)
if (axis == Z_AXIS) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOPGM("> ");
#endif
if (STOW_PROBE()) return;
}
#endif
2015-07-09 18:57:44 -05:00
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2016-08-19 01:09:03 -05:00
SERIAL_ECHOPAIR("<<< homeaxis(", axis_codes[axis]);
SERIAL_ECHOLNPGM(")");
2015-08-05 06:40:36 -05:00
}
2015-07-09 18:57:44 -05:00
#endif
2016-08-19 01:12:41 -05:00
} // homeaxis()
#if ENABLED(FWRETRACT)
void retract(bool retracting, bool swapping = false) {
if (retracting == retracted[active_extruder]) return;
float old_feedrate_mm_s = feedrate_mm_s;
set_destination_to_current();
if (retracting) {
feedrate_mm_s = retract_feedrate_mm_s;
current_position[E_AXIS] += (swapping ? retract_length_swap : retract_length) / volumetric_multiplier[active_extruder];
sync_plan_position_e();
prepare_move_to_destination();
if (retract_zlift > 0.01) {
current_position[Z_AXIS] -= retract_zlift;
SYNC_PLAN_POSITION_KINEMATIC();
prepare_move_to_destination();
}
}
else {
if (retract_zlift > 0.01) {
current_position[Z_AXIS] += retract_zlift;
SYNC_PLAN_POSITION_KINEMATIC();
}
feedrate_mm_s = retract_recover_feedrate_mm_s;
float move_e = swapping ? retract_length_swap + retract_recover_length_swap : retract_length + retract_recover_length;
current_position[E_AXIS] -= move_e / volumetric_multiplier[active_extruder];
sync_plan_position_e();
prepare_move_to_destination();
}
feedrate_mm_s = old_feedrate_mm_s;
retracted[active_extruder] = retracting;
} // retract()
#endif // FWRETRACT
#if ENABLED(MIXING_EXTRUDER)
void normalize_mix() {
float mix_total = 0.0;
for (int i = 0; i < MIXING_STEPPERS; i++) {
float v = mixing_factor[i];
if (v < 0) v = mixing_factor[i] = 0;
mix_total += v;
}
// Scale all values if they don't add up to ~1.0
if (mix_total < 0.9999 || mix_total > 1.0001) {
SERIAL_PROTOCOLLNPGM("Warning: Mix factors must add up to 1.0. Scaling.");
float mix_scale = 1.0 / mix_total;
for (int i = 0; i < MIXING_STEPPERS; i++)
mixing_factor[i] *= mix_scale;
}
}
#if ENABLED(DIRECT_MIXING_IN_G1)
// Get mixing parameters from the GCode
// Factors that are left out are set to 0
// The total "must" be 1.0 (but it will be normalized)
void gcode_get_mix() {
const char* mixing_codes = "ABCDHI";
for (int i = 0; i < MIXING_STEPPERS; i++)
mixing_factor[i] = code_seen(mixing_codes[i]) ? code_value_float() : 0;
normalize_mix();
}
#endif
#endif
/**
2016-03-26 22:36:36 -05:00
* ***************************************************************************
* ***************************** G-CODE HANDLING *****************************
* ***************************************************************************
*/
/**
* Set XYZE destination and feedrate from the current GCode command
*
* - Set destination from included axis codes
* - Set to current for missing axis codes
* - Set the feedrate, if included
*/
void gcode_get_destination() {
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) {
if (code_seen(axis_codes[i]))
destination[i] = code_value_axis_units(i) + (axis_relative_modes[i] || relative_mode ? current_position[i] : 0);
else
destination[i] = current_position[i];
}
if (code_seen('F') && code_value_linear_units() > 0.0)
feedrate_mm_s = MMM_TO_MMS(code_value_linear_units());
#if ENABLED(PRINTCOUNTER)
2016-07-15 20:49:34 -05:00
if (!DEBUGGING(DRYRUN))
print_job_timer.incFilamentUsed(destination[E_AXIS] - current_position[E_AXIS]);
#endif
// Get ABCDHI mixing factors
#if ENABLED(MIXING_EXTRUDER) && ENABLED(DIRECT_MIXING_IN_G1)
gcode_get_mix();
#endif
}
2015-05-17 07:00:09 -05:00
void unknown_command_error() {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_UNKNOWN_COMMAND);
SERIAL_ECHO(current_command);
SERIAL_ECHOLNPGM("\"");
2015-05-17 07:00:09 -05:00
}
#if ENABLED(HOST_KEEPALIVE_FEATURE)
/**
* Output a "busy" message at regular intervals
* while the machine is not accepting commands.
*/
void host_keepalive() {
millis_t ms = millis();
2016-04-09 18:58:17 -05:00
if (host_keepalive_interval && busy_state != NOT_BUSY) {
2016-04-10 17:55:12 -05:00
if (PENDING(ms, next_busy_signal_ms)) return;
switch (busy_state) {
case IN_HANDLER:
case IN_PROCESS:
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_BUSY_PROCESSING);
break;
case PAUSED_FOR_USER:
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_BUSY_PAUSED_FOR_USER);
break;
case PAUSED_FOR_INPUT:
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_BUSY_PAUSED_FOR_INPUT);
break;
2016-04-02 16:28:17 -05:00
default:
break;
}
}
2016-04-10 17:55:12 -05:00
next_busy_signal_ms = ms + host_keepalive_interval * 1000UL;
}
#endif //HOST_KEEPALIVE_FEATURE
/**
* G0, G1: Coordinated movement of X Y Z E axes
*/
inline void gcode_G0_G1() {
2015-04-08 02:56:19 -05:00
if (IsRunning()) {
gcode_get_destination(); // For X Y Z E F
2015-04-13 19:17:36 -05:00
#if ENABLED(FWRETRACT)
2015-04-13 19:17:36 -05:00
if (autoretract_enabled && !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) {
float echange = destination[E_AXIS] - current_position[E_AXIS];
// Is this move an attempt to retract or recover?
if ((echange < -MIN_RETRACT && !retracted[active_extruder]) || (echange > MIN_RETRACT && retracted[active_extruder])) {
current_position[E_AXIS] = destination[E_AXIS]; // hide the slicer-generated retract/recover from calculations
sync_plan_position_e(); // AND from the planner
retract(!retracted[active_extruder]);
return;
}
}
2015-04-13 19:17:36 -05:00
#endif //FWRETRACT
2015-04-13 19:17:36 -05:00
prepare_move_to_destination();
}
}
/**
* G2: Clockwise Arc
* G3: Counterclockwise Arc
*/
#if ENABLED(ARC_SUPPORT)
inline void gcode_G2_G3(bool clockwise) {
if (IsRunning()) {
#if ENABLED(SF_ARC_FIX)
bool relative_mode_backup = relative_mode;
relative_mode = true;
#endif
gcode_get_destination();
#if ENABLED(SF_ARC_FIX)
relative_mode = relative_mode_backup;
#endif
// Center of arc as offset from current_position
float arc_offset[2] = {
code_seen('I') ? code_value_axis_units(X_AXIS) : 0,
code_seen('J') ? code_value_axis_units(Y_AXIS) : 0
};
// Send an arc to the planner
plan_arc(destination, arc_offset, clockwise);
refresh_cmd_timeout();
}
}
#endif
/**
* G4: Dwell S<seconds> or P<milliseconds>
*/
inline void gcode_G4() {
2016-07-14 18:39:49 -05:00
millis_t dwell_ms = 0;
2016-07-14 18:39:49 -05:00
if (code_seen('P')) dwell_ms = code_value_millis(); // milliseconds to wait
if (code_seen('S')) dwell_ms = code_value_millis_from_seconds(); // seconds to wait
stepper.synchronize();
2015-04-03 17:31:35 -05:00
refresh_cmd_timeout();
2016-07-14 18:39:49 -05:00
dwell_ms += previous_cmd_ms; // keep track of when we started waiting
if (!lcd_hasstatus()) LCD_MESSAGEPGM(MSG_DWELL);
2016-07-14 18:39:49 -05:00
while (PENDING(millis(), dwell_ms)) idle();
}
#if ENABLED(BEZIER_CURVE_SUPPORT)
/**
* Parameters interpreted according to:
* http://linuxcnc.org/docs/2.6/html/gcode/gcode.html#sec:G5-Cubic-Spline
* However I, J omission is not supported at this point; all
* parameters can be omitted and default to zero.
*/
/**
* G5: Cubic B-spline
*/
inline void gcode_G5() {
if (IsRunning()) {
gcode_get_destination();
float offset[] = {
code_seen('I') ? code_value_axis_units(X_AXIS) : 0.0,
code_seen('J') ? code_value_axis_units(Y_AXIS) : 0.0,
code_seen('P') ? code_value_axis_units(X_AXIS) : 0.0,
code_seen('Q') ? code_value_axis_units(Y_AXIS) : 0.0
};
plan_cubic_move(offset);
}
}
#endif // BEZIER_CURVE_SUPPORT
#if ENABLED(FWRETRACT)
/**
* G10 - Retract filament according to settings of M207
* G11 - Recover filament according to settings of M208
*/
inline void gcode_G10_G11(bool doRetract=false) {
#if EXTRUDERS > 1
if (doRetract) {
retracted_swap[active_extruder] = (code_seen('S') && code_value_bool()); // checks for swap retract argument
}
#endif
retract(doRetract
#if EXTRUDERS > 1
, retracted_swap[active_extruder]
#endif
);
}
2013-06-09 23:10:00 -05:00
#endif //FWRETRACT
2013-06-09 23:10:00 -05:00
#if ENABLED(NOZZLE_CLEAN_FEATURE)
/**
* G12: Clean the nozzle
*/
inline void gcode_G12() {
// Don't allow nozzle cleaning without homing first
if (axis_unhomed_error(true, true, true)) { return; }
uint8_t const pattern = code_seen('P') ? code_value_ushort() : 0;
uint8_t const strokes = code_seen('S') ? code_value_ushort() : NOZZLE_CLEAN_STROKES;
2016-06-22 18:23:55 -05:00
uint8_t const objects = code_seen('T') ? code_value_ushort() : 3;
2016-06-22 18:23:55 -05:00
Nozzle::clean(pattern, strokes, objects);
}
#endif
#if ENABLED(INCH_MODE_SUPPORT)
/**
* G20: Set input mode to inches
*/
inline void gcode_G20() {
set_input_linear_units(LINEARUNIT_INCH);
}
/**
* G21: Set input mode to millimeters
*/
inline void gcode_G21() {
set_input_linear_units(LINEARUNIT_MM);
}
#endif
#if ENABLED(NOZZLE_PARK_FEATURE)
/**
* G27: Park the nozzle
*/
inline void gcode_G27() {
// Don't allow nozzle parking without homing first
if (axis_unhomed_error(true, true, true)) { return; }
uint8_t const z_action = code_seen('P') ? code_value_ushort() : 0;
Nozzle::park(z_action);
}
#endif // NOZZLE_PARK_FEATURE
#if ENABLED(QUICK_HOME)
static void quick_home_xy() {
// Pretend the current position is 0,0
current_position[X_AXIS] = current_position[Y_AXIS] = 0.0;
sync_plan_position();
2016-07-20 12:30:10 -05:00
int x_axis_home_dir =
#if ENABLED(DUAL_X_CARRIAGE)
x_home_dir(active_extruder)
#else
home_dir(X_AXIS)
#endif
;
float mlx = max_length(X_AXIS),
mly = max_length(Y_AXIS),
mlratio = mlx > mly ? mly / mlx : mlx / mly,
fr_mm_s = min(homing_feedrate_mm_s[X_AXIS], homing_feedrate_mm_s[Y_AXIS]) * sqrt(sq(mlratio) + 1.0);
do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * home_dir(Y_AXIS), fr_mm_s);
endstops.hit_on_purpose(); // clear endstop hit flags
current_position[X_AXIS] = current_position[Y_AXIS] = 0.0;
}
#endif // QUICK_HOME
/**
* G28: Home all axes according to settings
*
* Parameters
*
* None Home to all axes with no parameters.
* With QUICK_HOME enabled XY will home together, then Z.
*
* Cartesian parameters
*
* X Home to the X endstop
* Y Home to the Y endstop
* Z Home to the Z endstop
*
*/
inline void gcode_G28() {
2015-04-03 17:31:35 -05:00
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-06-27 21:33:37 -05:00
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM(">>> gcode_G28");
2015-07-09 18:57:44 -05:00
#endif
2015-05-12 02:31:51 -05:00
// Wait for planner moves to finish!
stepper.synchronize();
2015-05-12 02:31:51 -05:00
2015-04-03 17:31:35 -05:00
// For auto bed leveling, clear the level matrix
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
2016-04-27 20:06:32 -05:00
planner.bed_level_matrix.set_to_identity();
#if ENABLED(DELTA)
reset_bed_level();
#endif
#endif
2013-06-09 23:10:00 -05:00
2016-07-19 21:37:31 -05:00
// Always home with tool 0 active
#if HOTENDS > 1
uint8_t old_tool_index = active_extruder;
tool_change(0, 0, true);
#endif
2016-07-20 12:30:10 -05:00
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
extruder_duplication_enabled = false;
#endif
2016-03-26 22:36:36 -05:00
/**
* For mesh bed leveling deactivate the mesh calculations, will be turned
* on again when homing all axis
*/
#if ENABLED(MESH_BED_LEVELING)
float pre_home_z = MESH_HOME_SEARCH_Z;
if (mbl.active()) {
2016-07-17 01:35:15 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("MBL was active");
#endif
// Save known Z position if already homed
if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) {
pre_home_z = current_position[Z_AXIS];
pre_home_z += mbl.get_z(RAW_CURRENT_POSITION(X_AXIS), RAW_CURRENT_POSITION(Y_AXIS));
}
mbl.set_active(false);
current_position[Z_AXIS] = pre_home_z;
2016-07-17 01:35:15 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("Set Z to pre_home_z", current_position);
#endif
}
#endif
2015-03-15 17:18:11 -05:00
setup_for_endstop_or_probe_move();
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> endstops.enable(true)");
#endif
endstops.enable(true); // Enable endstops for next homing move
#if ENABLED(DELTA)
2016-03-26 22:36:36 -05:00
/**
* A delta can only safely home all axes at the same time
2016-08-27 19:53:02 -05:00
* This is like quick_home_xy() but for 3 towers.
2016-03-26 22:36:36 -05:00
*/
2016-08-27 19:53:02 -05:00
// Init the current position of all carriages to 0,0,0
memset(current_position, 0, sizeof(current_position));
sync_plan_position();
2016-08-27 19:53:02 -05:00
// Move all carriages together linearly until an endstop is hit.
current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (Z_MAX_LENGTH + 10);
feedrate_mm_s = homing_feedrate_mm_s[X_AXIS];
line_to_current_position();
stepper.synchronize();
endstops.hit_on_purpose(); // clear endstop hit flags
2016-08-27 19:53:02 -05:00
// Probably not needed. Double-check this line:
memset(current_position, 0, sizeof(current_position));
// At least one carriage has reached the top.
// Now back off and re-home each carriage separately.
HOMEAXIS(A);
HOMEAXIS(B);
HOMEAXIS(C);
// Set all carriages to their home positions
// Do this here all at once for Delta, because
// XYZ isn't ABC. Applying this per-tower would
// give the impression that they are the same.
LOOP_XYZ(i) set_axis_is_at_home((AxisEnum)i);
SYNC_PLAN_POSITION_KINEMATIC();
2013-06-09 23:10:00 -05:00
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("(DELTA)", current_position);
2015-07-09 18:57:44 -05:00
#endif
#else // NOT DELTA
bool homeX = code_seen('X'), homeY = code_seen('Y'), homeZ = code_seen('Z');
2015-04-24 21:23:12 -05:00
home_all_axis = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ);
set_destination_to_current();
#if Z_HOME_DIR > 0 // If homing away from BED do Z first
if (home_all_axis || homeZ) {
HOMEAXIS(Z);
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("> HOMEAXIS(Z)", current_position);
2015-07-09 18:57:44 -05:00
#endif
}
#else
2016-07-07 14:28:23 -05:00
if (home_all_axis || homeX || homeY) {
// Raise Z before homing any other axes and z is not already high enough (never lower z)
2016-08-03 22:51:05 -05:00
destination[Z_AXIS] = LOGICAL_Z_POSITION(Z_HOMING_HEIGHT);
2016-07-15 08:02:15 -05:00
if (destination[Z_AXIS] > current_position[Z_AXIS]) {
2016-07-07 14:28:23 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING))
SERIAL_ECHOLNPAIR("Raise Z (before homing) to ", destination[Z_AXIS]);
2016-07-07 14:28:23 -05:00
#endif
2016-07-15 08:02:15 -05:00
do_blocking_move_to_z(destination[Z_AXIS]);
2016-07-07 14:28:23 -05:00
}
}
#endif
2015-07-09 18:57:44 -05:00
#if ENABLED(QUICK_HOME)
2015-07-09 18:57:44 -05:00
2016-07-07 14:13:14 -05:00
if (home_all_axis || (homeX && homeY)) quick_home_xy();
2015-04-01 03:44:13 -05:00
#endif
#if ENABLED(HOME_Y_BEFORE_X)
// Home Y
2016-07-07 14:13:14 -05:00
if (home_all_axis || homeY) {
2016-06-27 11:01:11 -05:00
HOMEAXIS(Y);
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("> homeY", current_position);
#endif
}
#endif
// Home X
2016-07-07 14:13:14 -05:00
if (home_all_axis || homeX) {
#if ENABLED(DUAL_X_CARRIAGE)
int tmp_extruder = active_extruder;
active_extruder = !active_extruder;
HOMEAXIS(X);
inactive_extruder_x_pos = RAW_X_POSITION(current_position[X_AXIS]);
active_extruder = tmp_extruder;
HOMEAXIS(X);
// reset state used by the different modes
memcpy(raised_parked_position, current_position, sizeof(raised_parked_position));
delayed_move_time = 0;
active_extruder_parked = true;
#else
HOMEAXIS(X);
#endif
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("> homeX", current_position);
2015-07-09 18:57:44 -05:00
#endif
}
#if DISABLED(HOME_Y_BEFORE_X)
// Home Y
2016-07-07 14:13:14 -05:00
if (home_all_axis || homeY) {
2015-07-09 18:57:44 -05:00
HOMEAXIS(Y);
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("> homeY", current_position);
2015-07-09 18:57:44 -05:00
#endif
}
#endif
// Home Z last if homing towards the bed
#if Z_HOME_DIR < 0
if (home_all_axis || homeZ) {
#if ENABLED(Z_SAFE_HOMING)
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2015-08-05 06:40:36 -05:00
SERIAL_ECHOLNPGM("> Z_SAFE_HOMING >>>");
}
2015-07-09 18:57:44 -05:00
#endif
if (home_all_axis) {
2016-03-26 22:36:36 -05:00
/**
2016-08-03 22:51:05 -05:00
* At this point we already have Z at Z_HOMING_HEIGHT height
2016-03-26 22:36:36 -05:00
* No need to move Z any more as this height should already be safe
* enough to reach Z_SAFE_HOMING XY positions.
* Just make sure the planner is in sync.
*/
SYNC_PLAN_POSITION_KINEMATIC();
2016-03-26 22:36:36 -05:00
/**
2016-07-27 06:30:39 -05:00
* Move the Z probe (or just the nozzle) to the safe homing point
2016-03-26 22:36:36 -05:00
*/
2016-03-13 00:38:55 -06:00
destination[X_AXIS] = round(Z_SAFE_HOMING_X_POINT - (X_PROBE_OFFSET_FROM_EXTRUDER));
destination[Y_AXIS] = round(Z_SAFE_HOMING_Y_POINT - (Y_PROBE_OFFSET_FROM_EXTRUDER));
2016-07-27 06:30:39 -05:00
destination[Z_AXIS] = current_position[Z_AXIS]; // Z is already at the right height
2016-06-22 04:22:43 -05:00
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
DEBUG_POS("> Z_SAFE_HOMING > home_all_axis", current_position);
DEBUG_POS("> Z_SAFE_HOMING > home_all_axis", destination);
2015-08-05 06:40:36 -05:00
}
2015-07-09 18:57:44 -05:00
#endif
// Move in the XY plane
2016-07-15 08:02:15 -05:00
do_blocking_move_to_xy(destination[X_AXIS], destination[Y_AXIS]);
}
// Let's see if X and Y are homed
if (axis_unhomed_error(true, true, false)) return;
/**
* Make sure the Z probe is within the physical limits
* NOTE: This doesn't necessarily ensure the Z probe is also
* within the bed!
*/
float cpx = RAW_CURRENT_POSITION(X_AXIS), cpy = RAW_CURRENT_POSITION(Y_AXIS);
if ( cpx >= X_MIN_POS - (X_PROBE_OFFSET_FROM_EXTRUDER)
&& cpx <= X_MAX_POS - (X_PROBE_OFFSET_FROM_EXTRUDER)
&& cpy >= Y_MIN_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)
&& cpy <= Y_MAX_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)) {
2016-06-27 17:46:40 -05:00
// Home the Z axis
HOMEAXIS(Z);
}
else {
LCD_MESSAGEPGM(MSG_ZPROBE_OUT);
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_ZPROBE_OUT);
}
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2015-08-05 06:40:36 -05:00
SERIAL_ECHOLNPGM("<<< Z_SAFE_HOMING");
}
2015-07-09 18:57:44 -05:00
#endif
#else // !Z_SAFE_HOMING
HOMEAXIS(Z);
#endif // !Z_SAFE_HOMING
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("> (home_all_axis || homeZ) > final", current_position);
2015-07-09 18:57:44 -05:00
#endif
} // home_all_axis || homeZ
#endif // Z_HOME_DIR < 0
SYNC_PLAN_POSITION_KINEMATIC();
#endif // !DELTA (gcode_G28)
2016-06-22 16:20:34 -05:00
endstops.not_homing();
// Enable mesh leveling again
#if ENABLED(MESH_BED_LEVELING)
if (mbl.has_mesh()) {
2016-07-17 01:35:15 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("MBL has mesh");
#endif
if (home_all_axis || (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && homeZ)) {
2016-07-17 01:35:15 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("MBL Z homing");
#endif
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z
#if Z_HOME_DIR > 0
+ Z_MAX_POS
#endif
;
SYNC_PLAN_POSITION_KINEMATIC();
mbl.set_active(true);
#if ENABLED(MESH_G28_REST_ORIGIN)
current_position[Z_AXIS] = 0.0;
set_destination_to_current();
feedrate_mm_s = homing_feedrate_mm_s[Z_AXIS];
line_to_destination();
stepper.synchronize();
2016-07-17 01:35:15 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("MBL Rest Origin", current_position);
#endif
#else
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z -
mbl.get_z(RAW_CURRENT_POSITION(X_AXIS), RAW_CURRENT_POSITION(Y_AXIS))
#if Z_HOME_DIR > 0
+ Z_MAX_POS
#endif
;
2016-07-17 01:35:15 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("MBL adjusted MESH_HOME_SEARCH_Z", current_position);
#endif
#endif
}
else if ((axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) && (homeX || homeY)) {
current_position[Z_AXIS] = pre_home_z;
SYNC_PLAN_POSITION_KINEMATIC();
mbl.set_active(true);
current_position[Z_AXIS] = pre_home_z -
mbl.get_z(RAW_CURRENT_POSITION(X_AXIS), RAW_CURRENT_POSITION(Y_AXIS));
2016-07-17 01:35:15 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("MBL Home X or Y", current_position);
#endif
}
2015-03-15 17:18:11 -05:00
}
#endif
#if ENABLED(DELTA)
// move to a height where we can use the full xy-area
do_blocking_move_to_z(delta_clip_start_height);
#endif
2016-06-22 16:20:34 -05:00
clean_up_after_endstop_or_probe_move();
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-06-21 18:18:19 -05:00
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< gcode_G28");
2015-07-09 18:57:44 -05:00
#endif
2016-07-19 21:37:31 -05:00
// Restore the active tool after homing
#if HOTENDS > 1
tool_change(old_tool_index, 0, true);
#endif
report_current_position();
}
2016-06-22 16:03:22 -05:00
#if HAS_PROBING_PROCEDURE
void out_of_range_error(const char* p_edge) {
SERIAL_PROTOCOLPGM("?Probe ");
serialprintPGM(p_edge);
SERIAL_PROTOCOLLNPGM(" position out of range.");
}
#endif
#if ENABLED(MESH_BED_LEVELING)
2016-04-13 04:37:41 -05:00
inline void _mbl_goto_xy(float x, float y) {
float old_feedrate_mm_s = feedrate_mm_s;
feedrate_mm_s = homing_feedrate_mm_s[X_AXIS];
2016-04-13 04:37:41 -05:00
2016-04-16 16:17:06 -05:00
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z
2016-08-03 22:51:05 -05:00
#if Z_PROBE_TRAVEL_HEIGHT > Z_HOMING_HEIGHT
+ Z_PROBE_TRAVEL_HEIGHT
#elif Z_HOMING_HEIGHT > 0
+ Z_HOMING_HEIGHT
2016-04-16 16:17:06 -05:00
#endif
;
line_to_current_position();
2016-04-13 04:37:41 -05:00
2016-07-24 18:34:01 -05:00
current_position[X_AXIS] = LOGICAL_X_POSITION(x);
current_position[Y_AXIS] = LOGICAL_Y_POSITION(y);
2016-04-13 04:37:41 -05:00
line_to_current_position();
2016-08-03 22:51:05 -05:00
#if Z_PROBE_TRAVEL_HEIGHT > 0 || Z_HOMING_HEIGHT > 0
2016-07-24 18:34:01 -05:00
current_position[Z_AXIS] = LOGICAL_Z_POSITION(MESH_HOME_SEARCH_Z);
2016-04-13 04:37:41 -05:00
line_to_current_position();
#endif
feedrate_mm_s = old_feedrate_mm_s;
stepper.synchronize();
2016-04-13 04:37:41 -05:00
}
/**
* G29: Mesh-based Z probe, probes a grid and produces a
* mesh to compensate for variable bed height
*
* Parameters With MESH_BED_LEVELING:
*
* S0 Produce a mesh report
* S1 Start probing mesh points
* S2 Probe the next mesh point
* S3 Xn Yn Zn.nn Manually modify a single point
* S4 Zn.nn Set z offset. Positive away from bed, negative closer to bed.
* S5 Reset and disable mesh
*
* The S0 report the points as below
*
* +----> X-axis 1-n
* |
* |
* v Y-axis 1-n
2015-08-05 06:40:36 -05:00
*
*/
2015-03-21 08:50:47 -05:00
inline void gcode_G29() {
2015-03-21 08:50:47 -05:00
static int probe_point = -1;
MeshLevelingState state = code_seen('S') ? (MeshLevelingState)code_value_byte() : MeshReport;
if (state < 0 || state > 5) {
SERIAL_PROTOCOLLNPGM("S out of range (0-5).");
2015-04-03 17:31:35 -05:00
return;
2015-03-21 08:50:47 -05:00
}
2016-05-21 19:38:14 -05:00
int8_t px, py;
switch (state) {
2015-04-03 17:31:35 -05:00
case MeshReport:
if (mbl.has_mesh()) {
2016-08-20 20:11:08 -05:00
SERIAL_PROTOCOLPAIR("State: ", mbl.active() ? MSG_ON : MSG_OFF);
2016-08-10 20:49:25 -05:00
SERIAL_PROTOCOLLNPGM("\nNum X,Y: " STRINGIFY(MESH_NUM_X_POINTS) "," STRINGIFY(MESH_NUM_Y_POINTS));
SERIAL_PROTOCOLLNPGM("Z search height: " STRINGIFY(MESH_HOME_SEARCH_Z));
SERIAL_PROTOCOLPGM("Z offset: "); SERIAL_PROTOCOL_F(mbl.z_offset, 5);
2015-04-03 17:31:35 -05:00
SERIAL_PROTOCOLLNPGM("\nMeasured points:");
2016-05-21 19:38:14 -05:00
for (py = 0; py < MESH_NUM_Y_POINTS; py++) {
for (px = 0; px < MESH_NUM_X_POINTS; px++) {
2015-04-03 17:31:35 -05:00
SERIAL_PROTOCOLPGM(" ");
2016-05-21 19:38:14 -05:00
SERIAL_PROTOCOL_F(mbl.z_values[py][px], 5);
2015-04-03 17:31:35 -05:00
}
SERIAL_EOL;
2015-03-21 08:50:47 -05:00
}
}
2015-04-03 17:31:35 -05:00
else
SERIAL_PROTOCOLLNPGM("Mesh bed leveling not active.");
break;
2015-03-21 08:50:47 -05:00
2015-04-03 17:31:35 -05:00
case MeshStart:
mbl.reset();
probe_point = 0;
2016-02-20 19:35:35 -06:00
enqueue_and_echo_commands_P(PSTR("G28\nG29 S2"));
2015-04-03 17:31:35 -05:00
break;
2015-03-21 08:50:47 -05:00
2015-04-03 17:31:35 -05:00
case MeshNext:
if (probe_point < 0) {
SERIAL_PROTOCOLLNPGM("Start mesh probing with \"G29 S1\" first.");
return;
}
2016-04-13 04:37:41 -05:00
// For each G29 S2...
2015-04-03 17:31:35 -05:00
if (probe_point == 0) {
// For the initial G29 S2 make Z a positive value (e.g., 4.0)
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z
#if Z_HOME_DIR > 0
+ Z_MAX_POS
#endif
;
SYNC_PLAN_POSITION_KINEMATIC();
2015-04-03 17:31:35 -05:00
}
else {
2016-04-13 04:37:41 -05:00
// For G29 S2 after adjusting Z.
mbl.set_zigzag_z(probe_point - 1, current_position[Z_AXIS]);
2015-04-03 17:31:35 -05:00
}
2016-04-13 04:37:41 -05:00
// If there's another point to sample, move there with optional lift.
2016-03-13 00:38:55 -06:00
if (probe_point < (MESH_NUM_X_POINTS) * (MESH_NUM_Y_POINTS)) {
2016-05-21 19:38:14 -05:00
mbl.zigzag(probe_point, px, py);
_mbl_goto_xy(mbl.get_probe_x(px), mbl.get_probe_y(py));
2015-04-03 17:31:35 -05:00
probe_point++;
}
else {
2016-04-13 04:37:41 -05:00
// One last "return to the bed" (as originally coded) at completion
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z
2016-08-03 22:51:05 -05:00
#if Z_PROBE_TRAVEL_HEIGHT > Z_HOMING_HEIGHT
+ Z_PROBE_TRAVEL_HEIGHT
#elif Z_HOMING_HEIGHT > 0
+ Z_HOMING_HEIGHT
#endif
;
2016-04-13 04:37:41 -05:00
line_to_current_position();
stepper.synchronize();
2016-04-13 04:37:41 -05:00
2015-04-03 17:31:35 -05:00
// After recording the last point, activate the mbl and home
SERIAL_PROTOCOLLNPGM("Mesh probing done.");
probe_point = -1;
mbl.set_has_mesh(true);
2016-02-20 19:35:35 -06:00
enqueue_and_echo_commands_P(PSTR("G28"));
2015-04-03 17:31:35 -05:00
}
break;
case MeshSet:
2015-07-07 00:55:13 -05:00
if (code_seen('X')) {
px = code_value_int() - 1;
2016-05-21 19:38:14 -05:00
if (px < 0 || px >= MESH_NUM_X_POINTS) {
SERIAL_PROTOCOLLNPGM("X out of range (1-" STRINGIFY(MESH_NUM_X_POINTS) ").");
return;
}
2015-10-13 05:51:34 -05:00
}
else {
SERIAL_PROTOCOLLNPGM("X not entered.");
return;
}
2015-07-07 00:55:13 -05:00
if (code_seen('Y')) {
py = code_value_int() - 1;
2016-05-21 19:38:14 -05:00
if (py < 0 || py >= MESH_NUM_Y_POINTS) {
SERIAL_PROTOCOLLNPGM("Y out of range (1-" STRINGIFY(MESH_NUM_Y_POINTS) ").");
return;
}
2015-10-13 05:51:34 -05:00
}
else {
SERIAL_PROTOCOLLNPGM("Y not entered.");
return;
}
2015-07-07 00:55:13 -05:00
if (code_seen('Z')) {
mbl.z_values[py][px] = code_value_axis_units(Z_AXIS);
}
else {
SERIAL_PROTOCOLLNPGM("Z not entered.");
return;
}
break;
case MeshSetZOffset:
if (code_seen('Z')) {
mbl.z_offset = code_value_axis_units(Z_AXIS);
2016-03-26 22:36:36 -05:00
}
else {
SERIAL_PROTOCOLLNPGM("Z not entered.");
return;
}
break;
case MeshReset:
if (mbl.active()) {
current_position[Z_AXIS] +=
mbl.get_z(RAW_CURRENT_POSITION(X_AXIS), RAW_CURRENT_POSITION(Y_AXIS)) - MESH_HOME_SEARCH_Z;
mbl.reset();
SYNC_PLAN_POSITION_KINEMATIC();
}
else
mbl.reset();
2015-04-03 17:31:35 -05:00
} // switch(state)
report_current_position();
2015-03-21 08:50:47 -05:00
}
#elif ENABLED(AUTO_BED_LEVELING_FEATURE)
/**
* G29: Detailed Z probe, probes the bed at 3 or more points.
* Will fail if the printer has not been homed with G28.
*
* Enhanced G29 Auto Bed Leveling Probe Routine
2015-08-05 06:40:36 -05:00
*
* Parameters With AUTO_BED_LEVELING_GRID:
*
* P Set the size of the grid that will be probed (P x P points).
* Not supported by non-linear delta printer bed leveling.
* Example: "G29 P4"
*
* S Set the XY travel speed between probe points (in units/min)
*
* D Dry-Run mode. Just evaluate the bed Topology - Don't apply
* or clean the rotation Matrix. Useful to check the topology
* after a first run of G29.
*
* V Set the verbose level (0-4). Example: "G29 V3"
*
* T Generate a Bed Topology Report. Example: "G29 P5 T" for a detailed report.
* This is useful for manual bed leveling and finding flaws in the bed (to
* assist with part placement).
* Not supported by non-linear delta printer bed leveling.
*
* F Set the Front limit of the probing grid
* B Set the Back limit of the probing grid
* L Set the Left limit of the probing grid
* R Set the Right limit of the probing grid
*
* Global Parameters:
*
* E/e By default G29 will engage the Z probe, test the bed, then disengage.
* Include "E" to engage/disengage the Z probe for each sample.
* There's no extra effect if you have a fixed Z probe.
* Usage: "G29 E" or "G29 e"
*
*/
inline void gcode_G29() {
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2016-06-27 21:33:37 -05:00
SERIAL_ECHOLNPGM(">>> gcode_G29");
DEBUG_POS("", current_position);
SERIAL_ECHOPGM("Probe: ");
#if ENABLED(FIX_MOUNTED_PROBE)
SERIAL_ECHOLNPGM("FIX_MOUNTED_PROBE");
#elif HAS_Z_SERVO_ENDSTOP
SERIAL_ECHOLNPGM("SERVO PROBE");
#elif ENABLED(BLTOUCH)
SERIAL_ECHOLNPGM("BLTOUCH");
#elif ENABLED(Z_PROBE_SLED)
SERIAL_ECHOLNPGM("Z_PROBE_SLED");
#elif ENABLED(Z_PROBE_ALLEN_KEY)
SERIAL_ECHOLNPGM("Z_PROBE_ALLEN_KEY");
#endif
SERIAL_ECHOPAIR("Probe Offset X:", X_PROBE_OFFSET_FROM_EXTRUDER);
SERIAL_ECHOPAIR(" Y:", Y_PROBE_OFFSET_FROM_EXTRUDER);
SERIAL_ECHOPAIR(" Z:", zprobe_zoffset);
#if (X_PROBE_OFFSET_FROM_EXTRUDER > 0)
2016-08-28 18:44:44 -05:00
SERIAL_ECHOPGM(" (Right");
#elif (X_PROBE_OFFSET_FROM_EXTRUDER < 0)
2016-08-28 18:44:44 -05:00
SERIAL_ECHOPGM(" (Left");
#endif
#if (Y_PROBE_OFFSET_FROM_EXTRUDER > 0)
SERIAL_ECHOPGM("-Back");
#elif (Y_PROBE_OFFSET_FROM_EXTRUDER < 0)
SERIAL_ECHOPGM("-Front");
#endif
if (zprobe_zoffset < 0)
SERIAL_ECHOPGM(" & Below");
else if (zprobe_zoffset > 0)
SERIAL_ECHOPGM(" & Above");
else
SERIAL_ECHOPGM(" & Same Z as");
SERIAL_ECHOLNPGM(" Nozzle)");
2015-08-05 06:40:36 -05:00
}
2015-07-09 18:57:44 -05:00
#endif
2015-04-03 17:31:35 -05:00
// Don't allow auto-leveling without homing first
2016-06-27 17:46:40 -05:00
if (axis_unhomed_error(true, true, true)) return;
int verbose_level = code_seen('V') ? code_value_int() : 1;
2015-04-03 17:31:35 -05:00
if (verbose_level < 0 || verbose_level > 4) {
2016-08-19 04:30:09 -05:00
SERIAL_PROTOCOLLNPGM("?(V)erbose Level is implausible (0-4).");
2015-04-03 17:31:35 -05:00
return;
}
bool dryrun = code_seen('D');
bool stow_probe_after_each = code_seen('E');
#if ENABLED(AUTO_BED_LEVELING_GRID)
#if DISABLED(DELTA)
2015-07-07 00:55:13 -05:00
bool do_topography_map = verbose_level > 2 || code_seen('T');
#endif
if (verbose_level > 0) {
SERIAL_PROTOCOLLNPGM("G29 Auto Bed Leveling");
if (dryrun) SERIAL_PROTOCOLLNPGM("Running in DRY-RUN mode");
}
int auto_bed_leveling_grid_points = AUTO_BED_LEVELING_GRID_POINTS;
#if DISABLED(DELTA)
if (code_seen('P')) auto_bed_leveling_grid_points = code_value_int();
if (auto_bed_leveling_grid_points < 2) {
SERIAL_PROTOCOLLNPGM("?Number of probed (P)oints is implausible (2 minimum).");
return;
}
#endif
xy_probe_feedrate_mm_s = MMM_TO_MMS(code_seen('S') ? code_value_linear_units() : XY_PROBE_SPEED);
int left_probe_bed_position = code_seen('L') ? (int)code_value_axis_units(X_AXIS) : LOGICAL_X_POSITION(LEFT_PROBE_BED_POSITION),
right_probe_bed_position = code_seen('R') ? (int)code_value_axis_units(X_AXIS) : LOGICAL_X_POSITION(RIGHT_PROBE_BED_POSITION),
front_probe_bed_position = code_seen('F') ? (int)code_value_axis_units(Y_AXIS) : LOGICAL_Y_POSITION(FRONT_PROBE_BED_POSITION),
back_probe_bed_position = code_seen('B') ? (int)code_value_axis_units(Y_AXIS) : LOGICAL_Y_POSITION(BACK_PROBE_BED_POSITION);
bool left_out_l = left_probe_bed_position < LOGICAL_X_POSITION(MIN_PROBE_X),
2016-03-13 00:38:55 -06:00
left_out = left_out_l || left_probe_bed_position > right_probe_bed_position - (MIN_PROBE_EDGE),
right_out_r = right_probe_bed_position > LOGICAL_X_POSITION(MAX_PROBE_X),
right_out = right_out_r || right_probe_bed_position < left_probe_bed_position + MIN_PROBE_EDGE,
front_out_f = front_probe_bed_position < LOGICAL_Y_POSITION(MIN_PROBE_Y),
2016-03-13 00:38:55 -06:00
front_out = front_out_f || front_probe_bed_position > back_probe_bed_position - (MIN_PROBE_EDGE),
back_out_b = back_probe_bed_position > LOGICAL_Y_POSITION(MAX_PROBE_Y),
back_out = back_out_b || back_probe_bed_position < front_probe_bed_position + MIN_PROBE_EDGE;
if (left_out || right_out || front_out || back_out) {
if (left_out) {
out_of_range_error(PSTR("(L)eft"));
left_probe_bed_position = left_out_l ? LOGICAL_X_POSITION(MIN_PROBE_X) : right_probe_bed_position - (MIN_PROBE_EDGE);
}
if (right_out) {
out_of_range_error(PSTR("(R)ight"));
right_probe_bed_position = right_out_r ? LOGICAL_Y_POSITION(MAX_PROBE_X) : left_probe_bed_position + MIN_PROBE_EDGE;
}
if (front_out) {
out_of_range_error(PSTR("(F)ront"));
front_probe_bed_position = front_out_f ? LOGICAL_Y_POSITION(MIN_PROBE_Y) : back_probe_bed_position - (MIN_PROBE_EDGE);
}
if (back_out) {
out_of_range_error(PSTR("(B)ack"));
back_probe_bed_position = back_out_b ? LOGICAL_Y_POSITION(MAX_PROBE_Y) : front_probe_bed_position + MIN_PROBE_EDGE;
}
return;
}
#endif // AUTO_BED_LEVELING_GRID
if (!dryrun) {
#if ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(DELTA)
if (DEBUGGING(LEVELING)) {
2016-04-27 20:06:32 -05:00
vector_3 corrected_position = planner.adjusted_position();
DEBUG_POS("BEFORE matrix.set_to_identity", corrected_position);
DEBUG_POS("BEFORE matrix.set_to_identity", current_position);
}
#endif
// make sure the bed_level_rotation_matrix is identity or the planner will get it wrong
2016-04-27 20:06:32 -05:00
planner.bed_level_matrix.set_to_identity();
#if ENABLED(DELTA)
reset_bed_level();
#else //!DELTA
2016-04-27 20:06:32 -05:00
//vector_3 corrected_position = planner.adjusted_position();
//corrected_position.debug("position before G29");
2016-04-27 20:06:32 -05:00
vector_3 uncorrected_position = planner.adjusted_position();
//uncorrected_position.debug("position during G29");
current_position[X_AXIS] = uncorrected_position.x;
current_position[Y_AXIS] = uncorrected_position.y;
current_position[Z_AXIS] = uncorrected_position.z;
2016-04-08 19:37:06 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-04-11 02:06:33 -05:00
if (DEBUGGING(LEVELING)) DEBUG_POS("AFTER matrix.set_to_identity", uncorrected_position);
2016-04-08 19:37:06 -05:00
#endif
SYNC_PLAN_POSITION_KINEMATIC();
#endif // !DELTA
}
stepper.synchronize();
2016-06-21 17:32:28 -05:00
setup_for_endstop_or_probe_move();
// Deploy the probe. Probe will raise if needed.
if (DEPLOY_PROBE()) return;
bed_leveling_in_progress = true;
#if ENABLED(AUTO_BED_LEVELING_GRID)
// probe at the points of a lattice grid
2016-08-19 01:14:36 -05:00
const float xGridSpacing = (right_probe_bed_position - left_probe_bed_position) / (auto_bed_leveling_grid_points - 1),
yGridSpacing = (back_probe_bed_position - front_probe_bed_position) / (auto_bed_leveling_grid_points - 1);
#if ENABLED(DELTA)
delta_grid_spacing[X_AXIS] = xGridSpacing;
delta_grid_spacing[Y_AXIS] = yGridSpacing;
2016-04-13 04:33:53 -05:00
float zoffset = zprobe_zoffset;
if (code_seen('Z')) zoffset += code_value_axis_units(Z_AXIS);
#else // !DELTA
2016-03-26 22:36:36 -05:00
/**
* solve the plane equation ax + by + d = z
* A is the matrix with rows [x y 1] for all the probed points
* B is the vector of the Z positions
* the normal vector to the plane is formed by the coefficients of the
* plane equation in the standard form, which is Vx*x+Vy*y+Vz*z+d = 0
* so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z
*/
2016-07-15 20:50:25 -05:00
int abl2 = sq(auto_bed_leveling_grid_points);
double eqnAMatrix[abl2 * 3], // "A" matrix of the linear system of equations
eqnBVector[abl2], // "B" vector of Z points
mean = 0.0;
int8_t indexIntoAB[auto_bed_leveling_grid_points][auto_bed_leveling_grid_points];
#endif // !DELTA
int probePointCounter = 0;
bool zig = auto_bed_leveling_grid_points & 1; //always end at [RIGHT_PROBE_BED_POSITION, BACK_PROBE_BED_POSITION]
for (int yCount = 0; yCount < auto_bed_leveling_grid_points; yCount++) {
2016-08-19 01:14:36 -05:00
float yBase = front_probe_bed_position + yGridSpacing * yCount,
2016-08-20 04:28:08 -05:00
yProbe = floor(yBase + (yBase < 0 ? 0 : 0.5));
int xStart, xStop, xInc;
if (zig) {
xStart = 0;
xStop = auto_bed_leveling_grid_points;
xInc = 1;
}
else {
xStart = auto_bed_leveling_grid_points - 1;
xStop = -1;
xInc = -1;
}
zig = !zig;
for (int xCount = xStart; xCount != xStop; xCount += xInc) {
2016-08-19 01:14:36 -05:00
float xBase = left_probe_bed_position + xGridSpacing * xCount,
2016-08-20 04:28:08 -05:00
xProbe = floor(xBase + (xBase < 0 ? 0 : 0.5));
#if ENABLED(DELTA)
2016-08-19 01:12:41 -05:00
// Avoid probing outside the round or hexagonal area of a delta printer
if (sq(xProbe) + sq(yProbe) > sq(DELTA_PROBEABLE_RADIUS) + 0.1) continue;
2016-08-19 01:12:41 -05:00
#endif
float measured_z = probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level);
#if DISABLED(DELTA)
mean += measured_z;
eqnBVector[probePointCounter] = measured_z;
eqnAMatrix[probePointCounter + 0 * abl2] = xProbe;
eqnAMatrix[probePointCounter + 1 * abl2] = yProbe;
eqnAMatrix[probePointCounter + 2 * abl2] = 1;
indexIntoAB[xCount][yCount] = probePointCounter;
#else
2016-04-13 04:33:53 -05:00
bed_level[xCount][yCount] = measured_z + zoffset;
#endif
probePointCounter++;
2015-05-26 22:08:21 -05:00
idle();
} //xProbe
} //yProbe
2016-06-23 22:22:28 -05:00
#else // !AUTO_BED_LEVELING_GRID
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-06-23 20:17:31 -05:00
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> 3-point Leveling");
2015-07-09 18:57:44 -05:00
#endif
2016-06-23 22:22:28 -05:00
// Probe at 3 arbitrary points
2016-07-25 17:56:34 -05:00
float z_at_pt_1 = probe_pt( LOGICAL_X_POSITION(ABL_PROBE_PT_1_X),
LOGICAL_Y_POSITION(ABL_PROBE_PT_1_Y),
2016-06-23 22:22:28 -05:00
stow_probe_after_each, verbose_level),
2016-07-25 17:56:34 -05:00
z_at_pt_2 = probe_pt( LOGICAL_X_POSITION(ABL_PROBE_PT_2_X),
LOGICAL_Y_POSITION(ABL_PROBE_PT_2_Y),
2016-06-23 22:22:28 -05:00
stow_probe_after_each, verbose_level),
2016-07-25 17:56:34 -05:00
z_at_pt_3 = probe_pt( LOGICAL_X_POSITION(ABL_PROBE_PT_3_X),
LOGICAL_Y_POSITION(ABL_PROBE_PT_3_Y),
2016-06-23 22:22:28 -05:00
stow_probe_after_each, verbose_level);
if (!dryrun) set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3);
#endif // !AUTO_BED_LEVELING_GRID
2016-08-03 22:51:05 -05:00
// Raise to _Z_PROBE_DEPLOY_HEIGHT. Stow the probe.
if (STOW_PROBE()) return;
2016-06-23 22:22:28 -05:00
// Restore state after probing
clean_up_after_endstop_or_probe_move();
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("> probing complete", current_position);
#endif
// Calculate leveling, print reports, correct the position
#if ENABLED(AUTO_BED_LEVELING_GRID)
#if ENABLED(DELTA)
if (!dryrun) extrapolate_unprobed_bed_level();
print_bed_level();
#else // !DELTA
// solve lsq problem
double plane_equation_coefficients[3];
qr_solve(plane_equation_coefficients, abl2, 3, eqnAMatrix, eqnBVector);
mean /= abl2;
if (verbose_level) {
SERIAL_PROTOCOLPGM("Eqn coefficients: a: ");
SERIAL_PROTOCOL_F(plane_equation_coefficients[0], 8);
SERIAL_PROTOCOLPGM(" b: ");
SERIAL_PROTOCOL_F(plane_equation_coefficients[1], 8);
SERIAL_PROTOCOLPGM(" d: ");
SERIAL_PROTOCOL_F(plane_equation_coefficients[2], 8);
SERIAL_EOL;
if (verbose_level > 2) {
SERIAL_PROTOCOLPGM("Mean of sampled points: ");
SERIAL_PROTOCOL_F(mean, 8);
SERIAL_EOL;
}
}
if (!dryrun) set_bed_level_equation_lsq(plane_equation_coefficients);
// Show the Topography map if enabled
if (do_topography_map) {
SERIAL_PROTOCOLLNPGM("\nBed Height Topography:\n"
" +--- BACK --+\n"
" | |\n"
" L | (+) | R\n"
" E | | I\n"
" F | (-) N (+) | G\n"
" T | | H\n"
" | (-) | T\n"
" | |\n"
" O-- FRONT --+\n"
" (0,0)");
float min_diff = 999;
for (int yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
for (int xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
int ind = indexIntoAB[xx][yy];
float diff = eqnBVector[ind] - mean;
float x_tmp = eqnAMatrix[ind + 0 * abl2],
y_tmp = eqnAMatrix[ind + 1 * abl2],
z_tmp = 0;
2016-04-27 20:06:32 -05:00
apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp);
NOMORE(min_diff, eqnBVector[ind] - z_tmp);
if (diff >= 0.0)
SERIAL_PROTOCOLPGM(" +"); // Include + for column alignment
else
2015-04-03 23:43:30 -05:00
SERIAL_PROTOCOLCHAR(' ');
SERIAL_PROTOCOL_F(diff, 5);
} // xx
SERIAL_EOL;
} // yy
SERIAL_EOL;
if (verbose_level > 3) {
SERIAL_PROTOCOLLNPGM("\nCorrected Bed Height vs. Bed Topology:");
for (int yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
for (int xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
int ind = indexIntoAB[xx][yy];
float x_tmp = eqnAMatrix[ind + 0 * abl2],
y_tmp = eqnAMatrix[ind + 1 * abl2],
z_tmp = 0;
2016-04-27 20:06:32 -05:00
apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp);
float diff = eqnBVector[ind] - z_tmp - min_diff;
if (diff >= 0.0)
SERIAL_PROTOCOLPGM(" +");
// Include + for column alignment
else
SERIAL_PROTOCOLCHAR(' ');
SERIAL_PROTOCOL_F(diff, 5);
} // xx
SERIAL_EOL;
} // yy
SERIAL_EOL;
}
} //do_topography_map
#endif //!DELTA
2016-06-23 22:22:28 -05:00
#endif // AUTO_BED_LEVELING_GRID
2016-06-20 17:50:51 -05:00
#if DISABLED(DELTA)
if (verbose_level > 0)
planner.bed_level_matrix.debug("\n\nBed Level Correction Matrix:");
if (!dryrun) {
2016-03-26 22:36:36 -05:00
/**
* Correct the Z height difference from Z probe position and nozzle tip position.
* The Z height on homing is measured by Z probe, but the Z probe is quite far
* from the nozzle. When the bed is uneven, this height must be corrected.
*/
float x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER,
y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER,
z_tmp = current_position[Z_AXIS],
2016-06-23 22:22:28 -05:00
stepper_z = stepper.get_axis_position_mm(Z_AXIS); //get the real Z (since planner.adjusted_position is now correcting the plane)
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2016-06-23 22:22:28 -05:00
SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > stepper_z = ", stepper_z);
SERIAL_ECHOLNPAIR(" ... z_tmp = ", z_tmp);
2015-08-05 06:40:36 -05:00
}
2015-07-09 18:57:44 -05:00
#endif
2016-03-26 22:36:36 -05:00
// Apply the correction sending the Z probe offset
2016-04-27 20:06:32 -05:00
apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp);
2016-03-26 22:36:36 -05:00
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING))
SERIAL_ECHOLNPAIR("> AFTER apply_rotation_xyz > z_tmp = ", z_tmp);
2015-07-09 18:57:44 -05:00
#endif
2016-06-23 22:22:28 -05:00
// Adjust the current Z and send it to the planner.
current_position[Z_AXIS] += z_tmp - stepper_z;
SYNC_PLAN_POSITION_KINEMATIC();
2015-07-09 18:57:44 -05:00
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("> corrected Z in G29", current_position);
2015-07-09 18:57:44 -05:00
#endif
}
2015-08-11 18:10:59 -05:00
#endif // !DELTA
#ifdef Z_PROBE_END_SCRIPT
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOPGM("Z Probe End Script: ");
2015-08-05 06:40:36 -05:00
SERIAL_ECHOLNPGM(Z_PROBE_END_SCRIPT);
}
2015-07-09 18:57:44 -05:00
#endif
2016-02-20 19:35:35 -06:00
enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT));
stepper.synchronize();
#endif
2015-07-09 18:57:44 -05:00
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-06-23 22:22:28 -05:00
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< gcode_G29");
2015-07-09 18:57:44 -05:00
#endif
bed_leveling_in_progress = false;
report_current_position();
KEEPALIVE_STATE(IN_HANDLER);
}
2016-06-20 17:50:51 -05:00
#endif //AUTO_BED_LEVELING_FEATURE
2016-06-20 17:50:51 -05:00
#if HAS_BED_PROBE
2016-06-20 17:50:51 -05:00
/**
* G30: Do a single Z probe at the current XY
*/
inline void gcode_G30() {
2016-06-20 18:18:30 -05:00
2016-06-21 17:32:28 -05:00
setup_for_endstop_or_probe_move();
2016-06-20 18:18:30 -05:00
2016-06-20 18:40:28 -05:00
// TODO: clear the leveling matrix or the planner will be set incorrectly
2016-06-23 22:25:46 -05:00
float measured_z = probe_pt(current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER,
current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER,
true, 1);
2016-06-20 17:50:51 -05:00
SERIAL_PROTOCOLPGM("Bed X: ");
SERIAL_PROTOCOL(current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER + 0.0001);
SERIAL_PROTOCOLPGM(" Y: ");
SERIAL_PROTOCOL(current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER + 0.0001);
SERIAL_PROTOCOLPGM(" Z: ");
2016-06-22 18:52:32 -05:00
SERIAL_PROTOCOL(measured_z + 0.0001);
2016-06-20 17:50:51 -05:00
SERIAL_EOL;
2016-06-21 17:32:28 -05:00
clean_up_after_endstop_or_probe_move();
2016-06-20 18:18:30 -05:00
2016-06-20 17:50:51 -05:00
report_current_position();
}
2016-06-23 19:04:13 -05:00
#if ENABLED(Z_PROBE_SLED)
/**
* G31: Deploy the Z probe
*/
inline void gcode_G31() { DEPLOY_PROBE(); }
2016-06-23 19:04:13 -05:00
/**
* G32: Stow the Z probe
*/
inline void gcode_G32() { STOW_PROBE(); }
2016-06-23 19:04:13 -05:00
#endif // Z_PROBE_SLED
2016-06-20 17:50:51 -05:00
#endif // HAS_BED_PROBE
/**
* G92: Set current position to given X Y Z E
*/
inline void gcode_G92() {
bool didE = code_seen('E');
if (!didE) stepper.synchronize();
bool didXYZ = false;
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) {
if (code_seen(axis_codes[i])) {
float p = current_position[i],
v = code_value_axis_units(i);
current_position[i] = v;
if (i != E_AXIS) {
position_shift[i] += v - p; // Offset the coordinate space
update_software_endstops((AxisEnum)i);
didXYZ = true;
}
}
}
if (didXYZ)
SYNC_PLAN_POSITION_KINEMATIC();
else if (didE)
sync_plan_position_e();
}
#if ENABLED(ULTIPANEL)
/**
* M0: Unconditional stop - Wait for user button press on LCD
* M1: Conditional stop - Wait for user button press on LCD
*/
inline void gcode_M0_M1() {
char* args = current_command_args;
2015-04-12 20:07:08 -05:00
millis_t codenum = 0;
bool hasP = false, hasS = false;
if (code_seen('P')) {
codenum = code_value_millis(); // milliseconds to wait
hasP = codenum > 0;
}
if (code_seen('S')) {
codenum = code_value_millis_from_seconds(); // seconds to wait
hasS = codenum > 0;
}
if (!hasP && !hasS && *args != '\0')
lcd_setstatus(args, true);
else {
LCD_MESSAGEPGM(MSG_USERWAIT);
#if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0
dontExpireStatus();
#endif
}
lcd_ignore_click();
stepper.synchronize();
2015-04-03 17:31:35 -05:00
refresh_cmd_timeout();
if (codenum > 0) {
2015-05-26 22:08:21 -05:00
codenum += previous_cmd_ms; // wait until this time for a click
KEEPALIVE_STATE(PAUSED_FOR_USER);
2016-04-10 17:55:12 -05:00
while (PENDING(millis(), codenum) && !lcd_clicked()) idle();
KEEPALIVE_STATE(IN_HANDLER);
lcd_ignore_click(false);
}
else {
if (!lcd_detected()) return;
KEEPALIVE_STATE(PAUSED_FOR_USER);
2015-05-26 22:08:21 -05:00
while (!lcd_clicked()) idle();
KEEPALIVE_STATE(IN_HANDLER);
}
if (IS_SD_PRINTING)
LCD_MESSAGEPGM(MSG_RESUMING);
else
LCD_MESSAGEPGM(WELCOME_MSG);
}
#endif // ULTIPANEL
/**
* M17: Enable power on all stepper motors
*/
inline void gcode_M17() {
LCD_MESSAGEPGM(MSG_NO_MOVE);
enable_all_steppers();
}
#if ENABLED(SDSUPPORT)
/**
* M20: List SD card to serial output
*/
inline void gcode_M20() {
SERIAL_PROTOCOLLNPGM(MSG_BEGIN_FILE_LIST);
card.ls();
SERIAL_PROTOCOLLNPGM(MSG_END_FILE_LIST);
}
/**
* M21: Init SD Card
*/
inline void gcode_M21() {
card.initsd();
}
/**
* M22: Release SD Card
*/
inline void gcode_M22() {
card.release();
}
/**
2016-02-20 19:35:35 -06:00
* M23: Open a file
*/
inline void gcode_M23() {
card.openFile(current_command_args, true);
}
/**
* M24: Start SD Print
*/
inline void gcode_M24() {
card.startFileprint();
print_job_timer.start();
}
/**
* M25: Pause SD Print
*/
inline void gcode_M25() {
card.pauseSDPrint();
}
/**
* M26: Set SD Card file index
*/
inline void gcode_M26() {
if (card.cardOK && code_seen('S'))
card.setIndex(code_value_long());
}
/**
* M27: Get SD Card status
*/
inline void gcode_M27() {
card.getStatus();
}
/**
* M28: Start SD Write
*/
inline void gcode_M28() {
card.openFile(current_command_args, false);
}
/**
* M29: Stop SD Write
* Processed in write to file routine above
*/
inline void gcode_M29() {
// card.saving = false;
}
/**
* M30 <filename>: Delete SD Card file
*/
inline void gcode_M30() {
if (card.cardOK) {
card.closefile();
card.removeFile(current_command_args);
}
}
#endif //SDSUPPORT
/**
* M31: Get the time since the start of SD Print (or last M109)
*/
inline void gcode_M31() {
char buffer[21];
2016-07-23 21:13:35 -05:00
duration_t elapsed = print_job_timer.duration();
elapsed.toString(buffer);
2016-07-13 14:57:59 -05:00
lcd_setstatus(buffer);
2016-07-13 14:57:59 -05:00
SERIAL_ECHO_START;
2016-07-24 09:52:03 -05:00
SERIAL_ECHOPGM("Print time: ");
SERIAL_ECHOLN(buffer);
2016-07-13 14:57:59 -05:00
2016-04-28 20:18:13 -05:00
thermalManager.autotempShutdown();
}
#if ENABLED(SDSUPPORT)
/**
* M32: Select file and start SD Print
*/
inline void gcode_M32() {
if (card.sdprinting)
stepper.synchronize();
char* namestartpos = strchr(current_command_args, '!'); // Find ! to indicate filename string start.
if (!namestartpos)
namestartpos = current_command_args; // Default name position, 4 letters after the M
else
namestartpos++; //to skip the '!'
2015-05-17 07:00:09 -05:00
bool call_procedure = code_seen('P') && (seen_pointer < namestartpos);
if (card.cardOK) {
card.openFile(namestartpos, true, call_procedure);
2015-05-17 07:00:09 -05:00
if (code_seen('S') && seen_pointer < namestartpos) // "S" (must occur _before_ the filename!)
card.setIndex(code_value_long());
card.startFileprint();
// Procedure calls count as normal print time.
if (!call_procedure) print_job_timer.start();
}
}
#if ENABLED(LONG_FILENAME_HOST_SUPPORT)
2015-05-17 19:36:32 -05:00
/**
* M33: Get the long full path of a file or folder
*
* Parameters:
* <dospath> Case-insensitive DOS-style path to a file or folder
*
* Example:
* M33 miscel~1/armchair/armcha~1.gco
*
* Output:
* /Miscellaneous/Armchair/Armchair.gcode
*/
inline void gcode_M33() {
2015-05-28 16:17:39 -05:00
card.printLongPath(current_command_args);
2015-05-17 19:36:32 -05:00
}
#endif
/**
* M928: Start SD Write
*/
inline void gcode_M928() {
card.openLogFile(current_command_args);
}
#endif // SDSUPPORT
/**
* M42: Change pin status via GCode
*
* P<pin> Pin number (LED if omitted)
* S<byte> Pin status from 0 - 255
*/
inline void gcode_M42() {
if (!code_seen('S')) return;
int pin_status = code_value_int();
if (pin_status < 0 || pin_status > 255) return;
int pin_number = code_seen('P') ? code_value_int() : LED_PIN;
if (pin_number < 0) return;
2016-03-05 20:27:45 -06:00
for (uint8_t i = 0; i < COUNT(sensitive_pins); i++)
if (pin_number == sensitive_pins[i]) return;
2016-03-05 20:27:45 -06:00
pinMode(pin_number, OUTPUT);
digitalWrite(pin_number, pin_status);
analogWrite(pin_number, pin_status);
#if FAN_COUNT > 0
switch (pin_number) {
#if HAS_FAN0
case FAN_PIN: fanSpeeds[0] = pin_status; break;
#endif
#if HAS_FAN1
case FAN1_PIN: fanSpeeds[1] = pin_status; break;
#endif
#if HAS_FAN2
case FAN2_PIN: fanSpeeds[2] = pin_status; break;
#endif
}
#endif
}
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
/**
* M48: Z probe repeatability measurement function.
*
* Usage:
* M48 <P#> <X#> <Y#> <V#> <E> <L#>
* P = Number of sampled points (4-50, default 10)
* X = Sample X position
* Y = Sample Y position
* V = Verbose level (0-4, default=1)
* E = Engage Z probe for each reading
* L = Number of legs of movement before probe
* S = Schizoid (Or Star if you prefer)
2015-08-05 06:40:36 -05:00
*
* This function assumes the bed has been homed. Specifically, that a G28 command
* as been issued prior to invoking the M48 Z probe repeatability measurement function.
* Any information generated by a prior G29 Bed leveling command will be lost and need to be
* regenerated.
*/
inline void gcode_M48() {
2016-06-27 17:46:40 -05:00
if (axis_unhomed_error(true, true, true)) return;
2016-03-02 21:55:01 -06:00
2016-06-18 03:41:57 -05:00
int8_t verbose_level = code_seen('V') ? code_value_byte() : 1;
if (verbose_level < 0 || verbose_level > 4) {
SERIAL_PROTOCOLLNPGM("?Verbose Level not plausible (0-4).");
2016-06-18 03:41:57 -05:00
return;
}
2015-03-06 16:54:30 -06:00
if (verbose_level > 0)
SERIAL_PROTOCOLLNPGM("M48 Z-Probe Repeatability test");
2016-06-18 03:41:57 -05:00
int8_t n_samples = code_seen('P') ? code_value_byte() : 10;
if (n_samples < 4 || n_samples > 50) {
SERIAL_PROTOCOLLNPGM("?Sample size not plausible (4-50).");
2016-06-18 03:41:57 -05:00
return;
}
float X_current = current_position[X_AXIS],
2016-06-22 18:53:04 -05:00
Y_current = current_position[Y_AXIS];
bool stow_probe_after_each = code_seen('E');
2016-06-18 03:41:57 -05:00
float X_probe_location = code_seen('X') ? code_value_axis_units(X_AXIS) : X_current + X_PROBE_OFFSET_FROM_EXTRUDER;
#if DISABLED(DELTA)
if (X_probe_location < LOGICAL_X_POSITION(MIN_PROBE_X) || X_probe_location > LOGICAL_X_POSITION(MAX_PROBE_X)) {
2016-06-18 03:41:57 -05:00
out_of_range_error(PSTR("X"));
return;
}
#endif
2016-06-18 03:41:57 -05:00
float Y_probe_location = code_seen('Y') ? code_value_axis_units(Y_AXIS) : Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER;
#if DISABLED(DELTA)
if (Y_probe_location < LOGICAL_Y_POSITION(MIN_PROBE_Y) || Y_probe_location > LOGICAL_Y_POSITION(MAX_PROBE_Y)) {
2016-06-18 03:41:57 -05:00
out_of_range_error(PSTR("Y"));
return;
}
#else
if (HYPOT(RAW_X_POSITION(X_probe_location), RAW_Y_POSITION(Y_probe_location)) > DELTA_PROBEABLE_RADIUS) {
SERIAL_PROTOCOLLNPGM("? (X,Y) location outside of probeable radius.");
return;
}
#endif
bool seen_L = code_seen('L');
2016-06-18 03:41:57 -05:00
uint8_t n_legs = seen_L ? code_value_byte() : 0;
if (n_legs > 15) {
SERIAL_PROTOCOLLNPGM("?Number of legs in movement not plausible (0-15).");
2016-06-18 03:41:57 -05:00
return;
}
2016-06-18 03:41:57 -05:00
if (n_legs == 1) n_legs = 2;
2016-06-18 03:41:57 -05:00
bool schizoid_flag = code_seen('S');
if (schizoid_flag && !seen_L) n_legs = 7;
2016-03-26 22:36:36 -05:00
/**
* Now get everything to the specified probe point So we can safely do a
* probe to get us close to the bed. If the Z-Axis is far from the bed,
* we don't want to use that as a starting point for each probe.
*/
if (verbose_level > 2)
SERIAL_PROTOCOLLNPGM("Positioning the probe...");
#if ENABLED(DELTA)
2016-03-26 22:36:36 -05:00
// we don't do bed level correction in M48 because we want the raw data when we probe
reset_bed_level();
#elif ENABLED(AUTO_BED_LEVELING_FEATURE)
2016-03-26 22:36:36 -05:00
// we don't do bed level correction in M48 because we want the raw data when we probe
2016-04-27 20:06:32 -05:00
planner.bed_level_matrix.set_to_identity();
#endif
setup_for_endstop_or_probe_move();
2016-06-23 21:22:45 -05:00
// Move to the first point, deploy, and probe
probe_pt(X_probe_location, Y_probe_location, stow_probe_after_each, verbose_level);
2016-06-18 03:41:57 -05:00
randomSeed(millis());
double mean = 0, sigma = 0, sample_set[n_samples];
for (uint8_t n = 0; n < n_samples; n++) {
if (n_legs) {
int dir = (random(0, 10) > 5.0) ? -1 : 1; // clockwise or counter clockwise
2016-06-18 03:41:57 -05:00
float angle = random(0.0, 360.0),
radius = random(
#if ENABLED(DELTA)
DELTA_PROBEABLE_RADIUS / 8, DELTA_PROBEABLE_RADIUS / 3
#else
5, X_MAX_LENGTH / 8
#endif
);
if (verbose_level > 3) {
SERIAL_ECHOPAIR("Starting radius: ", radius);
SERIAL_ECHOPAIR(" angle: ", angle);
SERIAL_ECHOPGM(" Direction: ");
if (dir > 0) SERIAL_ECHOPGM("Counter-");
SERIAL_ECHOLNPGM("Clockwise");
}
for (uint8_t l = 0; l < n_legs - 1; l++) {
double delta_angle;
2016-03-26 22:36:36 -05:00
if (schizoid_flag)
2016-03-26 22:36:36 -05:00
// The points of a 5 point star are 72 degrees apart. We need to
// skip a point and go to the next one on the star.
delta_angle = dir * 2.0 * 72.0;
else
2016-03-26 22:36:36 -05:00
// If we do this line, we are just trying to move further
// around the circle.
delta_angle = dir * (float) random(25, 45);
angle += delta_angle;
2016-03-26 22:36:36 -05:00
while (angle > 360.0) // We probably do not need to keep the angle between 0 and 2*PI, but the
angle -= 360.0; // Arduino documentation says the trig functions should not be given values
while (angle < 0.0) // outside of this range. It looks like they behave correctly with
angle += 360.0; // numbers outside of the range, but just to be safe we clamp them.
2016-03-26 22:36:36 -05:00
X_current = X_probe_location - (X_PROBE_OFFSET_FROM_EXTRUDER) + cos(RADIANS(angle)) * radius;
Y_current = Y_probe_location - (Y_PROBE_OFFSET_FROM_EXTRUDER) + sin(RADIANS(angle)) * radius;
2016-03-26 22:36:36 -05:00
#if DISABLED(DELTA)
X_current = constrain(X_current, X_MIN_POS, X_MAX_POS);
Y_current = constrain(Y_current, Y_MIN_POS, Y_MAX_POS);
#else
// If we have gone out too far, we can do a simple fix and scale the numbers
// back in closer to the origin.
2016-07-15 20:50:25 -05:00
while (HYPOT(X_current, Y_current) > DELTA_PROBEABLE_RADIUS) {
X_current /= 1.25;
Y_current /= 1.25;
if (verbose_level > 3) {
SERIAL_ECHOPAIR("Pulling point towards center:", X_current);
SERIAL_ECHOLNPAIR(", ", Y_current);
}
}
#endif
if (verbose_level > 3) {
SERIAL_PROTOCOLPGM("Going to:");
SERIAL_ECHOPAIR(" X", X_current);
SERIAL_ECHOPAIR(" Y", Y_current);
SERIAL_ECHOLNPAIR(" Z", current_position[Z_AXIS]);
}
do_blocking_move_to_xy(X_current, Y_current);
} // n_legs loop
} // n_legs
2016-06-18 05:16:13 -05:00
// Probe a single point
2016-06-23 21:22:45 -05:00
sample_set[n] = probe_pt(X_probe_location, Y_probe_location, stow_probe_after_each, verbose_level);
2016-03-26 22:36:36 -05:00
/**
* Get the current mean for the data points we have so far
*/
2016-06-18 03:41:57 -05:00
double sum = 0.0;
for (uint8_t j = 0; j <= n; j++) sum += sample_set[j];
mean = sum / (n + 1);
2016-03-26 22:36:36 -05:00
/**
* Now, use that mean to calculate the standard deviation for the
* data points we have so far
*/
sum = 0.0;
2016-07-15 20:50:25 -05:00
for (uint8_t j = 0; j <= n; j++)
sum += sq(sample_set[j] - mean);
sigma = sqrt(sum / (n + 1));
2016-06-18 17:38:15 -05:00
if (verbose_level > 0) {
if (verbose_level > 1) {
SERIAL_PROTOCOL(n + 1);
SERIAL_PROTOCOLPGM(" of ");
SERIAL_PROTOCOL((int)n_samples);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL_F(current_position[Z_AXIS], 6);
if (verbose_level > 2) {
SERIAL_PROTOCOLPGM(" mean: ");
SERIAL_PROTOCOL_F(mean, 6);
SERIAL_PROTOCOLPGM(" sigma: ");
SERIAL_PROTOCOL_F(sigma, 6);
}
}
2016-06-18 17:38:15 -05:00
SERIAL_EOL;
Fixed error found by the free coverity tool (https://scan.coverity.com/) =================================================== Hi, Please find the latest report on new defect(s) introduced to ErikZalm/Marlin found with Coverity Scan. Defect(s) Reported-by: Coverity Scan Showing 15 of 15 defect(s) ** CID 59629: Unchecked return value (CHECKED_RETURN) /Marlin_main.cpp: 2154 in process_commands()() ** CID 59630: Operands don't affect result (CONSTANT_EXPRESSION_RESULT) /Applications/Arduino.app/Contents/Resources/Java/hardware/arduino/cores/arduino/Tone.cpp: 319 in tone(unsigned char, unsigned int, unsigned long)() ** CID 59631: Missing break in switch (MISSING_BREAK) /Marlin_main.cpp: 1187 in process_commands()() ** CID 59632: Missing break in switch (MISSING_BREAK) /Marlin_main.cpp: 1193 in process_commands()() ** CID 59633: Out-of-bounds write (OVERRUN) /temperature.cpp: 914 in disable_heater()() ** CID 59634: Out-of-bounds write (OVERRUN) /temperature.cpp: 913 in disable_heater()() ** CID 59635: Out-of-bounds read (OVERRUN) /temperature.cpp: 626 in analog2temp(int, unsigned char)() ** CID 59636: Out-of-bounds read (OVERRUN) /temperature.cpp: 620 in analog2temp(int, unsigned char)() ** CID 59637: Out-of-bounds write (OVERRUN) /temperature.cpp: 202 in PID_autotune(float, int, int)() ** CID 59638: Out-of-bounds read (OVERRUN) /temperature.cpp: 214 in PID_autotune(float, int, int)() ** CID 59639: Out-of-bounds write (OVERRUN) /Marlin_main.cpp: 2278 in process_commands()() ** CID 59640: Out-of-bounds read (OVERRUN) /Marlin_main.cpp: 1802 in process_commands()() ** CID 59641: Uninitialized scalar field (UNINIT_CTOR) /Applications/Arduino.app/Contents/Resources/Java/libraries/LiquidCrystal/LiquidCrystal.cpp: 51 in LiquidCrystal::LiquidCrystal(unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char)() ** CID 59642: Uninitialized scalar field (UNINIT_CTOR) /Applications/Arduino.app/Contents/Resources/Java/libraries/LiquidCrystal/LiquidCrystal.cpp: 45 in LiquidCrystal::LiquidCrystal(unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char)() ** CID 59643: Uninitialized scalar field (UNINIT_CTOR) /Applications/Arduino.app/Contents/Resources/Java/libraries/LiquidCrystal/LiquidCrystal.cpp: 32 in LiquidCrystal::LiquidCrystal(unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char)() ________________________________________________________________________________________________________ *** CID 59629: Unchecked return value (CHECKED_RETURN) /Marlin_main.cpp: 2154 in process_commands()() 2148 } 2149 #endif 2150 } 2151 } 2152 break; 2153 case 85: // M85 CID 59629: Unchecked return value (CHECKED_RETURN) Calling "code_seen" without checking return value (as is done elsewhere 66 out of 67 times). 2154 code_seen('S'); 2155 max_inactive_time = code_value() * 1000; 2156 break; 2157 case 92: // M92 2158 for(int8_t i=0; i < NUM_AXIS; i++) 2159 { ________________________________________________________________________________________________________ *** CID 59630: Operands don't affect result (CONSTANT_EXPRESSION_RESULT) /Applications/Arduino.app/Contents/Resources/Java/hardware/arduino/cores/arduino/Tone.cpp: 319 in tone(unsigned char, unsigned int, unsigned long)() 313 else 314 { 315 // two choices for the 16 bit timers: ck/1 or ck/64 316 ocr = F_CPU / frequency / 2 - 1; 317 318 prescalarbits = 0b001; CID 59630: Operands don't affect result (CONSTANT_EXPRESSION_RESULT) "ocr > 65535U" is always false regardless of the values of its operands. This occurs as the logical operand of if. 319 if (ocr > 0xffff) 320 { 321 ocr = F_CPU / frequency / 2 / 64 - 1; 322 prescalarbits = 0b011; 323 } 324 ________________________________________________________________________________________________________ *** CID 59631: Missing break in switch (MISSING_BREAK) /Marlin_main.cpp: 1187 in process_commands()() 1181 case 2: // G2 - CW ARC 1182 if(Stopped == false) { 1183 get_arc_coordinates(); 1184 prepare_arc_move(true); 1185 return; 1186 } CID 59631: Missing break in switch (MISSING_BREAK) The above case falls through to this one. 1187 case 3: // G3 - CCW ARC 1188 if(Stopped == false) { 1189 get_arc_coordinates(); 1190 prepare_arc_move(false); 1191 return; 1192 } ________________________________________________________________________________________________________ *** CID 59632: Missing break in switch (MISSING_BREAK) /Marlin_main.cpp: 1193 in process_commands()() 1187 case 3: // G3 - CCW ARC 1188 if(Stopped == false) { 1189 get_arc_coordinates(); 1190 prepare_arc_move(false); 1191 return; 1192 } CID 59632: Missing break in switch (MISSING_BREAK) The above case falls through to this one. 1193 case 4: // G4 dwell 1194 LCD_MESSAGEPGM(MSG_DWELL); 1195 codenum = 0; 1196 if(code_seen('P')) codenum = code_value(); // milliseconds to wait 1197 if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait 1198 ________________________________________________________________________________________________________ *** CID 59633: Out-of-bounds write (OVERRUN) /temperature.cpp: 914 in disable_heater()() 908 WRITE(HEATER_0_PIN,LOW); 909 #endif 910 #endif 911 912 #if defined(TEMP_1_PIN) && TEMP_1_PIN > -1 913 target_temperature[1]=0; CID 59633: Out-of-bounds write (OVERRUN) Overrunning array "soft_pwm" of 1 bytes at byte offset 1 using index "1". 914 soft_pwm[1]=0; 915 #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1 916 WRITE(HEATER_1_PIN,LOW); 917 #endif 918 #endif 919 ________________________________________________________________________________________________________ *** CID 59634: Out-of-bounds write (OVERRUN) /temperature.cpp: 913 in disable_heater()() 907 #if defined(HEATER_0_PIN) && HEATER_0_PIN > -1 908 WRITE(HEATER_0_PIN,LOW); 909 #endif 910 #endif 911 912 #if defined(TEMP_1_PIN) && TEMP_1_PIN > -1 CID 59634: Out-of-bounds write (OVERRUN) Overrunning array "target_temperature" of 1 2-byte elements at element index 1 (byte offset 2) using index "1". 913 target_temperature[1]=0; 914 soft_pwm[1]=0; 915 #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1 916 WRITE(HEATER_1_PIN,LOW); 917 #endif 918 #endif ________________________________________________________________________________________________________ *** CID 59635: Out-of-bounds read (OVERRUN) /temperature.cpp: 626 in analog2temp(int, unsigned char)() 620 if(heater_ttbl_map[e] != NULL) 621 { 622 float celsius = 0; 623 uint8_t i; 624 short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]); 625 CID 59635: Out-of-bounds read (OVERRUN) Overrunning array "heater_ttbllen_map" of 1 bytes at byte offset 1 using index "e" (which evaluates to 1). 626 for (i=1; i<heater_ttbllen_map[e]; i++) 627 { 628 if (PGM_RD_W((*tt)[i][0]) > raw) 629 { 630 celsius = PGM_RD_W((*tt)[i-1][1]) + 631 (raw - PGM_RD_W((*tt)[i-1][0])) * ________________________________________________________________________________________________________ *** CID 59636: Out-of-bounds read (OVERRUN) /temperature.cpp: 620 in analog2temp(int, unsigned char)() 614 if (e == 0) 615 { 616 return 0.25 * raw; 617 } 618 #endif 619 CID 59636: Out-of-bounds read (OVERRUN) Overrunning array "heater_ttbl_map" of 1 2-byte elements at element index 1 (byte offset 2) using index "e" (which evaluates to 1). 620 if(heater_ttbl_map[e] != NULL) 621 { 622 float celsius = 0; 623 uint8_t i; 624 short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]); 625 ________________________________________________________________________________________________________ *** CID 59637: Out-of-bounds write (OVERRUN) /temperature.cpp: 202 in PID_autotune(float, int, int)() 196 { 197 soft_pwm_bed = (MAX_BED_POWER)/2; 198 bias = d = (MAX_BED_POWER)/2; 199 } 200 else 201 { CID 59637: Out-of-bounds write (OVERRUN) Overrunning array "soft_pwm" of 1 bytes at byte offset 1 using index "extruder" (which evaluates to 1). 202 soft_pwm[extruder] = (PID_MAX)/2; 203 bias = d = (PID_MAX)/2; 204 } 205 206 207 ________________________________________________________________________________________________________ *** CID 59638: Out-of-bounds read (OVERRUN) /temperature.cpp: 214 in PID_autotune(float, int, int)() 208 209 for(;;) { 210 211 if(temp_meas_ready == true) { // temp sample ready 212 updateTemperaturesFromRawValues(); 213 CID 59638: Out-of-bounds read (OVERRUN) Overrunning array "current_temperature" of 1 4-byte elements at element index 1 (byte offset 4) using index "extruder" (which evaluates to 1). 214 input = (extruder<0)?current_temperature_bed:current_temperature[extruder]; 215 216 max=max(max,input); 217 min=min(min,input); 218 if(heating == true && input > temp) { 219 if(millis() - t2 > 5000) { ________________________________________________________________________________________________________ *** CID 59639: Out-of-bounds write (OVERRUN) /Marlin_main.cpp: 2278 in process_commands()() 2272 tmp_extruder = code_value(); 2273 if(tmp_extruder >= EXTRUDERS) { 2274 SERIAL_ECHO_START; 2275 SERIAL_ECHO(MSG_M200_INVALID_EXTRUDER); 2276 } 2277 } CID 59639: Out-of-bounds write (OVERRUN) Overrunning array "volumetric_multiplier" of 1 4-byte elements at element index 1 (byte offset 4) using index "tmp_extruder" (which evaluates to 1). 2278 volumetric_multiplier[tmp_extruder] = 1 / area; 2279 } 2280 break; 2281 case 201: // M201 2282 for(int8_t i=0; i < NUM_AXIS; i++) 2283 { ________________________________________________________________________________________________________ *** CID 59640: Out-of-bounds read (OVERRUN) /Marlin_main.cpp: 1802 in process_commands()() 1796 int pin_status = code_value(); 1797 int pin_number = LED_PIN; 1798 if (code_seen('P') && pin_status >= 0 && pin_status <= 255) 1799 pin_number = code_value(); 1800 for(int8_t i = 0; i < (int8_t)sizeof(sensitive_pins); i++) 1801 { CID 59640: Out-of-bounds read (OVERRUN) Overrunning array "sensitive_pins" of 28 2-byte elements at element index 55 (byte offset 110) using index "i" (which evaluates to 55). 1802 if (sensitive_pins[i] == pin_number) 1803 { 1804 pin_number = -1; 1805 break; 1806 } 1807 } ________________________________________________________________________________________________________ *** CID 59641: Uninitialized scalar field (UNINIT_CTOR) /Applications/Arduino.app/Contents/Resources/Java/libraries/LiquidCrystal/LiquidCrystal.cpp: 51 in LiquidCrystal::LiquidCrystal(unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char)() 45 } 46 47 LiquidCrystal::LiquidCrystal(uint8_t rs, uint8_t enable, 48 uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3) 49 { 50 init(1, rs, 255, enable, d0, d1, d2, d3, 0, 0, 0, 0); CID 59641: Uninitialized scalar field (UNINIT_CTOR) Non-static class member "_initialized" is not initialized in this constructor nor in any functions that it calls. 51 } 52 53 void LiquidCrystal::init(uint8_t fourbitmode, uint8_t rs, uint8_t rw, uint8_t enable, 54 uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3, 55 uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7) 56 { ________________________________________________________________________________________________________ *** CID 59642: Uninitialized scalar field (UNINIT_CTOR) /Applications/Arduino.app/Contents/Resources/Java/libraries/LiquidCrystal/LiquidCrystal.cpp: 45 in LiquidCrystal::LiquidCrystal(unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char)() 39 } 40 41 LiquidCrystal::LiquidCrystal(uint8_t rs, uint8_t rw, uint8_t enable, 42 uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3) 43 { 44 init(1, rs, rw, enable, d0, d1, d2, d3, 0, 0, 0, 0); CID 59642: Uninitialized scalar field (UNINIT_CTOR) Non-static class member "_initialized" is not initialized in this constructor nor in any functions that it calls. 45 } 46 47 LiquidCrystal::LiquidCrystal(uint8_t rs, uint8_t enable, 48 uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3) 49 { 50 init(1, rs, 255, enable, d0, d1, d2, d3, 0, 0, 0, 0); ________________________________________________________________________________________________________ *** CID 59643: Uninitialized scalar field (UNINIT_CTOR) /Applications/Arduino.app/Contents/Resources/Java/libraries/LiquidCrystal/LiquidCrystal.cpp: 32 in LiquidCrystal::LiquidCrystal(unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char, unsigned char)() 26 27 LiquidCrystal::LiquidCrystal(uint8_t rs, uint8_t rw, uint8_t enable, 28 uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3, 29 uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7) 30 { 31 init(0, rs, rw, enable, d0, d1, d2, d3, d4, d5, d6, d7); CID 59643: Uninitialized scalar field (UNINIT_CTOR) Non-static class member "_initialized" is not initialized in this constructor nor in any functions that it calls. 32 } 33 34 LiquidCrystal::LiquidCrystal(uint8_t rs, uint8_t enable, 35 uint8_t d0, uint8_t d1, uint8_t d2, uint8_t d3, 36 uint8_t d4, uint8_t d5, uint8_t d6, uint8_t d7) 37 { ________________________________________________________________________________________________________ To view the defects in Coverity Scan visit, http://scan.coverity.com/projects/2224?tab=overview
2014-05-14 14:59:48 -05:00
}
2016-06-18 05:16:13 -05:00
} // End of probe loop
if (STOW_PROBE()) return;
2016-06-23 21:22:45 -05:00
if (verbose_level > 0) {
SERIAL_PROTOCOLPGM("Mean: ");
SERIAL_PROTOCOL_F(mean, 6);
SERIAL_EOL;
}
SERIAL_PROTOCOLPGM("Standard Deviation: ");
SERIAL_PROTOCOL_F(sigma, 6);
SERIAL_EOL; SERIAL_EOL;
2016-06-21 17:32:28 -05:00
clean_up_after_endstop_or_probe_move();
2016-03-24 13:01:20 -05:00
report_current_position();
}
#endif // Z_MIN_PROBE_REPEATABILITY_TEST
/**
* M75: Start print timer
*/
inline void gcode_M75() { print_job_timer.start(); }
/**
* M76: Pause print timer
*/
inline void gcode_M76() { print_job_timer.pause(); }
/**
* M77: Stop print timer
*/
inline void gcode_M77() { print_job_timer.stop(); }
2016-04-26 20:13:27 -05:00
#if ENABLED(PRINTCOUNTER)
2016-07-18 21:27:42 -05:00
/**
2016-04-26 20:13:27 -05:00
* M78: Show print statistics
*/
inline void gcode_M78() {
// "M78 S78" will reset the statistics
if (code_seen('S') && code_value_int() == 78)
print_job_timer.initStats();
else print_job_timer.showStats();
2016-04-26 20:13:27 -05:00
}
#endif
/**
* M104: Set hot end temperature
*/
inline void gcode_M104() {
if (get_target_extruder_from_command(104)) return;
2016-03-29 21:50:01 -05:00
if (DEBUGGING(DRYRUN)) return;
#if ENABLED(SINGLENOZZLE)
if (target_extruder != active_extruder) return;
#endif
2015-04-03 23:43:30 -05:00
if (code_seen('S')) {
thermalManager.setTargetHotend(code_value_temp_abs(), target_extruder);
#if ENABLED(DUAL_X_CARRIAGE)
2015-04-03 23:43:30 -05:00
if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && target_extruder == 0)
thermalManager.setTargetHotend(code_value_temp_abs() == 0.0 ? 0.0 : code_value_temp_abs() + duplicate_extruder_temp_offset, 1);
2015-04-03 23:43:30 -05:00
#endif
2016-03-30 05:33:24 -05:00
#if ENABLED(PRINTJOB_TIMER_AUTOSTART)
/**
* Stop the timer at the end of print, starting is managed by
2016-07-08 08:00:39 -05:00
* 'heat and wait' M109.
* We use half EXTRUDE_MINTEMP here to allow nozzles to be put into hot
* stand by mode, for instance in a dual extruder setup, without affecting
* the running print timer.
*/
if (code_value_temp_abs() <= (EXTRUDE_MINTEMP)/2) {
print_job_timer.stop();
LCD_MESSAGEPGM(WELCOME_MSG);
}
#endif
if (code_value_temp_abs() > thermalManager.degHotend(target_extruder)) LCD_MESSAGEPGM(MSG_HEATING);
2015-04-03 23:43:30 -05:00
}
}
2016-04-03 18:18:49 -05:00
#if HAS_TEMP_HOTEND || HAS_TEMP_BED
void print_heaterstates() {
2016-04-03 18:18:49 -05:00
#if HAS_TEMP_HOTEND
SERIAL_PROTOCOLPGM(" T:");
2016-04-28 20:18:13 -05:00
SERIAL_PROTOCOL_F(thermalManager.degHotend(target_extruder), 1);
SERIAL_PROTOCOLPGM(" /");
2016-04-28 20:18:13 -05:00
SERIAL_PROTOCOL_F(thermalManager.degTargetHotend(target_extruder), 1);
#if ENABLED(SHOW_TEMP_ADC_VALUES)
SERIAL_PROTOCOLPAIR(" (", thermalManager.current_temperature_raw[target_extruder] / OVERSAMPLENR);
SERIAL_CHAR(')');
#endif
#endif
2015-04-03 17:31:35 -05:00
#if HAS_TEMP_BED
SERIAL_PROTOCOLPGM(" B:");
2016-04-28 20:18:13 -05:00
SERIAL_PROTOCOL_F(thermalManager.degBed(), 1);
SERIAL_PROTOCOLPGM(" /");
2016-04-28 20:18:13 -05:00
SERIAL_PROTOCOL_F(thermalManager.degTargetBed(), 1);
#if ENABLED(SHOW_TEMP_ADC_VALUES)
SERIAL_PROTOCOLPAIR(" (", thermalManager.current_temperature_bed_raw / OVERSAMPLENR);
SERIAL_CHAR(')');
#endif
#endif
2016-05-26 19:43:20 -05:00
#if HOTENDS > 1
2016-07-09 23:11:17 -05:00
HOTEND_LOOP() {
2016-07-28 16:51:18 -05:00
SERIAL_PROTOCOLPAIR(" T", e);
SERIAL_PROTOCOLCHAR(':');
2016-04-28 20:18:13 -05:00
SERIAL_PROTOCOL_F(thermalManager.degHotend(e), 1);
SERIAL_PROTOCOLPGM(" /");
2016-04-28 20:18:13 -05:00
SERIAL_PROTOCOL_F(thermalManager.degTargetHotend(e), 1);
#if ENABLED(SHOW_TEMP_ADC_VALUES)
SERIAL_PROTOCOLPAIR(" (", thermalManager.current_temperature_raw[e] / OVERSAMPLENR);
SERIAL_CHAR(')');
#endif
}
#endif
SERIAL_PROTOCOLPGM(" @:");
2016-07-29 17:14:13 -05:00
SERIAL_PROTOCOL(thermalManager.getHeaterPower(target_extruder));
#if HAS_TEMP_BED
SERIAL_PROTOCOLPGM(" B@:");
2016-07-29 17:14:13 -05:00
SERIAL_PROTOCOL(thermalManager.getHeaterPower(-1));
#endif
2016-05-26 19:43:20 -05:00
#if HOTENDS > 1
2016-07-09 23:11:17 -05:00
HOTEND_LOOP() {
2016-07-28 16:51:18 -05:00
SERIAL_PROTOCOLPAIR(" @", e);
SERIAL_PROTOCOLCHAR(':');
2016-07-29 17:14:13 -05:00
SERIAL_PROTOCOL(thermalManager.getHeaterPower(e));
}
#endif
}
#endif
/**
* M105: Read hot end and bed temperature
*/
inline void gcode_M105() {
if (get_target_extruder_from_command(105)) return;
2016-04-03 18:18:49 -05:00
#if HAS_TEMP_HOTEND || HAS_TEMP_BED
SERIAL_PROTOCOLPGM(MSG_OK);
print_heaterstates();
2016-04-03 18:18:49 -05:00
#else // !HAS_TEMP_HOTEND && !HAS_TEMP_BED
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_NO_THERMISTORS);
#endif
SERIAL_EOL;
}
2016-03-05 20:27:45 -06:00
#if FAN_COUNT > 0
/**
* M106: Set Fan Speed
2016-03-05 20:27:45 -06:00
*
* S<int> Speed between 0-255
* P<index> Fan index, if more than one fan
*/
2016-03-05 20:27:45 -06:00
inline void gcode_M106() {
uint16_t s = code_seen('S') ? code_value_ushort() : 255,
p = code_seen('P') ? code_value_ushort() : 0;
2016-03-05 20:27:45 -06:00
NOMORE(s, 255);
if (p < FAN_COUNT) fanSpeeds[p] = s;
}
/**
* M107: Fan Off
*/
2016-03-05 20:27:45 -06:00
inline void gcode_M107() {
uint16_t p = code_seen('P') ? code_value_ushort() : 0;
2016-03-05 20:27:45 -06:00
if (p < FAN_COUNT) fanSpeeds[p] = 0;
}
2016-03-05 20:27:45 -06:00
#endif // FAN_COUNT > 0
2014-12-20 10:33:43 -06:00
#if DISABLED(EMERGENCY_PARSER)
/**
* M108: Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature.
*/
inline void gcode_M108() { wait_for_heatup = false; }
2016-07-06 13:52:36 -05:00
/**
* M112: Emergency Stop
*/
inline void gcode_M112() { kill(PSTR(MSG_KILLED)); }
/**
* M410: Quickstop - Abort all planned moves
*
* This will stop the carriages mid-move, so most likely they
* will be out of sync with the stepper position after this.
*/
inline void gcode_M410() { quickstop_stepper(); }
2016-07-06 13:52:36 -05:00
#endif
#ifndef MIN_COOLING_SLOPE_DEG
#define MIN_COOLING_SLOPE_DEG 1.50
#endif
#ifndef MIN_COOLING_SLOPE_TIME
#define MIN_COOLING_SLOPE_TIME 60
#endif
/**
* M109: Sxxx Wait for extruder(s) to reach temperature. Waits only when heating.
* Rxxx Wait for extruder(s) to reach temperature. Waits when heating and cooling.
*/
inline void gcode_M109() {
2015-11-09 06:21:47 -06:00
if (get_target_extruder_from_command(109)) return;
2016-03-29 21:50:01 -05:00
if (DEBUGGING(DRYRUN)) return;
#if ENABLED(SINGLENOZZLE)
if (target_extruder != active_extruder) return;
#endif
bool no_wait_for_cooling = code_seen('S');
2015-04-13 19:17:36 -05:00
if (no_wait_for_cooling || code_seen('R')) {
thermalManager.setTargetHotend(code_value_temp_abs(), target_extruder);
#if ENABLED(DUAL_X_CARRIAGE)
2015-04-03 23:43:30 -05:00
if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && target_extruder == 0)
thermalManager.setTargetHotend(code_value_temp_abs() == 0.0 ? 0.0 : code_value_temp_abs() + duplicate_extruder_temp_offset, 1);
#endif
#if ENABLED(PRINTJOB_TIMER_AUTOSTART)
/**
* We use half EXTRUDE_MINTEMP here to allow nozzles to be put into hot
* stand by mode, for instance in a dual extruder setup, without affecting
* the running print timer.
*/
if (code_value_temp_abs() <= (EXTRUDE_MINTEMP)/2) {
print_job_timer.stop();
LCD_MESSAGEPGM(WELCOME_MSG);
}
/**
* We do not check if the timer is already running because this check will
* be done for us inside the Stopwatch::start() method thus a running timer
* will not restart.
*/
else print_job_timer.start();
#endif
if (thermalManager.isHeatingHotend(target_extruder)) LCD_MESSAGEPGM(MSG_HEATING);
}
#if ENABLED(AUTOTEMP)
2016-04-27 20:06:32 -05:00
planner.autotemp_M109();
#endif
#if TEMP_RESIDENCY_TIME > 0
2016-04-10 17:55:12 -05:00
millis_t residency_start_ms = 0;
// Loop until the temperature has stabilized
2016-04-10 17:55:12 -05:00
#define TEMP_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_RESIDENCY_TIME) * 1000UL))
#else
// Loop until the temperature is very close target
2016-04-28 20:18:13 -05:00
#define TEMP_CONDITIONS (wants_to_cool ? thermalManager.isCoolingHotend(target_extruder) : thermalManager.isHeatingHotend(target_extruder))
#endif //TEMP_RESIDENCY_TIME > 0
float theTarget = -1.0, old_temp = 9999.0;
bool wants_to_cool = false;
wait_for_heatup = true;
millis_t now, next_temp_ms = 0, next_cool_check_ms = 0;
KEEPALIVE_STATE(NOT_BUSY);
do {
2016-06-17 19:26:21 -05:00
// Target temperature might be changed during the loop
if (theTarget != thermalManager.degTargetHotend(target_extruder)) {
wants_to_cool = thermalManager.isCoolingHotend(target_extruder);
theTarget = thermalManager.degTargetHotend(target_extruder);
// Exit if S<lower>, continue if S<higher>, R<lower>, or R<higher>
if (no_wait_for_cooling && wants_to_cool) break;
}
now = millis();
2016-04-10 17:55:12 -05:00
if (ELAPSED(now, next_temp_ms)) { //Print temp & remaining time every 1s while waiting
next_temp_ms = now + 1000UL;
2016-06-17 19:26:21 -05:00
print_heaterstates();
#if TEMP_RESIDENCY_TIME > 0
SERIAL_PROTOCOLPGM(" W:");
2016-04-10 17:55:12 -05:00
if (residency_start_ms) {
2016-03-13 00:38:55 -06:00
long rem = (((TEMP_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL;
SERIAL_PROTOCOLLN(rem);
}
else {
SERIAL_PROTOCOLLNPGM("?");
}
#else
SERIAL_EOL;
#endif
2013-03-24 23:35:05 -05:00
}
idle();
refresh_cmd_timeout(); // to prevent stepper_inactive_time from running out
float temp = thermalManager.degHotend(target_extruder);
#if TEMP_RESIDENCY_TIME > 0
float temp_diff = fabs(theTarget - temp);
2016-04-10 17:55:12 -05:00
if (!residency_start_ms) {
// Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time.
2016-06-17 19:26:21 -05:00
if (temp_diff < TEMP_WINDOW) residency_start_ms = now;
}
else if (temp_diff > TEMP_HYSTERESIS) {
// Restart the timer whenever the temperature falls outside the hysteresis.
2016-06-17 19:26:21 -05:00
residency_start_ms = now;
}
#endif //TEMP_RESIDENCY_TIME > 0
// Prevent a wait-forever situation if R is misused i.e. M109 R0
if (wants_to_cool) {
// break after MIN_COOLING_SLOPE_TIME seconds
// if the temperature did not drop at least MIN_COOLING_SLOPE_DEG
if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) {
if (old_temp - temp < MIN_COOLING_SLOPE_DEG) break;
next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME;
old_temp = temp;
}
}
} while (wait_for_heatup && TEMP_CONDITIONS);
LCD_MESSAGEPGM(MSG_HEATING_COMPLETE);
KEEPALIVE_STATE(IN_HANDLER);
}
2015-04-03 17:31:35 -05:00
#if HAS_TEMP_BED
#ifndef MIN_COOLING_SLOPE_DEG_BED
#define MIN_COOLING_SLOPE_DEG_BED 1.50
#endif
#ifndef MIN_COOLING_SLOPE_TIME_BED
#define MIN_COOLING_SLOPE_TIME_BED 60
#endif
/**
* M190: Sxxx Wait for bed current temp to reach target temp. Waits only when heating
* Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
*/
inline void gcode_M190() {
2016-03-29 21:50:01 -05:00
if (DEBUGGING(DRYRUN)) return;
LCD_MESSAGEPGM(MSG_BED_HEATING);
bool no_wait_for_cooling = code_seen('S');
2016-07-08 08:00:39 -05:00
if (no_wait_for_cooling || code_seen('R')) {
thermalManager.setTargetBed(code_value_temp_abs());
#if ENABLED(PRINTJOB_TIMER_AUTOSTART)
if (code_value_temp_abs() > BED_MINTEMP) {
2016-07-08 08:00:39 -05:00
/**
* We start the timer when 'heating and waiting' command arrives, LCD
2016-07-08 08:00:39 -05:00
* functions never wait. Cooling down managed by extruders.
*
* We do not check if the timer is already running because this check will
* be done for us inside the Stopwatch::start() method thus a running timer
* will not restart.
*/
print_job_timer.start();
}
#endif
}
#if TEMP_BED_RESIDENCY_TIME > 0
millis_t residency_start_ms = 0;
// Loop until the temperature has stabilized
#define TEMP_BED_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_BED_RESIDENCY_TIME) * 1000UL))
#else
// Loop until the temperature is very close target
2016-04-28 20:18:13 -05:00
#define TEMP_BED_CONDITIONS (wants_to_cool ? thermalManager.isCoolingBed() : thermalManager.isHeatingBed())
#endif //TEMP_BED_RESIDENCY_TIME > 0
float theTarget = -1.0, old_temp = 9999.0;
bool wants_to_cool = false;
wait_for_heatup = true;
millis_t now, next_temp_ms = 0, next_cool_check_ms = 0;
KEEPALIVE_STATE(NOT_BUSY);
target_extruder = active_extruder; // for print_heaterstates
do {
2016-06-17 19:26:21 -05:00
// Target temperature might be changed during the loop
if (theTarget != thermalManager.degTargetBed()) {
wants_to_cool = thermalManager.isCoolingBed();
theTarget = thermalManager.degTargetBed();
// Exit if S<lower>, continue if S<higher>, R<lower>, or R<higher>
if (no_wait_for_cooling && wants_to_cool) break;
}
now = millis();
2016-04-10 17:55:12 -05:00
if (ELAPSED(now, next_temp_ms)) { //Print Temp Reading every 1 second while heating up.
next_temp_ms = now + 1000UL;
print_heaterstates();
#if TEMP_BED_RESIDENCY_TIME > 0
SERIAL_PROTOCOLPGM(" W:");
if (residency_start_ms) {
long rem = (((TEMP_BED_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL;
SERIAL_PROTOCOLLN(rem);
}
else {
SERIAL_PROTOCOLLNPGM("?");
}
#else
SERIAL_EOL;
#endif
}
2015-05-26 22:08:21 -05:00
idle();
refresh_cmd_timeout(); // to prevent stepper_inactive_time from running out
float temp = thermalManager.degBed();
#if TEMP_BED_RESIDENCY_TIME > 0
float temp_diff = fabs(theTarget - temp);
if (!residency_start_ms) {
// Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time.
2016-06-17 19:26:21 -05:00
if (temp_diff < TEMP_BED_WINDOW) residency_start_ms = now;
}
else if (temp_diff > TEMP_BED_HYSTERESIS) {
// Restart the timer whenever the temperature falls outside the hysteresis.
2016-06-17 19:26:21 -05:00
residency_start_ms = now;
}
#endif //TEMP_BED_RESIDENCY_TIME > 0
// Prevent a wait-forever situation if R is misused i.e. M190 R0
if (wants_to_cool) {
// break after MIN_COOLING_SLOPE_TIME_BED seconds
// if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_BED
if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) {
if (old_temp - temp < MIN_COOLING_SLOPE_DEG_BED) break;
next_cool_check_ms = now + 1000UL * MIN_COOLING_SLOPE_TIME_BED;
old_temp = temp;
}
}
} while (wait_for_heatup && TEMP_BED_CONDITIONS);
LCD_MESSAGEPGM(MSG_BED_DONE);
KEEPALIVE_STATE(IN_HANDLER);
}
2015-04-03 17:31:35 -05:00
#endif // HAS_TEMP_BED
/**
* M110: Set Current Line Number
*/
inline void gcode_M110() {
if (code_seen('N')) gcode_N = code_value_long();
}
/**
* M111: Set the debug level
*/
inline void gcode_M111() {
2016-06-16 13:24:11 -05:00
marlin_debug_flags = code_seen('S') ? code_value_byte() : (uint8_t) DEBUG_NONE;
2015-08-27 20:40:10 -05:00
const static char str_debug_1[] PROGMEM = MSG_DEBUG_ECHO;
const static char str_debug_2[] PROGMEM = MSG_DEBUG_INFO;
const static char str_debug_4[] PROGMEM = MSG_DEBUG_ERRORS;
const static char str_debug_8[] PROGMEM = MSG_DEBUG_DRYRUN;
const static char str_debug_16[] PROGMEM = MSG_DEBUG_COMMUNICATION;
2015-08-27 20:40:10 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
const static char str_debug_32[] PROGMEM = MSG_DEBUG_LEVELING;
2015-08-27 20:40:10 -05:00
#endif
const static char* const debug_strings[] PROGMEM = {
str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16,
#if ENABLED(DEBUG_LEVELING_FEATURE)
str_debug_32
#endif
};
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_DEBUG_PREFIX);
if (marlin_debug_flags) {
uint8_t comma = 0;
for (uint8_t i = 0; i < COUNT(debug_strings); i++) {
if (TEST(marlin_debug_flags, i)) {
2016-04-04 17:36:07 -05:00
if (comma++) SERIAL_CHAR(',');
serialprintPGM((char*)pgm_read_word(&(debug_strings[i])));
}
}
}
else {
SERIAL_ECHOPGM(MSG_DEBUG_OFF);
}
SERIAL_EOL;
}
2016-04-06 19:31:49 -05:00
#if ENABLED(HOST_KEEPALIVE_FEATURE)
/**
* M113: Get or set Host Keepalive interval (0 to disable)
*
* S<seconds> Optional. Set the keepalive interval.
*/
inline void gcode_M113() {
if (code_seen('S')) {
host_keepalive_interval = code_value_byte();
2016-04-06 19:31:49 -05:00
NOMORE(host_keepalive_interval, 60);
}
else {
SERIAL_ECHO_START;
SERIAL_ECHOLNPAIR("M113 S", (unsigned long)host_keepalive_interval);
2016-04-06 19:31:49 -05:00
}
}
#endif
#if ENABLED(BARICUDA)
2015-04-03 17:31:35 -05:00
#if HAS_HEATER_1
/**
* M126: Heater 1 valve open
*/
inline void gcode_M126() { baricuda_valve_pressure = code_seen('S') ? code_value_byte() : 255; }
/**
* M127: Heater 1 valve close
*/
2016-04-18 01:12:15 -05:00
inline void gcode_M127() { baricuda_valve_pressure = 0; }
#endif
2015-04-03 17:31:35 -05:00
#if HAS_HEATER_2
/**
* M128: Heater 2 valve open
*/
inline void gcode_M128() { baricuda_e_to_p_pressure = code_seen('S') ? code_value_byte() : 255; }
/**
* M129: Heater 2 valve close
*/
2016-04-18 01:12:15 -05:00
inline void gcode_M129() { baricuda_e_to_p_pressure = 0; }
#endif
#endif //BARICUDA
/**
* M140: Set bed temperature
*/
inline void gcode_M140() {
2016-03-29 21:50:01 -05:00
if (DEBUGGING(DRYRUN)) return;
if (code_seen('S')) thermalManager.setTargetBed(code_value_temp_abs());
}
#if ENABLED(ULTIPANEL)
/**
* M145: Set the heatup state for a material in the LCD menu
* S<material> (0=PLA, 1=ABS)
* H<hotend temp>
* B<bed temp>
* F<fan speed>
*/
inline void gcode_M145() {
int8_t material = code_seen('S') ? (int8_t)code_value_int() : 0;
if (material < 0 || material > 1) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_MATERIAL_INDEX);
}
else {
int v;
switch (material) {
case 0:
if (code_seen('H')) {
v = code_value_int();
preheatHotendTemp1 = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15);
}
if (code_seen('F')) {
v = code_value_int();
preheatFanSpeed1 = constrain(v, 0, 255);
}
#if TEMP_SENSOR_BED != 0
if (code_seen('B')) {
v = code_value_int();
preheatBedTemp1 = constrain(v, BED_MINTEMP, BED_MAXTEMP - 15);
}
#endif
break;
case 1:
if (code_seen('H')) {
v = code_value_int();
preheatHotendTemp2 = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15);
}
if (code_seen('F')) {
v = code_value_int();
preheatFanSpeed2 = constrain(v, 0, 255);
}
#if TEMP_SENSOR_BED != 0
if (code_seen('B')) {
v = code_value_int();
preheatBedTemp2 = constrain(v, BED_MINTEMP, BED_MAXTEMP - 15);
}
#endif
break;
}
}
}
#endif
#if ENABLED(TEMPERATURE_UNITS_SUPPORT)
/**
* M149: Set temperature units
*/
inline void gcode_M149() {
if (code_seen('C')) {
set_input_temp_units(TEMPUNIT_C);
} else if (code_seen('K')) {
set_input_temp_units(TEMPUNIT_K);
} else if (code_seen('F')) {
set_input_temp_units(TEMPUNIT_F);
}
}
#endif
#if HAS_POWER_SWITCH
/**
* M80: Turn on Power Supply
*/
inline void gcode_M80() {
OUT_WRITE(PS_ON_PIN, PS_ON_AWAKE); //GND
2016-03-26 22:36:36 -05:00
/**
* If you have a switch on suicide pin, this is useful
* if you want to start another print with suicide feature after
* a print without suicide...
*/
2015-04-03 17:31:35 -05:00
#if HAS_SUICIDE
OUT_WRITE(SUICIDE_PIN, HIGH);
#endif
#if ENABLED(ULTIPANEL)
powersupply = true;
LCD_MESSAGEPGM(WELCOME_MSG);
lcd_update();
#endif
}
2015-03-30 18:50:05 -05:00
#endif // HAS_POWER_SWITCH
/**
* M81: Turn off Power, including Power Supply, if there is one.
*
* This code should ALWAYS be available for EMERGENCY SHUTDOWN!
*/
inline void gcode_M81() {
2016-04-28 20:18:13 -05:00
thermalManager.disable_all_heaters();
stepper.finish_and_disable();
2016-03-05 20:27:45 -06:00
#if FAN_COUNT > 0
#if FAN_COUNT > 1
for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0;
#else
fanSpeeds[0] = 0;
#endif
#endif
2015-03-30 18:50:05 -05:00
delay(1000); // Wait 1 second before switching off
2015-04-03 17:31:35 -05:00
#if HAS_SUICIDE
stepper.synchronize();
2015-03-30 18:50:05 -05:00
suicide();
#elif HAS_POWER_SWITCH
OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP);
#endif
#if ENABLED(ULTIPANEL)
2015-03-30 18:50:05 -05:00
#if HAS_POWER_SWITCH
powersupply = false;
#endif
2015-03-30 18:50:05 -05:00
LCD_MESSAGEPGM(MACHINE_NAME " " MSG_OFF ".");
lcd_update();
#endif
}
/**
* M82: Set E codes absolute (default)
*/
inline void gcode_M82() { axis_relative_modes[E_AXIS] = false; }
/**
* M83: Set E codes relative while in Absolute Coordinates (G90) mode
*/
inline void gcode_M83() { axis_relative_modes[E_AXIS] = true; }
/**
* M18, M84: Disable all stepper motors
*/
inline void gcode_M18_M84() {
if (code_seen('S')) {
stepper_inactive_time = code_value_millis_from_seconds();
}
else {
bool all_axis = !((code_seen('X')) || (code_seen('Y')) || (code_seen('Z')) || (code_seen('E')));
if (all_axis) {
stepper.finish_and_disable();
}
else {
stepper.synchronize();
if (code_seen('X')) disable_x();
if (code_seen('Y')) disable_y();
if (code_seen('Z')) disable_z();
#if ((E0_ENABLE_PIN != X_ENABLE_PIN) && (E1_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS
if (code_seen('E')) {
disable_e0();
disable_e1();
disable_e2();
disable_e3();
}
#endif
}
}
}
/**
* M85: Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
*/
inline void gcode_M85() {
if (code_seen('S')) max_inactive_time = code_value_millis_from_seconds();
}
/**
* M92: Set axis steps-per-unit for one or more axes, X, Y, Z, and E.
* (Follows the same syntax as G92)
*/
inline void gcode_M92() {
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) {
if (code_seen(axis_codes[i])) {
if (i == E_AXIS) {
float value = code_value_per_axis_unit(i);
if (value < 20.0) {
float factor = planner.axis_steps_per_mm[i] / value; // increase e constants if M92 E14 is given for netfab.
2016-04-27 20:06:32 -05:00
planner.max_e_jerk *= factor;
2016-07-15 20:49:34 -05:00
planner.max_feedrate_mm_s[i] *= factor;
planner.max_acceleration_steps_per_s2[i] *= factor;
}
planner.axis_steps_per_mm[i] = value;
}
else {
planner.axis_steps_per_mm[i] = code_value_per_axis_unit(i);
}
}
}
planner.refresh_positioning();
}
/**
* Output the current position to serial
*/
static void report_current_position() {
SERIAL_PROTOCOLPGM("X:");
SERIAL_PROTOCOL(current_position[X_AXIS]);
SERIAL_PROTOCOLPGM(" Y:");
SERIAL_PROTOCOL(current_position[Y_AXIS]);
SERIAL_PROTOCOLPGM(" Z:");
SERIAL_PROTOCOL(current_position[Z_AXIS]);
SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOL(current_position[E_AXIS]);
stepper.report_positions();
#if ENABLED(SCARA)
SERIAL_PROTOCOLPGM("SCARA Theta:");
SERIAL_PROTOCOL(delta[X_AXIS]);
SERIAL_PROTOCOLPGM(" Psi+Theta:");
SERIAL_PROTOCOL(delta[Y_AXIS]);
SERIAL_EOL;
2015-08-05 06:40:36 -05:00
SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
SERIAL_PROTOCOL(delta[X_AXIS]);
SERIAL_PROTOCOLPGM(" Psi+Theta (90):");
SERIAL_PROTOCOL(delta[Y_AXIS] - delta[X_AXIS] - 90);
SERIAL_EOL;
2015-08-05 06:40:36 -05:00
SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
SERIAL_PROTOCOL(delta[X_AXIS] / 90 * planner.axis_steps_per_mm[X_AXIS]);
SERIAL_PROTOCOLPGM(" Psi+Theta:");
SERIAL_PROTOCOL((delta[Y_AXIS] - delta[X_AXIS]) / 90 * planner.axis_steps_per_mm[Y_AXIS]);
SERIAL_EOL; SERIAL_EOL;
#endif
}
/**
* M114: Output current position to serial port
*/
inline void gcode_M114() { report_current_position(); }
/**
* M115: Capabilities string
*/
inline void gcode_M115() {
SERIAL_PROTOCOLPGM(MSG_M115_REPORT);
}
2015-05-17 07:00:09 -05:00
/**
* M117: Set LCD Status Message
*/
inline void gcode_M117() {
lcd_setstatus(current_command_args);
2015-05-17 07:00:09 -05:00
}
/**
* M119: Output endstop states to serial output
*/
2016-04-27 16:46:24 -05:00
inline void gcode_M119() { endstops.M119(); }
/**
* M120: Enable endstops and set non-homing endstop state to "enabled"
*/
inline void gcode_M120() { endstops.enable_globally(true); }
/**
* M121: Disable endstops and set non-homing endstop state to "disabled"
*/
inline void gcode_M121() { endstops.enable_globally(false); }
#if ENABLED(BLINKM)
/**
* M150: Set Status LED Color - Use R-U-B for R-G-B
*/
inline void gcode_M150() {
SendColors(
code_seen('R') ? code_value_byte() : 0,
code_seen('U') ? code_value_byte() : 0,
code_seen('B') ? code_value_byte() : 0
);
}
#endif // BLINKM
#if ENABLED(EXPERIMENTAL_I2CBUS)
/**
* M155: Send data to a I2C slave device
*
* This is a PoC, the formating and arguments for the GCODE will
* change to be more compatible, the current proposal is:
*
* M155 A<slave device address base 10> ; Sets the I2C slave address the data will be sent to
*
* M155 B<byte-1 value in base 10>
* M155 B<byte-2 value in base 10>
* M155 B<byte-3 value in base 10>
*
* M155 S1 ; Send the buffered data and reset the buffer
* M155 R1 ; Reset the buffer without sending data
*
*/
inline void gcode_M155() {
// Set the target address
2016-08-11 02:16:14 -05:00
if (code_seen('A')) i2c.address(code_value_byte());
// Add a new byte to the buffer
2016-08-11 02:16:14 -05:00
if (code_seen('B')) i2c.addbyte(code_value_byte());
// Flush the buffer to the bus
2016-08-11 02:16:14 -05:00
if (code_seen('S')) i2c.send();
// Reset and rewind the buffer
else if (code_seen('R')) i2c.reset();
}
/**
* M156: Request X bytes from I2C slave device
*
* Usage: M156 A<slave device address base 10> B<number of bytes>
*/
inline void gcode_M156() {
2016-08-11 02:16:14 -05:00
if (code_seen('A')) i2c.address(code_value_byte());
2016-08-11 02:16:14 -05:00
uint8_t bytes = code_seen('B') ? code_value_byte() : 1;
2016-08-14 23:45:28 -05:00
if (i2c.addr && bytes && bytes <= TWIBUS_BUFFER_SIZE) {
i2c.relay(bytes);
}
else {
SERIAL_ERROR_START;
SERIAL_ERRORLN("Bad i2c request");
}
}
#endif // EXPERIMENTAL_I2CBUS
/**
* M200: Set filament diameter and set E axis units to cubic units
*
* T<extruder> - Optional extruder number. Current extruder if omitted.
* D<linear> - Diameter of the filament. Use "D0" to switch back to linear units on the E axis.
*/
inline void gcode_M200() {
if (get_target_extruder_from_command(200)) return;
if (code_seen('D')) {
// setting any extruder filament size disables volumetric on the assumption that
// slicers either generate in extruder values as cubic mm or as as filament feeds
// for all extruders
volumetric_enabled = (code_value_linear_units() != 0.0);
if (volumetric_enabled) {
filament_size[target_extruder] = code_value_linear_units();
// make sure all extruders have some sane value for the filament size
for (uint8_t i = 0; i < COUNT(filament_size); i++)
if (! filament_size[i]) filament_size[i] = DEFAULT_NOMINAL_FILAMENT_DIA;
}
}
else {
//reserved for setting filament diameter via UFID or filament measuring device
return;
}
calculate_volumetric_multipliers();
}
/**
* M201: Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
*/
inline void gcode_M201() {
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) {
if (code_seen(axis_codes[i])) {
planner.max_acceleration_mm_per_s2[i] = code_value_axis_units(i);
}
}
// steps per sq second need to be updated to agree with the units per sq second (as they are what is used in the planner)
2016-04-27 20:06:32 -05:00
planner.reset_acceleration_rates();
}
#if 0 // Not used for Sprinter/grbl gen6
inline void gcode_M202() {
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) {
if (code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value_axis_units(i) * planner.axis_steps_per_mm[i];
}
}
#endif
/**
* M203: Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in units/sec
*/
inline void gcode_M203() {
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i)
if (code_seen(axis_codes[i]))
2016-07-15 20:49:34 -05:00
planner.max_feedrate_mm_s[i] = code_value_axis_units(i);
}
/**
* M204: Set Accelerations in units/sec^2 (M204 P1200 R3000 T3000)
*
* P = Printing moves
* R = Retract only (no X, Y, Z) moves
* T = Travel (non printing) moves
*
* Also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate
*/
inline void gcode_M204() {
2015-04-03 23:43:30 -05:00
if (code_seen('S')) { // Kept for legacy compatibility. Should NOT BE USED for new developments.
planner.travel_acceleration = planner.acceleration = code_value_linear_units();
SERIAL_ECHOLNPAIR("Setting Print and Travel Acceleration: ", planner.acceleration);
}
2015-04-03 23:43:30 -05:00
if (code_seen('P')) {
planner.acceleration = code_value_linear_units();
SERIAL_ECHOLNPAIR("Setting Print Acceleration: ", planner.acceleration);
}
2015-04-03 23:43:30 -05:00
if (code_seen('R')) {
planner.retract_acceleration = code_value_linear_units();
SERIAL_ECHOLNPAIR("Setting Retract Acceleration: ", planner.retract_acceleration);
}
2015-04-03 23:43:30 -05:00
if (code_seen('T')) {
planner.travel_acceleration = code_value_linear_units();
SERIAL_ECHOLNPAIR("Setting Travel Acceleration: ", planner.travel_acceleration);
}
}
/**
* M205: Set Advanced Settings
*
* S = Min Feed Rate (units/s)
* T = Min Travel Feed Rate (units/s)
* B = Min Segment Time (µs)
* X = Max XY Jerk (units/sec^2)
* Z = Max Z Jerk (units/sec^2)
* E = Max E Jerk (units/sec^2)
*/
inline void gcode_M205() {
2016-07-15 20:49:34 -05:00
if (code_seen('S')) planner.min_feedrate_mm_s = code_value_linear_units();
if (code_seen('T')) planner.min_travel_feedrate_mm_s = code_value_linear_units();
if (code_seen('B')) planner.min_segment_time = code_value_millis();
if (code_seen('X')) planner.max_xy_jerk = code_value_linear_units();
if (code_seen('Z')) planner.max_z_jerk = code_value_axis_units(Z_AXIS);
if (code_seen('E')) planner.max_e_jerk = code_value_axis_units(E_AXIS);
}
/**
* M206: Set Additional Homing Offset (X Y Z). SCARA aliases T=X, P=Y
*/
inline void gcode_M206() {
2016-07-23 15:07:23 -05:00
LOOP_XYZ(i)
if (code_seen(axis_codes[i]))
set_home_offset((AxisEnum)i, code_value_axis_units(i));
#if ENABLED(SCARA)
if (code_seen('T')) set_home_offset(X_AXIS, code_value_axis_units(X_AXIS)); // Theta
if (code_seen('P')) set_home_offset(Y_AXIS, code_value_axis_units(Y_AXIS)); // Psi
#endif
SYNC_PLAN_POSITION_KINEMATIC();
report_current_position();
}
#if ENABLED(DELTA)
/**
* M665: Set delta configurations
*
* L = diagonal rod
* R = delta radius
* S = segments per second
* A = Alpha (Tower 1) diagonal rod trim
* B = Beta (Tower 2) diagonal rod trim
* C = Gamma (Tower 3) diagonal rod trim
*/
inline void gcode_M665() {
if (code_seen('L')) delta_diagonal_rod = code_value_linear_units();
if (code_seen('R')) delta_radius = code_value_linear_units();
if (code_seen('S')) delta_segments_per_second = code_value_float();
if (code_seen('A')) delta_diagonal_rod_trim_tower_1 = code_value_linear_units();
if (code_seen('B')) delta_diagonal_rod_trim_tower_2 = code_value_linear_units();
if (code_seen('C')) delta_diagonal_rod_trim_tower_3 = code_value_linear_units();
recalc_delta_settings(delta_radius, delta_diagonal_rod);
}
/**
* M666: Set delta endstop adjustment
*/
inline void gcode_M666() {
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2015-08-05 06:40:36 -05:00
SERIAL_ECHOLNPGM(">>> gcode_M666");
}
2015-07-09 18:57:44 -05:00
#endif
2016-07-23 15:07:23 -05:00
LOOP_XYZ(i) {
if (code_seen(axis_codes[i])) {
endstop_adj[i] = code_value_axis_units(i);
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2015-08-05 06:40:36 -05:00
SERIAL_ECHOPGM("endstop_adj[");
SERIAL_ECHO(axis_codes[i]);
SERIAL_ECHOLNPAIR("] = ", endstop_adj[i]);
2015-08-05 06:40:36 -05:00
}
2015-07-09 18:57:44 -05:00
#endif
}
}
2015-08-05 06:40:36 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
2016-03-29 21:50:01 -05:00
if (DEBUGGING(LEVELING)) {
2015-08-05 06:40:36 -05:00
SERIAL_ECHOLNPGM("<<< gcode_M666");
}
2015-07-09 18:57:44 -05:00
#endif
}
#elif ENABLED(Z_DUAL_ENDSTOPS) // !DELTA && ENABLED(Z_DUAL_ENDSTOPS)
/**
* M666: For Z Dual Endstop setup, set z axis offset to the z2 axis.
*/
inline void gcode_M666() {
if (code_seen('Z')) z_endstop_adj = code_value_axis_units(Z_AXIS);
SERIAL_ECHOLNPAIR("Z Endstop Adjustment set to (mm):", z_endstop_adj);
}
2015-08-05 06:40:36 -05:00
#endif // !DELTA && Z_DUAL_ENDSTOPS
#if ENABLED(FWRETRACT)
/**
* M207: Set firmware retraction values
*
* S[+units] retract_length
* W[+units] retract_length_swap (multi-extruder)
* F[units/min] retract_feedrate_mm_s
* Z[units] retract_zlift
*/
inline void gcode_M207() {
if (code_seen('S')) retract_length = code_value_axis_units(E_AXIS);
2016-07-15 20:49:34 -05:00
if (code_seen('F')) retract_feedrate_mm_s = MMM_TO_MMS(code_value_axis_units(E_AXIS));
if (code_seen('Z')) retract_zlift = code_value_axis_units(Z_AXIS);
#if EXTRUDERS > 1
if (code_seen('W')) retract_length_swap = code_value_axis_units(E_AXIS);
#endif
}
/**
* M208: Set firmware un-retraction values
*
* S[+units] retract_recover_length (in addition to M207 S*)
* W[+units] retract_recover_length_swap (multi-extruder)
2016-07-15 20:49:34 -05:00
* F[units/min] retract_recover_feedrate_mm_s
*/
inline void gcode_M208() {
if (code_seen('S')) retract_recover_length = code_value_axis_units(E_AXIS);
2016-07-15 20:49:34 -05:00
if (code_seen('F')) retract_recover_feedrate_mm_s = MMM_TO_MMS(code_value_axis_units(E_AXIS));
#if EXTRUDERS > 1
if (code_seen('W')) retract_recover_length_swap = code_value_axis_units(E_AXIS);
#endif
}
/**
* M209: Enable automatic retract (M209 S1)
* detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction.
*/
inline void gcode_M209() {
if (code_seen('S')) {
2016-08-20 20:11:08 -05:00
autoretract_enabled = code_value_bool();
for (int i = 0; i < EXTRUDERS; i++) retracted[i] = false;
}
}
#endif // FWRETRACT
/**
* M211: Enable, Disable, and/or Report software endstops
*
* Usage: M211 S1 to enable, M211 S0 to disable, M211 alone for report
*/
inline void gcode_M211() {
SERIAL_ECHO_START;
#if ENABLED(min_software_endstops) || ENABLED(max_software_endstops)
if (code_seen('S')) soft_endstops_enabled = code_value_bool();
#endif
#if ENABLED(min_software_endstops) || ENABLED(max_software_endstops)
SERIAL_ECHOPGM(MSG_SOFT_ENDSTOPS ": ");
serialprintPGM(soft_endstops_enabled ? PSTR(MSG_ON) : PSTR(MSG_OFF));
#else
SERIAL_ECHOPGM(MSG_SOFT_ENDSTOPS ": " MSG_OFF);
#endif
SERIAL_ECHOPGM(" " MSG_SOFT_MIN ": ");
SERIAL_ECHOPAIR( MSG_X, soft_endstop_min[X_AXIS]);
SERIAL_ECHOPAIR(" " MSG_Y, soft_endstop_min[Y_AXIS]);
SERIAL_ECHOPAIR(" " MSG_Z, soft_endstop_min[Z_AXIS]);
SERIAL_ECHOPGM(" " MSG_SOFT_MAX ": ");
SERIAL_ECHOPAIR( MSG_X, soft_endstop_max[X_AXIS]);
SERIAL_ECHOPAIR(" " MSG_Y, soft_endstop_max[Y_AXIS]);
SERIAL_ECHOLNPAIR(" " MSG_Z, soft_endstop_max[Z_AXIS]);
}
2016-05-26 19:43:20 -05:00
#if HOTENDS > 1
/**
* M218 - set hotend offset (in linear units)
*
* T<tool>
* X<xoffset>
* Y<yoffset>
* Z<zoffset> - Available with DUAL_X_CARRIAGE and SWITCHING_EXTRUDER
*/
inline void gcode_M218() {
if (get_target_extruder_from_command(218)) return;
if (code_seen('X')) hotend_offset[X_AXIS][target_extruder] = code_value_axis_units(X_AXIS);
if (code_seen('Y')) hotend_offset[Y_AXIS][target_extruder] = code_value_axis_units(Y_AXIS);
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_EXTRUDER)
if (code_seen('Z')) hotend_offset[Z_AXIS][target_extruder] = code_value_axis_units(Z_AXIS);
#endif
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_HOTEND_OFFSET);
2016-07-09 23:11:17 -05:00
HOTEND_LOOP() {
2015-04-03 23:43:30 -05:00
SERIAL_CHAR(' ');
2016-05-26 19:43:20 -05:00
SERIAL_ECHO(hotend_offset[X_AXIS][e]);
2015-04-03 23:43:30 -05:00
SERIAL_CHAR(',');
2016-05-26 19:43:20 -05:00
SERIAL_ECHO(hotend_offset[Y_AXIS][e]);
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_EXTRUDER)
2015-04-03 23:43:30 -05:00
SERIAL_CHAR(',');
2016-05-26 19:43:20 -05:00
SERIAL_ECHO(hotend_offset[Z_AXIS][e]);
#endif
}
SERIAL_EOL;
}
2016-05-26 19:43:20 -05:00
#endif // HOTENDS > 1
/**
* M220: Set speed percentage factor, aka "Feed Rate" (M220 S95)
*/
inline void gcode_M220() {
2016-07-15 20:49:34 -05:00
if (code_seen('S')) feedrate_percentage = code_value_int();
}
/**
* M221: Set extrusion percentage (M221 T0 S95)
*/
inline void gcode_M221() {
if (get_target_extruder_from_command(221)) return;
if (code_seen('S'))
2016-08-18 22:13:47 -05:00
flow_percentage[target_extruder] = code_value_int();
}
/**
* M226: Wait until the specified pin reaches the state required (M226 P<pin> S<state>)
*/
inline void gcode_M226() {
if (code_seen('P')) {
int pin_number = code_value_int();
int pin_state = code_seen('S') ? code_value_int() : -1; // required pin state - default is inverted
if (pin_state >= -1 && pin_state <= 1) {
for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) {
if (sensitive_pins[i] == pin_number) {
pin_number = -1;
break;
}
}
if (pin_number > -1) {
int target = LOW;
stepper.synchronize();
pinMode(pin_number, INPUT);
switch (pin_state) {
case 1:
target = HIGH;
break;
case 0:
target = LOW;
break;
case -1:
target = !digitalRead(pin_number);
break;
}
2015-05-26 22:08:21 -05:00
while (digitalRead(pin_number) != target) idle();
} // pin_number > -1
} // pin_state -1 0 1
} // code_seen('P')
}
#if HAS_SERVOS
/**
* M280: Get or set servo position. P<index> [S<angle>]
*/
inline void gcode_M280() {
if (!code_seen('P')) return;
int servo_index = code_value_int();
if (servo_index >= 0 && servo_index < NUM_SERVOS) {
if (code_seen('S'))
MOVE_SERVO(servo_index, code_value_int());
else {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(" Servo ");
SERIAL_ECHO(servo_index);
SERIAL_ECHOPGM(": ");
SERIAL_ECHOLN(servo[servo_index].read());
}
}
else {
SERIAL_ERROR_START;
SERIAL_ERROR("Servo ");
SERIAL_ERROR(servo_index);
SERIAL_ERRORLN(" out of range");
}
}
#endif // HAS_SERVOS
#if HAS_BUZZER
/**
* M300: Play beep sound S<frequency Hz> P<duration ms>
*/
inline void gcode_M300() {
2016-06-04 14:29:01 -05:00
uint16_t const frequency = code_seen('S') ? code_value_ushort() : 260;
uint16_t duration = code_seen('P') ? code_value_ushort() : 1000;
// Limits the tone duration to 0-5 seconds.
NOMORE(duration, 5000);
2016-08-01 23:10:53 -05:00
BUZZ(duration, frequency);
}
#endif // HAS_BUZZER
#if ENABLED(PIDTEMP)
/**
2015-08-30 21:04:30 -05:00
* M301: Set PID parameters P I D (and optionally C, L)
*
* P[float] Kp term
* I[float] Ki term (unscaled)
* D[float] Kd term (unscaled)
*
* With PID_EXTRUSION_SCALING:
2015-08-30 21:04:30 -05:00
*
* C[float] Kc term
* L[float] LPQ length
*/
inline void gcode_M301() {
// multi-extruder PID patch: M301 updates or prints a single extruder's PID values
// default behaviour (omitting E parameter) is to update for extruder 0 only
int e = code_seen('E') ? code_value_int() : 0; // extruder being updated
2016-05-26 19:43:20 -05:00
if (e < HOTENDS) { // catch bad input value
if (code_seen('P')) PID_PARAM(Kp, e) = code_value_float();
if (code_seen('I')) PID_PARAM(Ki, e) = scalePID_i(code_value_float());
if (code_seen('D')) PID_PARAM(Kd, e) = scalePID_d(code_value_float());
#if ENABLED(PID_EXTRUSION_SCALING)
if (code_seen('C')) PID_PARAM(Kc, e) = code_value_float();
if (code_seen('L')) lpq_len = code_value_float();
2015-08-30 21:04:30 -05:00
NOMORE(lpq_len, LPQ_MAX_LEN);
2015-08-05 06:40:36 -05:00
#endif
2016-04-28 20:18:13 -05:00
thermalManager.updatePID();
SERIAL_ECHO_START;
2016-05-26 19:43:20 -05:00
#if ENABLED(PID_PARAMS_PER_HOTEND)
SERIAL_ECHOPGM(" e:"); // specify extruder in serial output
SERIAL_ECHO(e);
2016-05-26 19:43:20 -05:00
#endif // PID_PARAMS_PER_HOTEND
SERIAL_ECHOPGM(" p:");
SERIAL_ECHO(PID_PARAM(Kp, e));
SERIAL_ECHOPGM(" i:");
SERIAL_ECHO(unscalePID_i(PID_PARAM(Ki, e)));
SERIAL_ECHOPGM(" d:");
SERIAL_ECHO(unscalePID_d(PID_PARAM(Kd, e)));
#if ENABLED(PID_EXTRUSION_SCALING)
SERIAL_ECHOPGM(" c:");
//Kc does not have scaling applied above, or in resetting defaults
SERIAL_ECHO(PID_PARAM(Kc, e));
#endif
2015-08-05 06:40:36 -05:00
SERIAL_EOL;
}
else {
SERIAL_ERROR_START;
SERIAL_ERRORLN(MSG_INVALID_EXTRUDER);
}
}
#endif // PIDTEMP
#if ENABLED(PIDTEMPBED)
inline void gcode_M304() {
if (code_seen('P')) thermalManager.bedKp = code_value_float();
if (code_seen('I')) thermalManager.bedKi = scalePID_i(code_value_float());
if (code_seen('D')) thermalManager.bedKd = scalePID_d(code_value_float());
2016-04-28 20:18:13 -05:00
thermalManager.updatePID();
SERIAL_ECHO_START;
SERIAL_ECHOPGM(" p:");
2016-04-28 20:18:13 -05:00
SERIAL_ECHO(thermalManager.bedKp);
SERIAL_ECHOPGM(" i:");
2016-04-28 20:18:13 -05:00
SERIAL_ECHO(unscalePID_i(thermalManager.bedKi));
SERIAL_ECHOPGM(" d:");
2016-04-28 20:18:13 -05:00
SERIAL_ECHOLN(unscalePID_d(thermalManager.bedKd));
}
#endif // PIDTEMPBED
2015-04-03 17:31:35 -05:00
#if defined(CHDK) || HAS_PHOTOGRAPH
/**
* M240: Trigger a camera by emulating a Canon RC-1
* See http://www.doc-diy.net/photo/rc-1_hacked/
*/
inline void gcode_M240() {
#ifdef CHDK
2015-08-05 06:40:36 -05:00
OUT_WRITE(CHDK, HIGH);
chdkHigh = millis();
chdkActive = true;
2015-04-03 17:31:35 -05:00
#elif HAS_PHOTOGRAPH
const uint8_t NUM_PULSES = 16;
const float PULSE_LENGTH = 0.01524;
for (int i = 0; i < NUM_PULSES; i++) {
WRITE(PHOTOGRAPH_PIN, HIGH);
_delay_ms(PULSE_LENGTH);
WRITE(PHOTOGRAPH_PIN, LOW);
_delay_ms(PULSE_LENGTH);
}
delay(7.33);
for (int i = 0; i < NUM_PULSES; i++) {
WRITE(PHOTOGRAPH_PIN, HIGH);
_delay_ms(PULSE_LENGTH);
WRITE(PHOTOGRAPH_PIN, LOW);
_delay_ms(PULSE_LENGTH);
}
2015-04-03 17:31:35 -05:00
#endif // !CHDK && HAS_PHOTOGRAPH
}
#endif // CHDK || PHOTOGRAPH_PIN
2016-05-31 13:47:02 -05:00
#if HAS_LCD_CONTRAST
/**
* M250: Read and optionally set the LCD contrast
*/
inline void gcode_M250() {
if (code_seen('C')) set_lcd_contrast(code_value_int());
SERIAL_PROTOCOLPGM("lcd contrast value: ");
SERIAL_PROTOCOL(lcd_contrast);
SERIAL_EOL;
}
#endif // HAS_LCD_CONTRAST
#if ENABLED(PREVENT_COLD_EXTRUSION)
/**
2016-07-06 10:28:09 -05:00
* M302: Allow cold extrudes, or set the minimum extrude temperature
*
* S<temperature> sets the minimum extrude temperature
* P<bool> enables (1) or disables (0) cold extrusion
*
* Examples:
*
* M302 ; report current cold extrusion state
* M302 P0 ; enable cold extrusion checking
* M302 P1 ; disables cold extrusion checking
* M302 S0 ; always allow extrusion (disables checking)
* M302 S170 ; only allow extrusion above 170
* M302 S170 P1 ; set min extrude temp to 170 but leave disabled
*/
inline void gcode_M302() {
2016-07-06 10:28:09 -05:00
bool seen_S = code_seen('S');
if (seen_S) {
thermalManager.extrude_min_temp = code_value_temp_abs();
thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0);
}
if (code_seen('P'))
thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0) || code_value_bool();
else if (!seen_S) {
// Report current state
SERIAL_ECHO_START;
SERIAL_ECHOPAIR("Cold extrudes are ", (thermalManager.allow_cold_extrude ? "en" : "dis"));
SERIAL_ECHOPAIR("abled (min temp ", int(thermalManager.extrude_min_temp + 0.5));
SERIAL_ECHOLNPGM("C)");
}
}
#endif // PREVENT_COLD_EXTRUSION
/**
* M303: PID relay autotune
*
* S<temperature> sets the target temperature. (default 150C)
* E<extruder> (-1 for the bed) (default 0)
* C<cycles>
* U<bool> with a non-zero value will apply the result to current settings
*/
inline void gcode_M303() {
#if HAS_PID_HEATING
int e = code_seen('E') ? code_value_int() : 0;
int c = code_seen('C') ? code_value_int() : 5;
bool u = code_seen('U') && code_value_bool();
2016-03-24 13:01:20 -05:00
float temp = code_seen('S') ? code_value_temp_abs() : (e < 0 ? 70.0 : 150.0);
2016-05-26 19:43:20 -05:00
if (e >= 0 && e < HOTENDS)
target_extruder = e;
KEEPALIVE_STATE(NOT_BUSY); // don't send "busy: processing" messages during autotune output
2016-04-28 20:18:13 -05:00
thermalManager.PID_autotune(temp, e, c, u);
KEEPALIVE_STATE(IN_HANDLER);
#else
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_M303_DISABLED);
#endif
}
#if ENABLED(SCARA)
bool SCARA_move_to_cal(uint8_t delta_x, uint8_t delta_y) {
//SoftEndsEnabled = false; // Ignore soft endstops during calibration
//SERIAL_ECHOLNPGM(" Soft endstops disabled");
2015-04-08 02:56:19 -05:00
if (IsRunning()) {
//gcode_get_destination(); // For X Y Z E F
delta[X_AXIS] = delta_x;
delta[Y_AXIS] = delta_y;
2016-07-21 17:46:22 -05:00
forward_kinematics_SCARA(delta);
destination[X_AXIS] = delta[X_AXIS] / axis_scaling[X_AXIS];
destination[Y_AXIS] = delta[Y_AXIS] / axis_scaling[Y_AXIS];
prepare_move_to_destination();
//ok_to_send();
return true;
}
return false;
}
/**
* M360: SCARA calibration: Move to cal-position ThetaA (0 deg calibration)
*/
inline bool gcode_M360() {
SERIAL_ECHOLNPGM(" Cal: Theta 0");
return SCARA_move_to_cal(0, 120);
}
/**
* M361: SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree)
*/
inline bool gcode_M361() {
SERIAL_ECHOLNPGM(" Cal: Theta 90");
return SCARA_move_to_cal(90, 130);
}
/**
* M362: SCARA calibration: Move to cal-position PsiA (0 deg calibration)
*/
inline bool gcode_M362() {
SERIAL_ECHOLNPGM(" Cal: Psi 0");
return SCARA_move_to_cal(60, 180);
}
/**
* M363: SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree)
*/
inline bool gcode_M363() {
SERIAL_ECHOLNPGM(" Cal: Psi 90");
return SCARA_move_to_cal(50, 90);
}
/**
* M364: SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position)
*/
inline bool gcode_M364() {
SERIAL_ECHOLNPGM(" Cal: Theta-Psi 90");
return SCARA_move_to_cal(45, 135);
}
/**
* M365: SCARA calibration: Scaling factor, X, Y, Z axis
*/
inline void gcode_M365() {
2016-07-23 15:07:23 -05:00
LOOP_XYZ(i)
if (code_seen(axis_codes[i]))
axis_scaling[i] = code_value_float();
}
#endif // SCARA
#if ENABLED(EXT_SOLENOID)
void enable_solenoid(uint8_t num) {
switch (num) {
case 0:
OUT_WRITE(SOL0_PIN, HIGH);
break;
2015-04-03 17:31:35 -05:00
#if HAS_SOLENOID_1
case 1:
OUT_WRITE(SOL1_PIN, HIGH);
break;
#endif
2015-04-03 17:31:35 -05:00
#if HAS_SOLENOID_2
case 2:
OUT_WRITE(SOL2_PIN, HIGH);
break;
#endif
2015-04-03 17:31:35 -05:00
#if HAS_SOLENOID_3
case 3:
OUT_WRITE(SOL3_PIN, HIGH);
break;
#endif
default:
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_INVALID_SOLENOID);
break;
}
}
void enable_solenoid_on_active_extruder() { enable_solenoid(active_extruder); }
void disable_all_solenoids() {
OUT_WRITE(SOL0_PIN, LOW);
OUT_WRITE(SOL1_PIN, LOW);
OUT_WRITE(SOL2_PIN, LOW);
OUT_WRITE(SOL3_PIN, LOW);
}
/**
* M380: Enable solenoid on the active extruder
*/
inline void gcode_M380() { enable_solenoid_on_active_extruder(); }
/**
* M381: Disable all solenoids
*/
inline void gcode_M381() { disable_all_solenoids(); }
#endif // EXT_SOLENOID
/**
* M400: Finish all moves
*/
inline void gcode_M400() { stepper.synchronize(); }
#if HAS_BED_PROBE
/**
* M401: Engage Z Servo endstop if available
*/
inline void gcode_M401() { DEPLOY_PROBE(); }
2015-04-16 09:24:33 -05:00
/**
* M402: Retract Z Servo endstop if enabled
*/
inline void gcode_M402() { STOW_PROBE(); }
#endif // HAS_BED_PROBE
#if ENABLED(FILAMENT_WIDTH_SENSOR)
/**
* M404: Display or set (in current units) the nominal filament width (3mm, 1.75mm ) W<3.0>
*/
inline void gcode_M404() {
2016-03-29 22:43:41 -05:00
if (code_seen('W')) {
filament_width_nominal = code_value_linear_units();
2016-03-29 22:43:41 -05:00
}
else {
SERIAL_PROTOCOLPGM("Filament dia (nominal mm):");
SERIAL_PROTOCOLLN(filament_width_nominal);
}
}
2015-08-05 06:40:36 -05:00
/**
* M405: Turn on filament sensor for control
*/
inline void gcode_M405() {
// This is technically a linear measurement, but since it's quantized to centimeters and is a different unit than
// everything else, it uses code_value_int() instead of code_value_linear_units().
if (code_seen('D')) meas_delay_cm = code_value_int();
NOMORE(meas_delay_cm, MAX_MEASUREMENT_DELAY);
if (filwidth_delay_index2 == -1) { // Initialize the ring buffer if not done since startup
2016-04-28 20:18:13 -05:00
int temp_ratio = thermalManager.widthFil_to_size_ratio();
for (uint8_t i = 0; i < COUNT(measurement_delay); ++i)
measurement_delay[i] = temp_ratio - 100; // Subtract 100 to scale within a signed byte
filwidth_delay_index1 = filwidth_delay_index2 = 0;
}
filament_sensor = true;
//SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
//SERIAL_PROTOCOL(filament_width_meas);
//SERIAL_PROTOCOLPGM("Extrusion ratio(%):");
2016-08-18 22:13:47 -05:00
//SERIAL_PROTOCOL(flow_percentage[active_extruder]);
}
/**
* M406: Turn off filament sensor for control
*/
inline void gcode_M406() { filament_sensor = false; }
2015-08-05 06:40:36 -05:00
/**
* M407: Get measured filament diameter on serial output
*/
inline void gcode_M407() {
2015-08-05 06:40:36 -05:00
SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
SERIAL_PROTOCOLLN(filament_width_meas);
}
#endif // FILAMENT_WIDTH_SENSOR
void quickstop_stepper() {
stepper.quick_stop();
#if DISABLED(SCARA)
2016-06-02 19:11:54 -05:00
stepper.synchronize();
2016-07-23 15:11:18 -05:00
LOOP_XYZ(i) set_current_from_steppers_for_axis((AxisEnum)i);
SYNC_PLAN_POSITION_KINEMATIC();
2016-06-02 19:11:54 -05:00
#endif
}
2015-04-19 01:07:48 -05:00
#if ENABLED(MESH_BED_LEVELING)
/**
* M420: Enable/Disable Mesh Bed Leveling
*/
inline void gcode_M420() { if (code_seen('S') && code_has_value()) mbl.set_has_mesh(code_value_bool()); }
/**
* M421: Set a single Mesh Bed Leveling Z coordinate
* Use either 'M421 X<linear> Y<linear> Z<linear>' or 'M421 I<xindex> J<yindex> Z<linear>'
*/
inline void gcode_M421() {
2016-04-30 04:51:18 -05:00
int8_t px = 0, py = 0;
2016-05-21 21:06:27 -05:00
float z = 0;
bool hasX, hasY, hasZ, hasI, hasJ;
if ((hasX = code_seen('X'))) px = mbl.probe_index_x(code_value_axis_units(X_AXIS));
if ((hasY = code_seen('Y'))) py = mbl.probe_index_y(code_value_axis_units(Y_AXIS));
if ((hasI = code_seen('I'))) px = code_value_axis_units(X_AXIS);
if ((hasJ = code_seen('J'))) py = code_value_axis_units(Y_AXIS);
if ((hasZ = code_seen('Z'))) z = code_value_axis_units(Z_AXIS);
2016-05-14 19:12:44 -05:00
if (hasX && hasY && hasZ) {
2016-05-21 19:38:14 -05:00
if (px >= 0 && py >= 0)
mbl.set_z(px, py, z);
2016-05-14 19:12:44 -05:00
else {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY);
}
}
else if (hasI && hasJ && hasZ) {
2016-05-21 19:38:14 -05:00
if (px >= 0 && px < MESH_NUM_X_POINTS && py >= 0 && py < MESH_NUM_Y_POINTS)
mbl.set_z(px, py, z);
else {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY);
}
}
2016-05-21 19:38:14 -05:00
else {
SERIAL_ERROR_START;
2016-05-21 21:06:27 -05:00
SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS);
}
}
#endif
2015-04-29 20:26:16 -05:00
/**
* M428: Set home_offset based on the distance between the
* current_position and the nearest "reference point."
* If an axis is past center its endstop position
2015-04-29 20:26:16 -05:00
* is the reference-point. Otherwise it uses 0. This allows
* the Z offset to be set near the bed when using a max endstop.
*
* M428 can't be used more than 2cm away from 0 or an endstop.
*
2015-04-29 20:26:16 -05:00
* Use M206 to set these values directly.
*/
inline void gcode_M428() {
bool err = false;
2016-07-23 15:07:23 -05:00
LOOP_XYZ(i) {
if (axis_homed[i]) {
float base = (current_position[i] > (soft_endstop_min[i] + soft_endstop_max[i]) * 0.5) ? base_home_pos(i) : 0,
diff = current_position[i] - LOGICAL_POSITION(base, i);
if (diff > -20 && diff < 20) {
set_home_offset((AxisEnum)i, home_offset[i] - diff);
}
else {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_M428_TOO_FAR);
LCD_ALERTMESSAGEPGM("Err: Too far!");
2016-08-01 23:10:53 -05:00
BUZZ(200, 40);
err = true;
break;
}
2015-04-29 20:26:16 -05:00
}
}
if (!err) {
SYNC_PLAN_POSITION_KINEMATIC();
report_current_position();
LCD_MESSAGEPGM(MSG_HOME_OFFSETS_APPLIED);
2016-08-01 23:10:53 -05:00
BUZZ(200, 659);
BUZZ(200, 698);
}
2015-04-29 20:26:16 -05:00
}
/**
* M500: Store settings in EEPROM
*/
inline void gcode_M500() {
Config_StoreSettings();
}
/**
* M501: Read settings from EEPROM
*/
inline void gcode_M501() {
Config_RetrieveSettings();
}
/**
* M502: Revert to default settings
*/
inline void gcode_M502() {
Config_ResetDefault();
}
/**
* M503: print settings currently in memory
*/
inline void gcode_M503() {
Config_PrintSettings(code_seen('S') && !code_value_bool());
}
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
/**
* M540: Set whether SD card print should abort on endstop hit (M540 S<0|1>)
*/
inline void gcode_M540() {
if (code_seen('S')) stepper.abort_on_endstop_hit = code_value_bool();
}
#endif // ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
2016-06-14 20:05:20 -05:00
#if HAS_BED_PROBE
2016-06-14 20:05:20 -05:00
inline void gcode_M851() {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_ZPROBE_ZOFFSET);
SERIAL_CHAR(' ');
if (code_seen('Z')) {
float value = code_value_axis_units(Z_AXIS);
if (Z_PROBE_OFFSET_RANGE_MIN <= value && value <= Z_PROBE_OFFSET_RANGE_MAX) {
zprobe_zoffset = value;
SERIAL_ECHO(zprobe_zoffset);
}
else {
SERIAL_ECHOPGM(MSG_Z_MIN);
SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MIN);
SERIAL_CHAR(' ');
SERIAL_ECHOPGM(MSG_Z_MAX);
SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MAX);
}
}
else {
SERIAL_ECHOPAIR(": ", zprobe_zoffset);
}
SERIAL_EOL;
}
2016-06-14 20:05:20 -05:00
#endif // HAS_BED_PROBE
#if ENABLED(FILAMENT_CHANGE_FEATURE)
/**
2015-06-15 19:54:41 -05:00
* M600: Pause for filament change
*
* E[distance] - Retract the filament this far (negative value)
* Z[distance] - Move the Z axis by this distance
* X[position] - Move to this X position, with Y
* Y[position] - Move to this Y position, with X
* L[distance] - Retract distance for removal (manual reload)
*
* Default values are used for omitted arguments.
*
*/
inline void gcode_M600() {
2016-04-28 20:18:13 -05:00
if (thermalManager.tooColdToExtrude(active_extruder)) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_TOO_COLD_FOR_M600);
return;
}
// Show initial message and wait for synchronize steppers
lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_INIT);
stepper.synchronize();
2016-04-02 16:28:17 -05:00
float lastpos[NUM_AXIS];
// Save current position of all axes
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i)
lastpos[i] = destination[i] = current_position[i];
// Define runplan for move axes
#if ENABLED(DELTA)
2016-07-21 17:46:22 -05:00
#define RUNPLAN(RATE_MM_S) inverse_kinematics(destination); \
2016-07-15 20:49:34 -05:00
planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], RATE_MM_S, active_extruder);
#else
#define RUNPLAN(RATE_MM_S) line_to_destination(RATE_MM_S);
#endif
KEEPALIVE_STATE(IN_HANDLER);
// Initial retract before move to filament change position
if (code_seen('E')) destination[E_AXIS] += code_value_axis_units(E_AXIS);
#if defined(FILAMENT_CHANGE_RETRACT_LENGTH) && FILAMENT_CHANGE_RETRACT_LENGTH > 0
else destination[E_AXIS] -= FILAMENT_CHANGE_RETRACT_LENGTH;
#endif
RUNPLAN(FILAMENT_CHANGE_RETRACT_FEEDRATE);
// Lift Z axis
float z_lift = code_seen('Z') ? code_value_axis_units(Z_AXIS) :
#if defined(FILAMENT_CHANGE_Z_ADD) && FILAMENT_CHANGE_Z_ADD > 0
FILAMENT_CHANGE_Z_ADD
#else
0
#endif
;
if (z_lift > 0) {
destination[Z_AXIS] += z_lift;
NOMORE(destination[Z_AXIS], Z_MAX_POS);
RUNPLAN(FILAMENT_CHANGE_Z_FEEDRATE);
}
// Move XY axes to filament exchange position
if (code_seen('X')) destination[X_AXIS] = code_value_axis_units(X_AXIS);
#ifdef FILAMENT_CHANGE_X_POS
else destination[X_AXIS] = FILAMENT_CHANGE_X_POS;
#endif
if (code_seen('Y')) destination[Y_AXIS] = code_value_axis_units(Y_AXIS);
#ifdef FILAMENT_CHANGE_Y_POS
else destination[Y_AXIS] = FILAMENT_CHANGE_Y_POS;
#endif
RUNPLAN(FILAMENT_CHANGE_XY_FEEDRATE);
stepper.synchronize();
lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_UNLOAD);
// Unload filament
if (code_seen('L')) destination[E_AXIS] += code_value_axis_units(E_AXIS);
#if defined(FILAMENT_CHANGE_UNLOAD_LENGTH) && FILAMENT_CHANGE_UNLOAD_LENGTH > 0
else destination[E_AXIS] -= FILAMENT_CHANGE_UNLOAD_LENGTH;
#endif
RUNPLAN(FILAMENT_CHANGE_UNLOAD_FEEDRATE);
// Synchronize steppers and then disable extruders steppers for manual filament changing
stepper.synchronize();
disable_e0();
disable_e1();
disable_e2();
disable_e3();
delay(100);
2016-04-30 04:51:18 -05:00
#if HAS_BUZZER
millis_t next_tick = 0;
#endif
// Wait for filament insert by user and press button
lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_INSERT);
while (!lcd_clicked()) {
#if HAS_BUZZER
millis_t ms = millis();
if (ms >= next_tick) {
2016-08-01 23:10:53 -05:00
BUZZ(300, 2000);
next_tick = ms + 2500; // Beep every 2.5s while waiting
}
#endif
idle(true);
}
delay(100);
while (lcd_clicked()) idle(true);
delay(100);
// Show load message
lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_LOAD);
2015-08-05 06:40:36 -05:00
// Load filament
if (code_seen('L')) destination[E_AXIS] -= code_value_axis_units(E_AXIS);
#if defined(FILAMENT_CHANGE_LOAD_LENGTH) && FILAMENT_CHANGE_LOAD_LENGTH > 0
else destination[E_AXIS] += FILAMENT_CHANGE_LOAD_LENGTH;
#endif
RUNPLAN(FILAMENT_CHANGE_LOAD_FEEDRATE);
stepper.synchronize();
#if defined(FILAMENT_CHANGE_EXTRUDE_LENGTH) && FILAMENT_CHANGE_EXTRUDE_LENGTH > 0
do {
// Extrude filament to get into hotend
lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_EXTRUDE);
destination[E_AXIS] += FILAMENT_CHANGE_EXTRUDE_LENGTH;
RUNPLAN(FILAMENT_CHANGE_EXTRUDE_FEEDRATE);
stepper.synchronize();
// Ask user if more filament should be extruded
KEEPALIVE_STATE(PAUSED_FOR_USER);
lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_OPTION);
while (filament_change_menu_response == FILAMENT_CHANGE_RESPONSE_WAIT_FOR) idle(true);
KEEPALIVE_STATE(IN_HANDLER);
} while (filament_change_menu_response != FILAMENT_CHANGE_RESPONSE_RESUME_PRINT);
#endif
lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_RESUME);
KEEPALIVE_STATE(IN_HANDLER);
// Set extruder to saved position
current_position[E_AXIS] = lastpos[E_AXIS];
destination[E_AXIS] = lastpos[E_AXIS];
planner.set_e_position_mm(current_position[E_AXIS]);
#if ENABLED(DELTA)
2015-06-15 19:54:41 -05:00
// Move XYZ to starting position, then E
2016-07-21 17:46:22 -05:00
inverse_kinematics(lastpos);
planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], FILAMENT_CHANGE_XY_FEEDRATE, active_extruder);
planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], lastpos[E_AXIS], FILAMENT_CHANGE_XY_FEEDRATE, active_extruder);
#else
// Move XY to starting position, then Z, then E
destination[X_AXIS] = lastpos[X_AXIS];
destination[Y_AXIS] = lastpos[Y_AXIS];
RUNPLAN(FILAMENT_CHANGE_XY_FEEDRATE);
destination[Z_AXIS] = lastpos[Z_AXIS];
RUNPLAN(FILAMENT_CHANGE_Z_FEEDRATE);
2015-08-05 06:40:36 -05:00
#endif
stepper.synchronize();
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
2016-04-18 01:16:49 -05:00
filament_ran_out = false;
#endif
2015-08-05 06:40:36 -05:00
// Show status screen
lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_STATUS);
}
#endif // FILAMENT_CHANGE_FEATURE
#if ENABLED(DUAL_X_CARRIAGE)
/**
* M605: Set dual x-carriage movement mode
*
* M605 S0: Full control mode. The slicer has full control over x-carriage movement
* M605 S1: Auto-park mode. The inactive head will auto park/unpark without slicer involvement
* M605 S2 [Xnnn] [Rmmm]: Duplication mode. The second extruder will duplicate the first with nnn
* units x-offset and an optional differential hotend temperature of
* mmm degrees. E.g., with "M605 S2 X100 R2" the second extruder will duplicate
* the first with a spacing of 100mm in the x direction and 2 degrees hotter.
*
* Note: the X axis should be homed after changing dual x-carriage mode.
*/
inline void gcode_M605() {
stepper.synchronize();
if (code_seen('S')) dual_x_carriage_mode = code_value_byte();
switch (dual_x_carriage_mode) {
case DXC_DUPLICATION_MODE:
if (code_seen('X')) duplicate_extruder_x_offset = max(code_value_axis_units(X_AXIS), X2_MIN_POS - x_home_pos(0));
if (code_seen('R')) duplicate_extruder_temp_offset = code_value_temp_diff();
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_HOTEND_OFFSET);
2015-04-03 23:43:30 -05:00
SERIAL_CHAR(' ');
2016-05-26 19:43:20 -05:00
SERIAL_ECHO(hotend_offset[X_AXIS][0]);
2015-04-03 23:43:30 -05:00
SERIAL_CHAR(',');
2016-05-26 19:43:20 -05:00
SERIAL_ECHO(hotend_offset[Y_AXIS][0]);
2015-04-03 23:43:30 -05:00
SERIAL_CHAR(' ');
SERIAL_ECHO(duplicate_extruder_x_offset);
2015-04-03 23:43:30 -05:00
SERIAL_CHAR(',');
2016-05-26 19:43:20 -05:00
SERIAL_ECHOLN(hotend_offset[Y_AXIS][1]);
break;
case DXC_FULL_CONTROL_MODE:
case DXC_AUTO_PARK_MODE:
break;
default:
dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
break;
}
active_extruder_parked = false;
extruder_duplication_enabled = false;
delayed_move_time = 0;
}
2016-07-20 12:30:10 -05:00
#elif ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
inline void gcode_M605() {
stepper.synchronize();
extruder_duplication_enabled = code_seen('S') && code_value_int() == 2;
SERIAL_ECHO_START;
2016-08-20 20:11:08 -05:00
SERIAL_ECHOLNPAIR(MSG_DUPLICATION_MODE, extruder_duplication_enabled ? MSG_ON : MSG_OFF);
2016-07-20 12:30:10 -05:00
}
#endif // M605
2016-05-04 11:53:17 -05:00
#if ENABLED(LIN_ADVANCE)
/**
* M905: Set advance factor
*/
inline void gcode_M905() {
stepper.synchronize();
2016-06-13 21:25:05 -05:00
stepper.advance_M905(code_seen('K') ? code_value_float() : -1.0);
}
2016-05-04 11:53:17 -05:00
#endif
/**
* M907: Set digital trimpot motor current using axis codes X, Y, Z, E, B, S
*/
inline void gcode_M907() {
#if HAS_DIGIPOTSS
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i)
if (code_seen(axis_codes[i])) stepper.digipot_current(i, code_value_int());
if (code_seen('B')) stepper.digipot_current(4, code_value_int());
if (code_seen('S')) for (int i = 0; i <= 4; i++) stepper.digipot_current(i, code_value_int());
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_XY)
if (code_seen('X')) stepper.digipot_current(0, code_value_int());
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
if (code_seen('Z')) stepper.digipot_current(1, code_value_int());
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
if (code_seen('E')) stepper.digipot_current(2, code_value_int());
#endif
#if ENABLED(DIGIPOT_I2C)
// this one uses actual amps in floating point
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) if (code_seen(axis_codes[i])) digipot_i2c_set_current(i, code_value_float());
// for each additional extruder (named B,C,D,E..., channels 4,5,6,7...)
for (int i = NUM_AXIS; i < DIGIPOT_I2C_NUM_CHANNELS; i++) if (code_seen('B' + i - (NUM_AXIS))) digipot_i2c_set_current(i, code_value_float());
#endif
#if ENABLED(DAC_STEPPER_CURRENT)
if (code_seen('S')) {
float dac_percent = code_value_float();
for (uint8_t i = 0; i <= 4; i++) dac_current_percent(i, dac_percent);
}
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) if (code_seen(axis_codes[i])) dac_current_percent(i, code_value_float());
#endif
}
#if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT)
/**
* M908: Control digital trimpot directly (M908 P<pin> S<current>)
*/
inline void gcode_M908() {
#if HAS_DIGIPOTSS
stepper.digitalPotWrite(
code_seen('P') ? code_value_int() : 0,
code_seen('S') ? code_value_int() : 0
);
#endif
#ifdef DAC_STEPPER_CURRENT
dac_current_raw(
code_seen('P') ? code_value_byte() : -1,
code_seen('S') ? code_value_ushort() : 0
);
#endif
}
#if ENABLED(DAC_STEPPER_CURRENT) // As with Printrbot RevF
inline void gcode_M909() { dac_print_values(); }
inline void gcode_M910() { dac_commit_eeprom(); }
#endif
#endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT
2015-04-03 17:31:35 -05:00
#if HAS_MICROSTEPS
// M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
inline void gcode_M350() {
if (code_seen('S')) for (int i = 0; i <= 4; i++) stepper.microstep_mode(i, code_value_byte());
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) if (code_seen(axis_codes[i])) stepper.microstep_mode(i, code_value_byte());
if (code_seen('B')) stepper.microstep_mode(4, code_value_byte());
stepper.microstep_readings();
2015-04-03 17:31:35 -05:00
}
2015-04-03 17:31:35 -05:00
/**
* M351: Toggle MS1 MS2 pins directly with axis codes X Y Z E B
* S# determines MS1 or MS2, X# sets the pin high/low.
*/
inline void gcode_M351() {
if (code_seen('S')) switch (code_value_byte()) {
case 1:
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) if (code_seen(axis_codes[i])) stepper.microstep_ms(i, code_value_byte(), -1);
if (code_seen('B')) stepper.microstep_ms(4, code_value_byte(), -1);
break;
case 2:
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) if (code_seen(axis_codes[i])) stepper.microstep_ms(i, -1, code_value_byte());
if (code_seen('B')) stepper.microstep_ms(4, -1, code_value_byte());
break;
}
stepper.microstep_readings();
2015-04-03 17:31:35 -05:00
}
#endif // HAS_MICROSTEPS
#if ENABLED(MIXING_EXTRUDER)
/**
* M163: Set a single mix factor for a mixing extruder
* This is called "weight" by some systems.
*
* S[index] The channel index to set
* P[float] The mix value
*
*/
inline void gcode_M163() {
int mix_index = code_seen('S') ? code_value_int() : 0;
float mix_value = code_seen('P') ? code_value_float() : 0.0;
if (mix_index < MIXING_STEPPERS) mixing_factor[mix_index] = mix_value;
}
#if MIXING_VIRTUAL_TOOLS > 1
/**
* M164: Store the current mix factors as a virtual tool.
*
* S[index] The virtual tool to store
*
*/
inline void gcode_M164() {
int tool_index = code_seen('S') ? code_value_int() : 0;
if (tool_index < MIXING_VIRTUAL_TOOLS) {
normalize_mix();
for (uint8_t i = 0; i < MIXING_STEPPERS; i++)
mixing_virtual_tool_mix[tool_index][i] = mixing_factor[i];
}
}
#endif
#if ENABLED(DIRECT_MIXING_IN_G1)
/**
* M165: Set multiple mix factors for a mixing extruder.
* Factors that are left out will be set to 0.
* All factors together must add up to 1.0.
*
* A[factor] Mix factor for extruder stepper 1
* B[factor] Mix factor for extruder stepper 2
* C[factor] Mix factor for extruder stepper 3
* D[factor] Mix factor for extruder stepper 4
* H[factor] Mix factor for extruder stepper 5
* I[factor] Mix factor for extruder stepper 6
*
*/
inline void gcode_M165() { gcode_get_mix(); }
#endif
#endif // MIXING_EXTRUDER
/**
* M999: Restart after being stopped
2016-05-18 18:13:33 -05:00
*
* Default behaviour is to flush the serial buffer and request
* a resend to the host starting on the last N line received.
*
* Sending "M999 S1" will resume printing without flushing the
* existing command buffer.
*
*/
inline void gcode_M999() {
2015-04-08 02:56:19 -05:00
Running = true;
lcd_reset_alert_level();
2016-05-18 18:13:33 -05:00
if (code_seen('S') && code_value_bool()) return;
2016-05-18 18:13:33 -05:00
// gcode_LastN = Stopped_gcode_LastN;
FlushSerialRequestResend();
}
#if ENABLED(SWITCHING_EXTRUDER)
inline void move_extruder_servo(uint8_t e) {
const int angles[2] = SWITCHING_EXTRUDER_SERVO_ANGLES;
MOVE_SERVO(SWITCHING_EXTRUDER_SERVO_NR, angles[e]);
}
#endif
inline void invalid_extruder_error(const uint8_t &e) {
SERIAL_ECHO_START;
SERIAL_CHAR('T');
SERIAL_PROTOCOL_F(e, DEC);
SERIAL_ECHOLN(MSG_INVALID_EXTRUDER);
}
void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool no_move/*=false*/) {
#if ENABLED(MIXING_EXTRUDER) && MIXING_VIRTUAL_TOOLS > 1
if (tmp_extruder >= MIXING_VIRTUAL_TOOLS) {
invalid_extruder_error(tmp_extruder);
return;
}
// T0-Tnnn: Switch virtual tool by changing the mix
for (uint8_t j = 0; j < MIXING_STEPPERS; j++)
mixing_factor[j] = mixing_virtual_tool_mix[tmp_extruder][j];
#else //!MIXING_EXTRUDER || MIXING_VIRTUAL_TOOLS <= 1
2016-06-16 02:05:36 -05:00
#if HOTENDS > 1
if (tmp_extruder >= EXTRUDERS) {
invalid_extruder_error(tmp_extruder);
return;
}
float old_feedrate_mm_s = feedrate_mm_s;
feedrate_mm_s = fr_mm_s > 0.0 ? (old_feedrate_mm_s = fr_mm_s) : XY_PROBE_FEEDRATE_MM_S;
if (tmp_extruder != active_extruder) {
if (!no_move && axis_unhomed_error(true, true, true)) {
SERIAL_ECHOLNPGM("No move on toolchange");
no_move = true;
}
// Save current position to destination, for use later
set_destination_to_current();
#if ENABLED(DUAL_X_CARRIAGE)
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOPGM("Dual X Carriage Mode ");
switch (dual_x_carriage_mode) {
case DXC_DUPLICATION_MODE: SERIAL_ECHOLNPGM("DXC_DUPLICATION_MODE"); break;
case DXC_AUTO_PARK_MODE: SERIAL_ECHOLNPGM("DXC_AUTO_PARK_MODE"); break;
case DXC_FULL_CONTROL_MODE: SERIAL_ECHOLNPGM("DXC_FULL_CONTROL_MODE"); break;
}
}
#endif
2015-04-03 23:43:30 -05:00
if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE && IsRunning() &&
(delayed_move_time || current_position[X_AXIS] != x_home_pos(active_extruder))
) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOPAIR("Raise to ", current_position[Z_AXIS] + TOOLCHANGE_PARK_ZLIFT); SERIAL_EOL;
SERIAL_ECHOPAIR("MoveX to ", x_home_pos(active_extruder)); SERIAL_EOL;
SERIAL_ECHOPAIR("Lower to ", current_position[Z_AXIS]); SERIAL_EOL;
}
#endif
// Park old head: 1) raise 2) move to park position 3) lower
for (uint8_t i = 0; i < 3; i++)
planner.buffer_line(
i == 0 ? current_position[X_AXIS] : x_home_pos(active_extruder),
current_position[Y_AXIS],
current_position[Z_AXIS] + (i == 2 ? 0 : TOOLCHANGE_PARK_ZLIFT),
current_position[E_AXIS],
2016-07-15 20:49:34 -05:00
planner.max_feedrate_mm_s[i == 1 ? X_AXIS : Z_AXIS],
active_extruder
);
stepper.synchronize();
}
2015-04-03 23:43:30 -05:00
// apply Y & Z extruder offset (x offset is already used in determining home pos)
current_position[Y_AXIS] -= hotend_offset[Y_AXIS][active_extruder] - hotend_offset[Y_AXIS][tmp_extruder];
current_position[Z_AXIS] -= hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][tmp_extruder];
active_extruder = tmp_extruder;
// This function resets the max/min values - the current position may be overwritten below.
set_axis_is_at_home(X_AXIS);
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("New Extruder", current_position);
#endif
switch (dual_x_carriage_mode) {
case DXC_FULL_CONTROL_MODE:
current_position[X_AXIS] = LOGICAL_X_POSITION(inactive_extruder_x_pos);
inactive_extruder_x_pos = RAW_X_POSITION(destination[X_AXIS]);
break;
case DXC_DUPLICATION_MODE:
active_extruder_parked = (active_extruder == 0); // this triggers the second extruder to move into the duplication position
if (active_extruder_parked)
current_position[X_AXIS] = LOGICAL_X_POSITION(inactive_extruder_x_pos);
else
current_position[X_AXIS] = destination[X_AXIS] + duplicate_extruder_x_offset;
inactive_extruder_x_pos = RAW_X_POSITION(destination[X_AXIS]);
extruder_duplication_enabled = false;
break;
default:
// record raised toolhead position for use by unpark
memcpy(raised_parked_position, current_position, sizeof(raised_parked_position));
raised_parked_position[Z_AXIS] += TOOLCHANGE_UNPARK_ZLIFT;
active_extruder_parked = true;
delayed_move_time = 0;
break;
}
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOLNPAIR("Active extruder parked: ", active_extruder_parked ? "yes" : "no");
DEBUG_POS("New extruder (parked)", current_position);
}
#endif
// No extra case for AUTO_BED_LEVELING_FEATURE in DUAL_X_CARRIAGE. Does that mean they don't work together?
#else // !DUAL_X_CARRIAGE
#if ENABLED(SWITCHING_EXTRUDER)
// <0 if the new nozzle is higher, >0 if lower. A bigger raise when lower.
float z_diff = hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][tmp_extruder],
z_raise = 0.3 + (z_diff > 0.0 ? z_diff : 0.0);
// Always raise by some amount
planner.buffer_line(
current_position[X_AXIS],
current_position[Y_AXIS],
current_position[Z_AXIS] + z_raise,
current_position[E_AXIS],
2016-07-15 20:49:34 -05:00
planner.max_feedrate_mm_s[Z_AXIS],
active_extruder
);
stepper.synchronize();
move_extruder_servo(active_extruder);
delay(500);
// Move back down, if needed
if (z_raise != z_diff) {
planner.buffer_line(
current_position[X_AXIS],
current_position[Y_AXIS],
current_position[Z_AXIS] + z_diff,
current_position[E_AXIS],
2016-07-15 20:49:34 -05:00
planner.max_feedrate_mm_s[Z_AXIS],
active_extruder
);
stepper.synchronize();
}
#endif
/**
* Set current_position to the position of the new nozzle.
* Offsets are based on linear distance, so we need to get
* the resulting position in coordinate space.
*
* - With grid or 3-point leveling, offset XYZ by a tilted vector
* - With mesh leveling, update Z for the new position
* - Otherwise, just use the raw linear distance
*
* Software endstops are altered here too. Consider a case where:
* E0 at X=0 ... E1 at X=10
* When we switch to E1 now X=10, but E1 can't move left.
* To express this we apply the change in XY to the software endstops.
* E1 can move farther right than E0, so the right limit is extended.
*
* Note that we don't adjust the Z software endstops. Why not?
* Consider a case where Z=0 (here) and switching to E1 makes Z=1
* because the bed is 1mm lower at the new position. As long as
* the first nozzle is out of the way, the carriage should be
* allowed to move 1mm lower. This technically "breaks" the
* Z software endstop. But this is technically correct (and
* there is no viable alternative).
*/
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
// Offset extruder, make sure to apply the bed level rotation matrix
vector_3 tmp_offset_vec = vector_3(hotend_offset[X_AXIS][tmp_extruder],
hotend_offset[Y_AXIS][tmp_extruder],
0),
act_offset_vec = vector_3(hotend_offset[X_AXIS][active_extruder],
hotend_offset[Y_AXIS][active_extruder],
0),
offset_vec = tmp_offset_vec - act_offset_vec;
2016-04-11 22:30:00 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
tmp_offset_vec.debug("tmp_offset_vec");
act_offset_vec.debug("act_offset_vec");
offset_vec.debug("offset_vec (BEFORE)");
}
#endif
offset_vec.apply_rotation(planner.bed_level_matrix.transpose(planner.bed_level_matrix));
2016-04-27 21:35:55 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) offset_vec.debug("offset_vec (AFTER)");
#endif
// Adjustments to the current position
float xydiff[2] = { offset_vec.x, offset_vec.y };
current_position[Z_AXIS] += offset_vec.z;
#else // !AUTO_BED_LEVELING_FEATURE
float xydiff[2] = {
hotend_offset[X_AXIS][tmp_extruder] - hotend_offset[X_AXIS][active_extruder],
hotend_offset[Y_AXIS][tmp_extruder] - hotend_offset[Y_AXIS][active_extruder]
};
2016-04-27 21:35:55 -05:00
#if ENABLED(MESH_BED_LEVELING)
2016-04-27 21:35:55 -05:00
if (mbl.active()) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) SERIAL_ECHOPAIR("Z before MBL: ", current_position[Z_AXIS]);
#endif
float xpos = RAW_CURRENT_POSITION(X_AXIS),
ypos = RAW_CURRENT_POSITION(Y_AXIS);
current_position[Z_AXIS] += mbl.get_z(xpos + xydiff[X_AXIS], ypos + xydiff[Y_AXIS]) - mbl.get_z(xpos, ypos);
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING))
SERIAL_ECHOLNPAIR(" after: ", current_position[Z_AXIS]);
#endif
}
2016-06-11 14:59:44 -05:00
#endif // MESH_BED_LEVELING
#endif // !AUTO_BED_LEVELING_FEATURE
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOPAIR("Offset Tool XY by { ", xydiff[X_AXIS]);
2016-07-17 19:04:32 -05:00
SERIAL_ECHOPAIR(", ", xydiff[Y_AXIS]);
SERIAL_ECHOLNPGM(" }");
}
#endif
2016-04-27 21:35:55 -05:00
// The newly-selected extruder XY is actually at...
current_position[X_AXIS] += xydiff[X_AXIS];
current_position[Y_AXIS] += xydiff[Y_AXIS];
for (uint8_t i = X_AXIS; i <= Y_AXIS; i++) {
position_shift[i] += xydiff[i];
update_software_endstops((AxisEnum)i);
}
2016-04-27 21:35:55 -05:00
// Set the new active extruder
active_extruder = tmp_extruder;
2016-04-27 21:35:55 -05:00
#endif // !DUAL_X_CARRIAGE
2016-04-27 21:35:55 -05:00
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("Sync After Toolchange", current_position);
#endif
2016-04-27 21:35:55 -05:00
// Tell the planner the new "current position"
SYNC_PLAN_POSITION_KINEMATIC();
2016-04-11 22:30:00 -05:00
// Move to the "old position" (move the extruder into place)
if (!no_move && IsRunning()) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) DEBUG_POS("Move back", destination);
#endif
prepare_move_to_destination();
}
} // (tmp_extruder != active_extruder)
2016-04-11 22:30:00 -05:00
stepper.synchronize();
2016-06-16 02:05:36 -05:00
#if ENABLED(EXT_SOLENOID)
disable_all_solenoids();
enable_solenoid_on_active_extruder();
#endif // EXT_SOLENOID
feedrate_mm_s = old_feedrate_mm_s;
2016-06-16 02:05:36 -05:00
#else // HOTENDS <= 1
// Set the new active extruder
active_extruder = tmp_extruder;
UNUSED(fr_mm_s);
2016-07-22 10:08:56 -05:00
UNUSED(no_move);
#endif // HOTENDS <= 1
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_ACTIVE_EXTRUDER);
SERIAL_PROTOCOLLN((int)active_extruder);
#endif //!MIXING_EXTRUDER || MIXING_VIRTUAL_TOOLS <= 1
}
2016-07-19 21:37:31 -05:00
/**
* T0-T3: Switch tool, usually switching extruders
*
* F[units/min] Set the movement feedrate
* S1 Don't move the tool in XY after change
*/
inline void gcode_T(uint8_t tmp_extruder) {
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
SERIAL_ECHOPAIR(">>> gcode_T(", tmp_extruder);
SERIAL_ECHOLNPGM(")");
DEBUG_POS("BEFORE", current_position);
}
#endif
#if HOTENDS == 1 || (ENABLED(MIXING_EXTRUDER) && MIXING_VIRTUAL_TOOLS > 1)
tool_change(tmp_extruder);
#elif HOTENDS > 1
tool_change(
tmp_extruder,
code_seen('F') ? MMM_TO_MMS(code_value_axis_units(X_AXIS)) : 0.0,
2016-07-19 21:37:31 -05:00
(tmp_extruder == active_extruder) || (code_seen('S') && code_value_bool())
);
#endif
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (DEBUGGING(LEVELING)) {
DEBUG_POS("AFTER", current_position);
SERIAL_ECHOLNPGM("<<< gcode_T");
}
#endif
}
/**
* Process a single command and dispatch it to its handler
2015-04-03 17:31:35 -05:00
* This is called from the main loop()
*/
void process_next_command() {
current_command = command_queue[cmd_queue_index_r];
2016-03-29 21:50:01 -05:00
if (DEBUGGING(ECHO)) {
SERIAL_ECHO_START;
SERIAL_ECHOLN(current_command);
}
// Sanitize the current command:
// - Skip leading spaces
2016-02-09 20:16:35 -06:00
// - Bypass N[-0-9][0-9]*[ ]*
// - Overwrite * with nul to mark the end
while (*current_command == ' ') ++current_command;
if (*current_command == 'N' && NUMERIC_SIGNED(current_command[1])) {
current_command += 2; // skip N[-0-9]
while (NUMERIC(*current_command)) ++current_command; // skip [0-9]*
while (*current_command == ' ') ++current_command; // skip [ ]*
}
char* starpos = strchr(current_command, '*'); // * should always be the last parameter
if (starpos) while (*starpos == ' ' || *starpos == '*') *starpos-- = '\0'; // nullify '*' and ' '
char *cmd_ptr = current_command;
2015-05-17 07:00:09 -05:00
// Get the command code, which must be G, M, or T
char command_code = *cmd_ptr++;
// Skip spaces to get the numeric part
while (*cmd_ptr == ' ') cmd_ptr++;
2016-03-28 05:53:09 -05:00
uint16_t codenum = 0; // define ahead of goto
2016-03-28 05:53:09 -05:00
// Bail early if there's no code
bool code_is_good = NUMERIC(*cmd_ptr);
if (!code_is_good) goto ExitUnknownCommand;
// Get and skip the code number
2016-03-28 05:53:09 -05:00
do {
codenum = (codenum * 10) + (*cmd_ptr - '0');
cmd_ptr++;
2016-03-28 05:53:09 -05:00
} while (NUMERIC(*cmd_ptr));
2016-03-28 05:53:09 -05:00
// Skip all spaces to get to the first argument, or nul
while (*cmd_ptr == ' ') cmd_ptr++;
2016-03-28 05:53:09 -05:00
// The command's arguments (if any) start here, for sure!
current_command_args = cmd_ptr;
KEEPALIVE_STATE(IN_HANDLER);
// Handle a known G, M, or T
switch (command_code) {
2015-05-17 07:00:09 -05:00
case 'G': switch (codenum) {
2015-05-22 19:31:24 -05:00
// G0, G1
case 0:
case 1:
gcode_G0_G1();
break;
2015-05-22 19:31:38 -05:00
// G2, G3
#if ENABLED(ARC_SUPPORT) && DISABLED(SCARA)
2015-05-22 19:31:38 -05:00
case 2: // G2 - CW ARC
case 3: // G3 - CCW ARC
gcode_G2_G3(codenum == 2);
break;
#endif
2015-05-22 19:32:27 -05:00
// G4 Dwell
case 4:
gcode_G4();
break;
#if ENABLED(BEZIER_CURVE_SUPPORT)
// G5
case 5: // G5 - Cubic B_spline
gcode_G5();
break;
#endif // BEZIER_CURVE_SUPPORT
#if ENABLED(FWRETRACT)
2015-05-22 19:32:27 -05:00
case 10: // G10: retract
case 11: // G11: retract_recover
gcode_G10_G11(codenum == 10);
break;
#endif // FWRETRACT
#if ENABLED(NOZZLE_CLEAN_FEATURE)
case 12:
gcode_G12(); // G12: Nozzle Clean
break;
#endif // NOZZLE_CLEAN_FEATURE
#if ENABLED(INCH_MODE_SUPPORT)
case 20: //G20: Inch Mode
gcode_G20();
break;
case 21: //G21: MM Mode
gcode_G21();
break;
#endif // INCH_MODE_SUPPORT
#if ENABLED(NOZZLE_PARK_FEATURE)
case 27: // G27: Nozzle Park
gcode_G27();
break;
#endif // NOZZLE_PARK_FEATURE
2015-05-22 19:32:27 -05:00
case 28: // G28: Home all axes, one at a time
gcode_G28();
break;
#if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(MESH_BED_LEVELING)
case 29: // G29 Detailed Z probe, probes the bed at 3 or more points.
2015-05-22 19:32:46 -05:00
gcode_G29();
break;
#endif // AUTO_BED_LEVELING_FEATURE
2015-03-21 08:50:47 -05:00
2016-06-20 17:50:51 -05:00
#if HAS_BED_PROBE
2016-06-20 17:50:51 -05:00
case 30: // G30 Single Z probe
gcode_G30();
break;
2016-06-20 17:50:51 -05:00
#if ENABLED(Z_PROBE_SLED)
2015-05-22 19:33:17 -05:00
case 31: // G31: dock the sled
2016-06-23 19:04:13 -05:00
gcode_G31();
2016-06-20 17:50:51 -05:00
break;
2016-06-23 19:04:13 -05:00
2015-05-22 19:33:17 -05:00
case 32: // G32: undock the sled
2016-06-23 19:04:13 -05:00
gcode_G32();
2015-05-22 19:33:17 -05:00
break;
2015-05-22 19:33:17 -05:00
#endif // Z_PROBE_SLED
2016-06-20 17:50:51 -05:00
#endif // HAS_BED_PROBE
2015-05-22 19:34:08 -05:00
case 90: // G90
relative_mode = false;
break;
case 91: // G91
relative_mode = true;
break;
2015-05-22 19:34:08 -05:00
case 92: // G92
gcode_G92();
break;
}
2015-05-17 07:00:09 -05:00
break;
2015-05-17 07:00:09 -05:00
case 'M': switch (codenum) {
#if ENABLED(ULTIPANEL)
case 0: // M0 - Unconditional stop - Wait for user button press on LCD
case 1: // M1 - Conditional stop - Wait for user button press on LCD
gcode_M0_M1();
break;
#endif // ULTIPANEL
case 17:
gcode_M17();
break;
#if ENABLED(SDSUPPORT)
case 20: // M20 - list SD card
gcode_M20(); break;
case 21: // M21 - init SD card
gcode_M21(); break;
case 22: //M22 - release SD card
gcode_M22(); break;
case 23: //M23 - Select file
gcode_M23(); break;
case 24: //M24 - Start SD print
gcode_M24(); break;
case 25: //M25 - Pause SD print
gcode_M25(); break;
case 26: //M26 - Set SD index
gcode_M26(); break;
case 27: //M27 - Get SD status
gcode_M27(); break;
case 28: //M28 - Start SD write
gcode_M28(); break;
case 29: //M29 - Stop SD write
gcode_M29(); break;
case 30: //M30 <filename> Delete File
gcode_M30(); break;
case 32: //M32 - Select file and start SD print
gcode_M32(); break;
2015-05-17 19:36:32 -05:00
#if ENABLED(LONG_FILENAME_HOST_SUPPORT)
2015-05-17 19:36:32 -05:00
case 33: //M33 - Get the long full path to a file or folder
gcode_M33(); break;
#endif // LONG_FILENAME_HOST_SUPPORT
case 928: //M928 - Start SD write
gcode_M928(); break;
#endif //SDSUPPORT
case 31: //M31 take time since the start of the SD print or an M109 command
gcode_M31();
break;
case 42: //M42 -Change pin status via gcode
gcode_M42();
break;
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
case 48: // M48 Z probe repeatability
gcode_M48();
break;
#endif // Z_MIN_PROBE_REPEATABILITY_TEST
case 75: // Start print timer
gcode_M75();
break;
case 76: // Pause print timer
gcode_M76();
break;
case 77: // Stop print timer
gcode_M77();
break;
2016-04-26 20:13:27 -05:00
#if ENABLED(PRINTCOUNTER)
case 78: // Show print statistics
gcode_M78();
break;
#endif
#if ENABLED(M100_FREE_MEMORY_WATCHER)
2015-07-18 18:59:12 -05:00
case 100:
gcode_M100();
2015-07-05 19:42:13 -05:00
break;
#endif
case 104: // M104
gcode_M104();
break;
case 110: // M110: Set Current Line Number
gcode_M110();
break;
case 111: // M111: Set debug level
gcode_M111();
break;
#if DISABLED(EMERGENCY_PARSER)
2016-07-06 13:52:36 -05:00
case 108: // M108: Cancel Waiting
gcode_M108();
break;
case 112: // M112: Emergency Stop
gcode_M112();
break;
2016-07-06 13:52:36 -05:00
case 410: // M410 quickstop - Abort all the planned moves.
gcode_M410();
break;
#endif
#if ENABLED(HOST_KEEPALIVE_FEATURE)
case 113: // M113: Set Host Keepalive interval
gcode_M113();
break;
#endif
case 140: // M140: Set bed temp
gcode_M140();
break;
case 105: // M105: Read current temperature
gcode_M105();
KEEPALIVE_STATE(NOT_BUSY);
2015-05-17 07:00:09 -05:00
return; // "ok" already printed
case 109: // M109: Wait for temperature
gcode_M109();
break;
2015-04-03 17:31:35 -05:00
#if HAS_TEMP_BED
case 190: // M190: Wait for bed heater to reach target
gcode_M190();
break;
2015-04-03 17:31:35 -05:00
#endif // HAS_TEMP_BED
2016-03-05 20:27:45 -06:00
#if FAN_COUNT > 0
case 106: // M106: Fan On
gcode_M106();
break;
case 107: // M107: Fan Off
gcode_M107();
break;
2016-03-05 20:27:45 -06:00
#endif // FAN_COUNT > 0
#if ENABLED(BARICUDA)
// PWM for HEATER_1_PIN
2015-04-03 17:31:35 -05:00
#if HAS_HEATER_1
case 126: // M126: valve open
gcode_M126();
break;
case 127: // M127: valve closed
gcode_M127();
break;
2015-04-03 17:31:35 -05:00
#endif // HAS_HEATER_1
// PWM for HEATER_2_PIN
2015-04-03 17:31:35 -05:00
#if HAS_HEATER_2
case 128: // M128: valve open
gcode_M128();
break;
case 129: // M129: valve closed
gcode_M129();
break;
2015-04-03 17:31:35 -05:00
#endif // HAS_HEATER_2
#endif // BARICUDA
2015-03-30 18:50:05 -05:00
#if HAS_POWER_SWITCH
case 80: // M80: Turn on Power Supply
gcode_M80();
break;
2015-03-30 18:50:05 -05:00
#endif // HAS_POWER_SWITCH
case 81: // M81: Turn off Power, including Power Supply, if possible
gcode_M81();
break;
case 82:
gcode_M82();
break;
case 83:
gcode_M83();
break;
case 18: // (for compatibility)
case 84: // M84
gcode_M18_M84();
break;
case 85: // M85
gcode_M85();
break;
case 92: // M92: Set the steps-per-unit for one or more axes
gcode_M92();
break;
case 115: // M115: Report capabilities
gcode_M115();
break;
2015-05-17 07:00:09 -05:00
case 117: // M117: Set LCD message text, if possible
gcode_M117();
break;
case 114: // M114: Report current position
gcode_M114();
break;
case 120: // M120: Enable endstops
gcode_M120();
break;
case 121: // M121: Disable endstops
gcode_M121();
break;
case 119: // M119: Report endstop states
gcode_M119();
break;
#if ENABLED(ULTIPANEL)
case 145: // M145: Set material heatup parameters
gcode_M145();
break;
#endif
#if ENABLED(TEMPERATURE_UNITS_SUPPORT)
case 149:
gcode_M149();
break;
#endif
#if ENABLED(BLINKM)
case 150: // M150
gcode_M150();
break;
#endif //BLINKM
#if ENABLED(EXPERIMENTAL_I2CBUS)
case 155:
gcode_M155();
break;
case 156:
gcode_M156();
break;
#endif //EXPERIMENTAL_I2CBUS
#if ENABLED(MIXING_EXTRUDER)
case 163: // M163 S<int> P<float> set weight for a mixing extruder
gcode_M163();
break;
#if MIXING_VIRTUAL_TOOLS > 1
case 164: // M164 S<int> save current mix as a virtual extruder
gcode_M164();
break;
#endif
#if ENABLED(DIRECT_MIXING_IN_G1)
case 165: // M165 [ABCDHI]<float> set multiple mix weights
gcode_M165();
break;
#endif
#endif
case 200: // M200 D<diameter> Set filament diameter and set E axis units to cubic. (Use S0 to revert to linear units.)
gcode_M200();
break;
case 201: // M201
gcode_M201();
break;
#if 0 // Not used for Sprinter/grbl gen6
case 202: // M202
gcode_M202();
break;
#endif
case 203: // M203 max feedrate units/sec
gcode_M203();
break;
case 204: // M204 acclereration S normal moves T filmanent only moves
gcode_M204();
break;
case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
gcode_M205();
break;
case 206: // M206 additional homing offset
gcode_M206();
break;
#if ENABLED(DELTA)
case 665: // M665 set delta configurations L<diagonal_rod> R<delta_radius> S<segments_per_sec>
gcode_M665();
break;
2015-03-29 21:39:43 -05:00
#endif
#if ENABLED(DELTA) || ENABLED(Z_DUAL_ENDSTOPS)
2015-03-29 21:39:43 -05:00
case 666: // M666 set delta / dual endstop adjustment
gcode_M666();
break;
2015-03-29 21:39:43 -05:00
#endif
#if ENABLED(FWRETRACT)
case 207: // M207 - Set Retract Length: S<length>, Feedrate: F<units/min>, and Z lift: Z<distance>
gcode_M207();
break;
case 208: // M208 - Set Recover (unretract) Additional (!) Length: S<length> and Feedrate: F<units/min>
gcode_M208();
break;
case 209: // M209 - Turn Automatic Retract Detection on/off: S<bool> (For slicers that don't support G10/11). Every normal extrude-only move will be classified as retract depending on the direction.
gcode_M209();
break;
#endif // FWRETRACT
case 211: // M211 - Enable, Disable, and/or Report software endstops
gcode_M211();
break;
2016-05-26 19:43:20 -05:00
#if HOTENDS > 1
case 218: // M218 - Set a tool offset: T<index> X<offset> Y<offset>
gcode_M218();
break;
#endif
case 220: // M220 - Set Feedrate Percentage: S<percent> ("FR" on your LCD)
gcode_M220();
break;
case 221: // M221 - Set Flow Percentage: S<percent>
gcode_M221();
break;
case 226: // M226 P<pin number> S<pin state>- Wait until the specified pin reaches the state required
gcode_M226();
break;
#if HAS_SERVOS
case 280: // M280 - set servo position absolute. P: servo index, S: angle or microseconds
gcode_M280();
break;
#endif // HAS_SERVOS
#if HAS_BUZZER
case 300: // M300 - Play beep tone
gcode_M300();
break;
#endif // HAS_BUZZER
#if ENABLED(PIDTEMP)
case 301: // M301
gcode_M301();
break;
#endif // PIDTEMP
#if ENABLED(PIDTEMPBED)
case 304: // M304
gcode_M304();
break;
#endif // PIDTEMPBED
2015-04-03 17:31:35 -05:00
#if defined(CHDK) || HAS_PHOTOGRAPH
case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
gcode_M240();
break;
#endif // CHDK || PHOTOGRAPH_PIN
2016-05-31 13:47:02 -05:00
#if HAS_LCD_CONTRAST
case 250: // M250 Set LCD contrast value: C<value> (value 0..63)
gcode_M250();
break;
#endif // HAS_LCD_CONTRAST
#if ENABLED(PREVENT_COLD_EXTRUSION)
case 302: // allow cold extrudes, or set the minimum extrude temperature
gcode_M302();
break;
#endif // PREVENT_COLD_EXTRUSION
case 303: // M303 PID autotune
gcode_M303();
break;
#if ENABLED(SCARA)
case 360: // M360 SCARA Theta pos1
if (gcode_M360()) return;
break;
case 361: // M361 SCARA Theta pos2
if (gcode_M361()) return;
break;
case 362: // M362 SCARA Psi pos1
if (gcode_M362()) return;
break;
case 363: // M363 SCARA Psi pos2
if (gcode_M363()) return;
break;
case 364: // M364 SCARA Psi pos3 (90 deg to Theta)
if (gcode_M364()) return;
break;
case 365: // M365 Set SCARA scaling for X Y Z
gcode_M365();
break;
#endif // SCARA
case 400: // M400 finish all moves
gcode_M400();
break;
#if HAS_BED_PROBE
case 401:
gcode_M401();
break;
case 402:
gcode_M402();
break;
#endif // HAS_BED_PROBE
#if ENABLED(FILAMENT_WIDTH_SENSOR)
case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or display nominal filament width
gcode_M404();
break;
case 405: //M405 Turn on filament sensor for control
gcode_M405();
break;
case 406: //M406 Turn off filament sensor for control
gcode_M406();
break;
case 407: //M407 Display measured filament diameter
gcode_M407();
break;
#endif // ENABLED(FILAMENT_WIDTH_SENSOR)
#if ENABLED(MESH_BED_LEVELING)
case 420: // M420 Enable/Disable Mesh Bed Leveling
gcode_M420();
break;
case 421: // M421 Set a Mesh Bed Leveling Z coordinate
gcode_M421();
break;
#endif
2015-04-29 20:26:16 -05:00
case 428: // M428 Apply current_position to home_offset
gcode_M428();
break;
case 500: // M500 Store settings in EEPROM
gcode_M500();
break;
case 501: // M501 Read settings from EEPROM
gcode_M501();
break;
case 502: // M502 Revert to default settings
gcode_M502();
break;
case 503: // M503 print settings currently in memory
gcode_M503();
break;
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
case 540:
gcode_M540();
break;
#endif
#if HAS_BED_PROBE
case 851:
2016-06-14 20:05:20 -05:00
gcode_M851();
break;
#endif // HAS_BED_PROBE
#if ENABLED(FILAMENT_CHANGE_FEATURE)
case 600: //Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
gcode_M600();
break;
#endif // FILAMENT_CHANGE_FEATURE
#if ENABLED(DUAL_X_CARRIAGE)
case 605:
gcode_M605();
break;
#endif // DUAL_X_CARRIAGE
2016-06-16 13:24:11 -05:00
2016-05-04 11:53:17 -05:00
#if ENABLED(LIN_ADVANCE)
case 905: // M905 Set advance factor.
gcode_M905();
break;
#endif
case 907: // M907 Set digital trimpot motor current using axis codes.
gcode_M907();
break;
#if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT)
case 908: // M908 Control digital trimpot directly.
gcode_M908();
break;
#if ENABLED(DAC_STEPPER_CURRENT) // As with Printrbot RevF
case 909: // M909 Print digipot/DAC current value
gcode_M909();
break;
case 910: // M910 Commit digipot/DAC value to external EEPROM
gcode_M910();
break;
#endif
#endif // HAS_DIGIPOTSS || DAC_STEPPER_CURRENT
2015-04-03 17:31:35 -05:00
#if HAS_MICROSTEPS
2015-04-03 17:31:35 -05:00
case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
gcode_M350();
break;
case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
gcode_M351();
break;
#endif // HAS_MICROSTEPS
case 999: // M999: Restart after being Stopped
gcode_M999();
break;
}
2015-05-17 07:00:09 -05:00
break;
2015-05-17 07:00:09 -05:00
case 'T':
2015-05-17 07:07:51 -05:00
gcode_T(codenum);
break;
default: code_is_good = false;
}
KEEPALIVE_STATE(NOT_BUSY);
ExitUnknownCommand:
// Still unknown command? Throw an error
2015-05-17 07:00:09 -05:00
if (!code_is_good) unknown_command_error();
ok_to_send();
}
2015-04-03 17:31:35 -05:00
void FlushSerialRequestResend() {
2015-04-13 19:17:36 -05:00
//char command_queue[cmd_queue_index_r][100]="Resend:";
MYSERIAL.flush();
SERIAL_PROTOCOLPGM(MSG_RESEND);
SERIAL_PROTOCOLLN(gcode_LastN + 1);
ok_to_send();
}
void ok_to_send() {
2015-04-03 17:31:35 -05:00
refresh_cmd_timeout();
2016-02-20 19:35:35 -06:00
if (!send_ok[cmd_queue_index_r]) return;
2015-04-19 17:22:40 -05:00
SERIAL_PROTOCOLPGM(MSG_OK);
#if ENABLED(ADVANCED_OK)
char* p = command_queue[cmd_queue_index_r];
if (*p == 'N') {
SERIAL_PROTOCOL(' ');
SERIAL_ECHO(*p++);
while (NUMERIC_SIGNED(*p))
SERIAL_ECHO(*p++);
}
SERIAL_PROTOCOLPGM(" P"); SERIAL_PROTOCOL(int(BLOCK_BUFFER_SIZE - planner.movesplanned() - 1));
SERIAL_PROTOCOLPGM(" B"); SERIAL_PROTOCOL(BUFSIZE - commands_in_queue);
2015-04-19 17:22:40 -05:00
#endif
2015-08-05 06:40:36 -05:00
SERIAL_EOL;
}
#if ENABLED(min_software_endstops) || ENABLED(max_software_endstops)
void clamp_to_software_endstops(float target[XYZ]) {
#if ENABLED(min_software_endstops)
NOLESS(target[X_AXIS], soft_endstop_min[X_AXIS]);
NOLESS(target[Y_AXIS], soft_endstop_min[Y_AXIS]);
NOLESS(target[Z_AXIS], soft_endstop_min[Z_AXIS]);
#endif
#if ENABLED(max_software_endstops)
NOMORE(target[X_AXIS], soft_endstop_max[X_AXIS]);
NOMORE(target[Y_AXIS], soft_endstop_max[Y_AXIS]);
NOMORE(target[Z_AXIS], soft_endstop_max[Z_AXIS]);
#endif
}
#endif
#if ENABLED(DELTA)
void recalc_delta_settings(float radius, float diagonal_rod) {
delta_tower1_x = -SIN_60 * (radius + DELTA_RADIUS_TRIM_TOWER_1); // front left tower
delta_tower1_y = -COS_60 * (radius + DELTA_RADIUS_TRIM_TOWER_1);
delta_tower2_x = SIN_60 * (radius + DELTA_RADIUS_TRIM_TOWER_2); // front right tower
delta_tower2_y = -COS_60 * (radius + DELTA_RADIUS_TRIM_TOWER_2);
delta_tower3_x = 0.0; // back middle tower
delta_tower3_y = (radius + DELTA_RADIUS_TRIM_TOWER_3);
delta_diagonal_rod_2_tower_1 = sq(diagonal_rod + delta_diagonal_rod_trim_tower_1);
delta_diagonal_rod_2_tower_2 = sq(diagonal_rod + delta_diagonal_rod_trim_tower_2);
delta_diagonal_rod_2_tower_3 = sq(diagonal_rod + delta_diagonal_rod_trim_tower_3);
}
2016-08-20 22:38:32 -05:00
void inverse_kinematics(const float in_cartesian[XYZ]) {
2016-08-20 22:38:32 -05:00
const float cartesian[XYZ] = {
2016-07-24 18:34:01 -05:00
RAW_X_POSITION(in_cartesian[X_AXIS]),
RAW_Y_POSITION(in_cartesian[Y_AXIS]),
RAW_Z_POSITION(in_cartesian[Z_AXIS])
};
delta[TOWER_1] = sqrt(delta_diagonal_rod_2_tower_1
- sq(delta_tower1_x - cartesian[X_AXIS])
- sq(delta_tower1_y - cartesian[Y_AXIS])
) + cartesian[Z_AXIS];
delta[TOWER_2] = sqrt(delta_diagonal_rod_2_tower_2
- sq(delta_tower2_x - cartesian[X_AXIS])
- sq(delta_tower2_y - cartesian[Y_AXIS])
) + cartesian[Z_AXIS];
delta[TOWER_3] = sqrt(delta_diagonal_rod_2_tower_3
- sq(delta_tower3_x - cartesian[X_AXIS])
- sq(delta_tower3_y - cartesian[Y_AXIS])
) + cartesian[Z_AXIS];
/**
SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
SERIAL_ECHOPGM("delta a="); SERIAL_ECHO(delta[TOWER_1]);
SERIAL_ECHOPGM(" b="); SERIAL_ECHO(delta[TOWER_2]);
SERIAL_ECHOPGM(" c="); SERIAL_ECHOLN(delta[TOWER_3]);
*/
}
float delta_safe_distance_from_top() {
2016-08-20 22:38:32 -05:00
float cartesian[XYZ] = {
2016-07-24 18:34:01 -05:00
LOGICAL_X_POSITION(0),
LOGICAL_Y_POSITION(0),
LOGICAL_Z_POSITION(0)
};
2016-07-21 17:46:22 -05:00
inverse_kinematics(cartesian);
float distance = delta[TOWER_3];
2016-07-24 18:34:01 -05:00
cartesian[Y_AXIS] = LOGICAL_Y_POSITION(DELTA_PRINTABLE_RADIUS);
2016-07-21 17:46:22 -05:00
inverse_kinematics(cartesian);
return abs(distance - delta[TOWER_3]);
}
2016-07-21 17:46:22 -05:00
void forward_kinematics_DELTA(float z1, float z2, float z3) {
2016-06-06 18:44:14 -05:00
//As discussed in Wikipedia "Trilateration"
//we are establishing a new coordinate
//system in the plane of the three carriage points.
//This system will have the origin at tower1 and
//tower2 is on the x axis. tower3 is in the X-Y
//plane with a Z component of zero. We will define unit
//vectors in this coordinate system in our original
//coordinate system. Then when we calculate the
//Xnew, Ynew and Znew values, we can translate back into
//the original system by moving along those unit vectors
//by the corresponding values.
// https://en.wikipedia.org/wiki/Trilateration
// Variable names matched to Marlin, c-version
// and avoiding a vector library
// by Andreas Hardtung 2016-06-7
// based on a Java function from
// "Delta Robot Kinematics by Steve Graves" V3
// Result is in cartesian_position[].
2016-06-06 18:44:14 -05:00
//Create a vector in old coordinates along x axis of new coordinate
2016-06-06 18:44:14 -05:00
float p12[3] = { delta_tower2_x - delta_tower1_x, delta_tower2_y - delta_tower1_y, z2 - z1 };
//Get the Magnitude of vector.
float d = sqrt( p12[0]*p12[0] + p12[1]*p12[1] + p12[2]*p12[2] );
//Create unit vector by dividing by magnitude.
float ex[3] = { p12[0]/d, p12[1]/d, p12[2]/d };
//Now find vector from the origin of the new system to the third point.
float p13[3] = { delta_tower3_x - delta_tower1_x, delta_tower3_y - delta_tower1_y, z3 - z1 };
//Now use dot product to find the component of this vector on the X axis.
float i = ex[0]*p13[0] + ex[1]*p13[1] + ex[2]*p13[2];
//Now create a vector along the x axis that represents the x component of p13.
float iex[3] = { ex[0]*i, ex[1]*i, ex[2]*i };
//Now subtract the X component away from the original vector leaving only the Y component. We use the
//variable that will be the unit vector after we scale it.
float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2]};
//The magnitude of Y component
float j = sqrt(sq(ey[0]) + sq(ey[1]) + sq(ey[2]));
//Now make vector a unit vector
ey[0] /= j; ey[1] /= j; ey[2] /= j;
//The cross product of the unit x and y is the unit z
//float[] ez = vectorCrossProd(ex, ey);
float ez[3] = { ex[1]*ey[2] - ex[2]*ey[1], ex[2]*ey[0] - ex[0]*ey[2], ex[0]*ey[1] - ex[1]*ey[0] };
//Now we have the d, i and j values defined in Wikipedia.
//We can plug them into the equations defined in
//Wikipedia for Xnew, Ynew and Znew
float Xnew = (delta_diagonal_rod_2_tower_1 - delta_diagonal_rod_2_tower_2 + d*d)/(d*2);
float Ynew = ((delta_diagonal_rod_2_tower_1 - delta_diagonal_rod_2_tower_3 + i*i + j*j)/2 - i*Xnew) /j;
float Znew = sqrt(delta_diagonal_rod_2_tower_1 - Xnew*Xnew - Ynew*Ynew);
//Now we can start from the origin in the old coords and
//add vectors in the old coords that represent the
//Xnew, Ynew and Znew to find the point in the old system
cartesian_position[X_AXIS] = delta_tower1_x + ex[0]*Xnew + ey[0]*Ynew - ez[0]*Znew;
cartesian_position[Y_AXIS] = delta_tower1_y + ex[1]*Xnew + ey[1]*Ynew - ez[1]*Znew;
cartesian_position[Z_AXIS] = z1 + ex[2]*Xnew + ey[2]*Ynew - ez[2]*Znew;
2016-06-06 18:44:14 -05:00
};
2016-08-20 22:38:32 -05:00
void forward_kinematics_DELTA(float point[ABC]) {
forward_kinematics_DELTA(point[A_AXIS], point[B_AXIS], point[C_AXIS]);
}
void set_cartesian_from_steppers() {
2016-08-20 22:38:32 -05:00
forward_kinematics_DELTA(stepper.get_axis_position_mm(A_AXIS),
stepper.get_axis_position_mm(B_AXIS),
stepper.get_axis_position_mm(C_AXIS));
}
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
// Adjust print surface height by linear interpolation over the bed_level array.
2016-08-20 22:38:32 -05:00
void adjust_delta(float cartesian[XYZ]) {
if (delta_grid_spacing[X_AXIS] == 0 || delta_grid_spacing[Y_AXIS] == 0) return; // G29 not done!
int half = (AUTO_BED_LEVELING_GRID_POINTS - 1) / 2;
float h1 = 0.001 - half, h2 = half - 0.001,
grid_x = max(h1, min(h2, RAW_X_POSITION(cartesian[X_AXIS]) / delta_grid_spacing[X_AXIS])),
grid_y = max(h1, min(h2, RAW_Y_POSITION(cartesian[Y_AXIS]) / delta_grid_spacing[Y_AXIS]));
int floor_x = floor(grid_x), floor_y = floor(grid_y);
float ratio_x = grid_x - floor_x, ratio_y = grid_y - floor_y,
z1 = bed_level[floor_x + half][floor_y + half],
z2 = bed_level[floor_x + half][floor_y + half + 1],
z3 = bed_level[floor_x + half + 1][floor_y + half],
z4 = bed_level[floor_x + half + 1][floor_y + half + 1],
left = (1 - ratio_y) * z1 + ratio_y * z2,
right = (1 - ratio_y) * z3 + ratio_y * z4,
offset = (1 - ratio_x) * left + ratio_x * right;
delta[X_AXIS] += offset;
delta[Y_AXIS] += offset;
delta[Z_AXIS] += offset;
/**
SERIAL_ECHOPGM("grid_x="); SERIAL_ECHO(grid_x);
SERIAL_ECHOPGM(" grid_y="); SERIAL_ECHO(grid_y);
SERIAL_ECHOPGM(" floor_x="); SERIAL_ECHO(floor_x);
SERIAL_ECHOPGM(" floor_y="); SERIAL_ECHO(floor_y);
SERIAL_ECHOPGM(" ratio_x="); SERIAL_ECHO(ratio_x);
SERIAL_ECHOPGM(" ratio_y="); SERIAL_ECHO(ratio_y);
SERIAL_ECHOPGM(" z1="); SERIAL_ECHO(z1);
SERIAL_ECHOPGM(" z2="); SERIAL_ECHO(z2);
SERIAL_ECHOPGM(" z3="); SERIAL_ECHO(z3);
SERIAL_ECHOPGM(" z4="); SERIAL_ECHO(z4);
SERIAL_ECHOPGM(" left="); SERIAL_ECHO(left);
SERIAL_ECHOPGM(" right="); SERIAL_ECHO(right);
SERIAL_ECHOPGM(" offset="); SERIAL_ECHOLN(offset);
*/
}
#endif // AUTO_BED_LEVELING_FEATURE
#endif // DELTA
2016-07-23 15:11:18 -05:00
void set_current_from_steppers_for_axis(AxisEnum axis) {
#if ENABLED(DELTA)
set_cartesian_from_steppers();
2016-07-23 15:11:18 -05:00
current_position[axis] = LOGICAL_POSITION(cartesian_position[axis], axis);
#elif ENABLED(AUTO_BED_LEVELING_FEATURE)
2016-07-23 15:11:18 -05:00
vector_3 pos = planner.adjusted_position();
2016-07-24 18:34:01 -05:00
current_position[axis] = axis == X_AXIS ? pos.x : axis == Y_AXIS ? pos.y : pos.z;
#else
2016-07-24 18:34:01 -05:00
current_position[axis] = stepper.get_axis_position_mm(axis); // CORE handled transparently
#endif
}
#if ENABLED(MESH_BED_LEVELING)
2015-03-15 04:43:26 -05:00
// This function is used to split lines on mesh borders so each segment is only part of one mesh area
void mesh_line_to_destination(float fr_mm_s, uint8_t x_splits = 0xff, uint8_t y_splits = 0xff) {
2016-07-16 21:11:56 -05:00
int cx1 = mbl.cell_index_x(RAW_CURRENT_POSITION(X_AXIS)),
cy1 = mbl.cell_index_y(RAW_CURRENT_POSITION(Y_AXIS)),
2016-07-24 18:34:01 -05:00
cx2 = mbl.cell_index_x(RAW_X_POSITION(destination[X_AXIS])),
cy2 = mbl.cell_index_y(RAW_Y_POSITION(destination[Y_AXIS]));
2016-07-16 21:11:56 -05:00
NOMORE(cx1, MESH_NUM_X_POINTS - 2);
NOMORE(cy1, MESH_NUM_Y_POINTS - 2);
NOMORE(cx2, MESH_NUM_X_POINTS - 2);
NOMORE(cy2, MESH_NUM_Y_POINTS - 2);
if (cx1 == cx2 && cy1 == cy2) {
2015-03-19 14:15:38 -05:00
// Start and end on same mesh square
line_to_destination(fr_mm_s);
set_current_to_destination();
2015-03-15 04:43:26 -05:00
return;
}
2016-07-16 21:08:54 -05:00
#define MBL_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist)
2016-07-16 21:20:16 -05:00
float normalized_dist, end[NUM_AXIS];
// Split at the left/front border of the right/top square
2016-07-16 21:11:56 -05:00
int8_t gcx = max(cx1, cx2), gcy = max(cy1, cy2);
if (cx2 != cx1 && TEST(x_splits, gcx)) {
memcpy(end, destination, sizeof(end));
2016-07-24 18:34:01 -05:00
destination[X_AXIS] = LOGICAL_X_POSITION(mbl.get_probe_x(gcx));
normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]);
destination[Y_AXIS] = MBL_SEGMENT_END(Y);
2016-07-16 21:08:54 -05:00
CBI(x_splits, gcx);
2015-10-13 05:51:34 -05:00
}
2016-07-16 21:11:56 -05:00
else if (cy2 != cy1 && TEST(y_splits, gcy)) {
memcpy(end, destination, sizeof(end));
2016-07-24 18:34:01 -05:00
destination[Y_AXIS] = LOGICAL_Y_POSITION(mbl.get_probe_y(gcy));
normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]);
destination[X_AXIS] = MBL_SEGMENT_END(X);
2016-07-16 21:08:54 -05:00
CBI(y_splits, gcy);
2015-10-13 05:51:34 -05:00
}
else {
2015-03-19 14:15:38 -05:00
// Already split on a border
line_to_destination(fr_mm_s);
set_current_to_destination();
2015-03-19 14:15:38 -05:00
return;
2015-03-15 04:43:26 -05:00
}
destination[Z_AXIS] = MBL_SEGMENT_END(Z);
destination[E_AXIS] = MBL_SEGMENT_END(E);
2015-03-19 14:15:38 -05:00
// Do the split and look for more borders
mesh_line_to_destination(fr_mm_s, x_splits, y_splits);
// Restore destination from stack
memcpy(destination, end, sizeof(end));
mesh_line_to_destination(fr_mm_s, x_splits, y_splits);
2015-03-15 04:43:26 -05:00
}
#endif // MESH_BED_LEVELING
#if ENABLED(DELTA) || ENABLED(SCARA)
2016-07-21 17:46:22 -05:00
inline bool prepare_kinematic_move_to(float target[NUM_AXIS]) {
float difference[NUM_AXIS];
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i) difference[i] = target[i] - current_position[i];
float cartesian_mm = sqrt(sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) + sq(difference[Z_AXIS]));
if (cartesian_mm < 0.000001) cartesian_mm = abs(difference[E_AXIS]);
if (cartesian_mm < 0.000001) return false;
float _feedrate_mm_s = MMS_SCALED(feedrate_mm_s);
2016-07-15 20:49:34 -05:00
float seconds = cartesian_mm / _feedrate_mm_s;
int steps = max(1, int(delta_segments_per_second * seconds));
float inv_steps = 1.0/steps;
// SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
// SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
// SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
for (int s = 1; s <= steps; s++) {
float fraction = float(s) * inv_steps;
2016-07-23 15:07:23 -05:00
LOOP_XYZE(i)
target[i] = current_position[i] + difference[i] * fraction;
2016-07-21 17:46:22 -05:00
inverse_kinematics(target);
2016-07-22 18:19:41 -05:00
#if ENABLED(DELTA) && ENABLED(AUTO_BED_LEVELING_FEATURE)
if (!bed_leveling_in_progress) adjust_delta(target);
#endif
2016-07-21 17:46:22 -05:00
//DEBUG_POS("prepare_kinematic_move_to", target);
//DEBUG_POS("prepare_kinematic_move_to", delta);
2016-07-15 20:49:34 -05:00
planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], target[E_AXIS], _feedrate_mm_s, active_extruder);
}
return true;
}
#endif // DELTA || SCARA
#if ENABLED(DUAL_X_CARRIAGE)
2016-06-30 17:37:32 -05:00
inline bool prepare_move_to_destination_dualx() {
if (active_extruder_parked) {
if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0) {
// move duplicate extruder into correct duplication position.
planner.set_position_mm(
LOGICAL_X_POSITION(inactive_extruder_x_pos),
current_position[Y_AXIS],
current_position[Z_AXIS],
current_position[E_AXIS]
);
2016-04-27 20:06:32 -05:00
planner.buffer_line(current_position[X_AXIS] + duplicate_extruder_x_offset,
2016-07-15 20:49:34 -05:00
current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate_mm_s[X_AXIS], 1);
SYNC_PLAN_POSITION_KINEMATIC();
stepper.synchronize();
extruder_duplication_enabled = true;
active_extruder_parked = false;
}
else if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE) { // handle unparking of head
if (current_position[E_AXIS] == destination[E_AXIS]) {
// This is a travel move (with no extrusion)
// Skip it, but keep track of the current position
// (so it can be used as the start of the next non-travel move)
if (delayed_move_time != 0xFFFFFFFFUL) {
set_current_to_destination();
2015-04-12 20:07:08 -05:00
NOLESS(raised_parked_position[Z_AXIS], destination[Z_AXIS]);
delayed_move_time = millis();
return false;
}
}
delayed_move_time = 0;
// unpark extruder: 1) raise, 2) move into starting XY position, 3) lower
2016-07-15 20:49:34 -05:00
planner.buffer_line(raised_parked_position[X_AXIS], raised_parked_position[Y_AXIS], raised_parked_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate_mm_s[Z_AXIS], active_extruder);
planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], raised_parked_position[Z_AXIS], current_position[E_AXIS], PLANNER_XY_FEEDRATE(), active_extruder);
2016-07-15 20:49:34 -05:00
planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate_mm_s[Z_AXIS], active_extruder);
active_extruder_parked = false;
}
}
return true;
}
#endif // DUAL_X_CARRIAGE
#if DISABLED(DELTA) && DISABLED(SCARA)
2016-06-30 17:37:32 -05:00
inline bool prepare_move_to_destination_cartesian() {
2016-07-15 20:49:34 -05:00
// Do not use feedrate_percentage for E or Z only moves
if (current_position[X_AXIS] == destination[X_AXIS] && current_position[Y_AXIS] == destination[Y_AXIS]) {
line_to_destination();
}
else {
#if ENABLED(MESH_BED_LEVELING)
if (mbl.active()) {
mesh_line_to_destination(MMS_SCALED(feedrate_mm_s));
return false;
}
else
#endif
line_to_destination(MMS_SCALED(feedrate_mm_s));
}
return true;
}
#endif // !DELTA && !SCARA
#if ENABLED(PREVENT_COLD_EXTRUSION)
inline void prevent_dangerous_extrude(float& curr_e, float& dest_e) {
if (DEBUGGING(DRYRUN)) return;
float de = dest_e - curr_e;
if (de) {
if (thermalManager.tooColdToExtrude(active_extruder)) {
curr_e = dest_e; // Behave as if the move really took place, but ignore E part
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP);
}
#if ENABLED(PREVENT_LENGTHY_EXTRUDE)
if (labs(de) > EXTRUDE_MAXLENGTH) {
curr_e = dest_e; // Behave as if the move really took place, but ignore E part
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP);
}
#endif
}
}
#endif // PREVENT_COLD_EXTRUSION
/**
* Prepare a single move and get ready for the next one
*
2016-04-27 20:06:32 -05:00
* (This may call planner.buffer_line several times to put
* smaller moves into the planner for DELTA or SCARA.)
*/
void prepare_move_to_destination() {
clamp_to_software_endstops(destination);
refresh_cmd_timeout();
#if ENABLED(PREVENT_COLD_EXTRUSION)
prevent_dangerous_extrude(current_position[E_AXIS], destination[E_AXIS]);
#endif
2016-07-21 17:46:22 -05:00
#if ENABLED(DELTA) || ENABLED(SCARA)
if (!prepare_kinematic_move_to(destination)) return;
#else
#if ENABLED(DUAL_X_CARRIAGE)
2016-06-30 17:37:32 -05:00
if (!prepare_move_to_destination_dualx()) return;
#endif
2016-06-30 17:37:32 -05:00
if (!prepare_move_to_destination_cartesian()) return;
#endif
set_current_to_destination();
}
#if ENABLED(ARC_SUPPORT)
2016-03-26 22:36:36 -05:00
/**
* Plan an arc in 2 dimensions
2016-03-26 22:36:36 -05:00
*
* The arc is approximated by generating many small linear segments.
* The length of each segment is configured in MM_PER_ARC_SEGMENT (Default 1mm)
* Arcs should only be made relatively large (over 5mm), as larger arcs with
* larger segments will tend to be more efficient. Your slicer should have
* options for G2/G3 arc generation. In future these options may be GCode tunable.
2016-03-26 22:36:36 -05:00
*/
void plan_arc(
float target[NUM_AXIS], // Destination position
float* offset, // Center of rotation relative to current_position
uint8_t clockwise // Clockwise?
) {
float radius = HYPOT(offset[X_AXIS], offset[Y_AXIS]),
center_X = current_position[X_AXIS] + offset[X_AXIS],
center_Y = current_position[Y_AXIS] + offset[Y_AXIS],
linear_travel = target[Z_AXIS] - current_position[Z_AXIS],
extruder_travel = target[E_AXIS] - current_position[E_AXIS],
r_X = -offset[X_AXIS], // Radius vector from center to current location
r_Y = -offset[Y_AXIS],
rt_X = target[X_AXIS] - center_X,
rt_Y = target[Y_AXIS] - center_Y;
// CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required.
float angular_travel = atan2(r_X * rt_Y - r_Y * rt_X, r_X * rt_X + r_Y * rt_Y);
if (angular_travel < 0) angular_travel += RADIANS(360);
if (clockwise) angular_travel -= RADIANS(360);
// Make a circle if the angular rotation is 0
if (angular_travel == 0 && current_position[X_AXIS] == target[X_AXIS] && current_position[Y_AXIS] == target[Y_AXIS])
angular_travel += RADIANS(360);
float mm_of_travel = HYPOT(angular_travel * radius, fabs(linear_travel));
if (mm_of_travel < 0.001) return;
uint16_t segments = floor(mm_of_travel / (MM_PER_ARC_SEGMENT));
if (segments == 0) segments = 1;
float theta_per_segment = angular_travel / segments;
float linear_per_segment = linear_travel / segments;
float extruder_per_segment = extruder_travel / segments;
2015-08-05 06:40:36 -05:00
/**
* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
* and phi is the angle of rotation. Based on the solution approach by Jens Geisler.
* r_T = [cos(phi) -sin(phi);
* sin(phi) cos(phi] * r ;
*
* For arc generation, the center of the circle is the axis of rotation and the radius vector is
* defined from the circle center to the initial position. Each line segment is formed by successive
* vector rotations. This requires only two cos() and sin() computations to form the rotation
* matrix for the duration of the entire arc. Error may accumulate from numerical round-off, since
* all double numbers are single precision on the Arduino. (True double precision will not have
* round off issues for CNC applications.) Single precision error can accumulate to be greater than
* tool precision in some cases. Therefore, arc path correction is implemented.
*
* Small angle approximation may be used to reduce computation overhead further. This approximation
* holds for everything, but very small circles and large MM_PER_ARC_SEGMENT values. In other words,
* theta_per_segment would need to be greater than 0.1 rad and N_ARC_CORRECTION would need to be large
* to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for
* numerical drift error. N_ARC_CORRECTION may be on the order a hundred(s) before error becomes an
* issue for CNC machines with the single precision Arduino calculations.
*
* This approximation also allows plan_arc to immediately insert a line segment into the planner
* without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied
* a correction, the planner should have caught up to the lag caused by the initial plan_arc overhead.
* This is important when there are successive arc motions.
*/
// Vector rotation matrix values
2016-07-15 20:50:25 -05:00
float cos_T = 1 - 0.5 * sq(theta_per_segment); // Small angle approximation
float sin_T = theta_per_segment;
2015-07-19 12:49:02 -05:00
float arc_target[NUM_AXIS];
float sin_Ti, cos_Ti, r_new_Y;
uint16_t i;
int8_t count = 0;
2015-08-05 06:40:36 -05:00
// Initialize the linear axis
arc_target[Z_AXIS] = current_position[Z_AXIS];
2015-07-19 12:49:02 -05:00
// Initialize the extruder axis
arc_target[E_AXIS] = current_position[E_AXIS];
2015-07-19 12:49:02 -05:00
float fr_mm_s = MMS_SCALED(feedrate_mm_s);
2015-07-19 12:49:02 -05:00
millis_t next_idle_ms = millis() + 200UL;
for (i = 1; i < segments; i++) { // Iterate (segments-1) times
2015-07-19 12:49:02 -05:00
thermalManager.manage_heater();
millis_t now = millis();
if (ELAPSED(now, next_idle_ms)) {
next_idle_ms = now + 200UL;
idle();
}
if (++count < N_ARC_CORRECTION) {
// Apply vector rotation matrix to previous r_X / 1
r_new_Y = r_X * sin_T + r_Y * cos_T;
r_X = r_X * cos_T - r_Y * sin_T;
r_Y = r_new_Y;
}
else {
// Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments.
// Compute exact location by applying transformation matrix from initial radius vector(=-offset).
// To reduce stuttering, the sin and cos could be computed at different times.
// For now, compute both at the same time.
cos_Ti = cos(i * theta_per_segment);
sin_Ti = sin(i * theta_per_segment);
r_X = -offset[X_AXIS] * cos_Ti + offset[Y_AXIS] * sin_Ti;
r_Y = -offset[X_AXIS] * sin_Ti - offset[Y_AXIS] * cos_Ti;
count = 0;
}
// Update arc_target location
arc_target[X_AXIS] = center_X + r_X;
arc_target[Y_AXIS] = center_Y + r_Y;
arc_target[Z_AXIS] += linear_per_segment;
arc_target[E_AXIS] += extruder_per_segment;
2015-07-19 12:49:02 -05:00
clamp_to_software_endstops(arc_target);
2015-07-19 12:49:02 -05:00
#if ENABLED(DELTA) || ENABLED(SCARA)
2016-07-21 17:46:22 -05:00
inverse_kinematics(arc_target);
2016-07-22 18:19:41 -05:00
#if ENABLED(DELTA) && ENABLED(AUTO_BED_LEVELING_FEATURE)
adjust_delta(arc_target);
#endif
2016-07-15 20:49:34 -05:00
planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], arc_target[E_AXIS], fr_mm_s, active_extruder);
#else
2016-07-15 20:49:34 -05:00
planner.buffer_line(arc_target[X_AXIS], arc_target[Y_AXIS], arc_target[Z_AXIS], arc_target[E_AXIS], fr_mm_s, active_extruder);
#endif
}
// Ensure last segment arrives at target location.
#if ENABLED(DELTA) || ENABLED(SCARA)
2016-07-21 17:46:22 -05:00
inverse_kinematics(target);
2016-07-22 18:19:41 -05:00
#if ENABLED(DELTA) && ENABLED(AUTO_BED_LEVELING_FEATURE)
adjust_delta(target);
2015-07-19 12:49:02 -05:00
#endif
2016-07-15 20:49:34 -05:00
planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], target[E_AXIS], fr_mm_s, active_extruder);
2015-07-19 12:49:02 -05:00
#else
2016-07-15 20:49:34 -05:00
planner.buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], fr_mm_s, active_extruder);
2015-07-19 12:49:02 -05:00
#endif
// As far as the parser is concerned, the position is now == target. In reality the
// motion control system might still be processing the action and the real tool position
// in any intermediate location.
set_current_to_destination();
}
#endif
2015-07-19 12:49:02 -05:00
#if ENABLED(BEZIER_CURVE_SUPPORT)
void plan_cubic_move(const float offset[4]) {
cubic_b_spline(current_position, destination, offset, MMS_SCALED(feedrate_mm_s), active_extruder);
// As far as the parser is concerned, the position is now == target. In reality the
// motion control system might still be processing the action and the real tool position
// in any intermediate location.
set_current_to_destination();
}
#endif // BEZIER_CURVE_SUPPORT
2015-04-03 17:31:35 -05:00
#if HAS_CONTROLLERFAN
void controllerFan() {
static millis_t lastMotorOn = 0; // Last time a motor was turned on
static millis_t nextMotorCheck = 0; // Last time the state was checked
millis_t ms = millis();
2016-04-10 17:55:12 -05:00
if (ELAPSED(ms, nextMotorCheck)) {
nextMotorCheck = ms + 2500UL; // Not a time critical function, so only check every 2.5s
2016-04-28 20:18:13 -05:00
if (X_ENABLE_READ == X_ENABLE_ON || Y_ENABLE_READ == Y_ENABLE_ON || Z_ENABLE_READ == Z_ENABLE_ON || thermalManager.soft_pwm_bed > 0
|| E0_ENABLE_READ == E_ENABLE_ON // If any of the drivers are enabled...
#if E_STEPPERS > 1
|| E1_ENABLE_READ == E_ENABLE_ON
#if HAS_X2_ENABLE
|| X2_ENABLE_READ == X_ENABLE_ON
#endif
#if E_STEPPERS > 2
|| E2_ENABLE_READ == E_ENABLE_ON
#if E_STEPPERS > 3
|| E3_ENABLE_READ == E_ENABLE_ON
#endif
#endif
#endif
) {
lastMotorOn = ms; //... set time to NOW so the fan will turn on
}
// Fan off if no steppers have been enabled for CONTROLLERFAN_SECS seconds
2016-04-10 17:55:12 -05:00
uint8_t speed = (!lastMotorOn || ELAPSED(ms, lastMotorOn + (CONTROLLERFAN_SECS) * 1000UL)) ? 0 : CONTROLLERFAN_SPEED;
// allows digital or PWM fan output to be used (see M42 handling)
digitalWrite(CONTROLLERFAN_PIN, speed);
analogWrite(CONTROLLERFAN_PIN, speed);
}
}
#endif // HAS_CONTROLLERFAN
#if ENABLED(SCARA)
2016-08-20 22:38:32 -05:00
void forward_kinematics_SCARA(float f_scara[ABC]) {
// Perform forward kinematics, and place results in delta[]
// The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
float x_sin, x_cos, y_sin, y_cos;
//SERIAL_ECHOPGM("f_delta x="); SERIAL_ECHO(f_scara[X_AXIS]);
//SERIAL_ECHOPGM(" y="); SERIAL_ECHO(f_scara[Y_AXIS]);
x_sin = sin(f_scara[X_AXIS] / SCARA_RAD2DEG) * Linkage_1;
x_cos = cos(f_scara[X_AXIS] / SCARA_RAD2DEG) * Linkage_1;
y_sin = sin(f_scara[Y_AXIS] / SCARA_RAD2DEG) * Linkage_2;
y_cos = cos(f_scara[Y_AXIS] / SCARA_RAD2DEG) * Linkage_2;
//SERIAL_ECHOPGM(" x_sin="); SERIAL_ECHO(x_sin);
//SERIAL_ECHOPGM(" x_cos="); SERIAL_ECHO(x_cos);
//SERIAL_ECHOPGM(" y_sin="); SERIAL_ECHO(y_sin);
//SERIAL_ECHOPGM(" y_cos="); SERIAL_ECHOLN(y_cos);
delta[X_AXIS] = x_cos + y_cos + SCARA_offset_x; //theta
delta[Y_AXIS] = x_sin + y_sin + SCARA_offset_y; //theta+phi
2015-05-13 04:02:19 -05:00
//SERIAL_ECHOPGM(" delta[X_AXIS]="); SERIAL_ECHO(delta[X_AXIS]);
//SERIAL_ECHOPGM(" delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
2015-08-05 06:40:36 -05:00
}
2016-08-20 22:38:32 -05:00
void inverse_kinematics(const float cartesian[XYZ]) {
2016-07-21 17:46:22 -05:00
// Inverse kinematics.
2016-08-20 22:38:32 -05:00
// Perform SCARA IK and place results in delta[].
2016-07-21 17:46:22 -05:00
// The maths and first version were done by QHARLEY.
// Integrated, tweaked by Joachim Cerny in June 2014.
2015-08-05 06:40:36 -05:00
float SCARA_pos[2];
2015-08-05 06:40:36 -05:00
static float SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi;
2016-07-24 18:34:01 -05:00
SCARA_pos[X_AXIS] = RAW_X_POSITION(cartesian[X_AXIS]) * axis_scaling[X_AXIS] - SCARA_offset_x; //Translate SCARA to standard X Y
SCARA_pos[Y_AXIS] = RAW_Y_POSITION(cartesian[Y_AXIS]) * axis_scaling[Y_AXIS] - SCARA_offset_y; // With scaling factor.
2015-08-05 06:40:36 -05:00
#if (Linkage_1 == Linkage_2)
SCARA_C2 = ((sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS])) / (2 * (float)L1_2)) - 1;
#else
SCARA_C2 = (sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) - (float)L1_2 - (float)L2_2) / 45000;
#endif
2015-08-05 06:40:36 -05:00
SCARA_S2 = sqrt(1 - sq(SCARA_C2));
2015-08-05 06:40:36 -05:00
SCARA_K1 = Linkage_1 + Linkage_2 * SCARA_C2;
SCARA_K2 = Linkage_2 * SCARA_S2;
2015-08-05 06:40:36 -05:00
SCARA_theta = (atan2(SCARA_pos[X_AXIS], SCARA_pos[Y_AXIS]) - atan2(SCARA_K1, SCARA_K2)) * -1;
SCARA_psi = atan2(SCARA_S2, SCARA_C2);
2015-08-05 06:40:36 -05:00
delta[X_AXIS] = SCARA_theta * SCARA_RAD2DEG; // Multiply by 180/Pi - theta is support arm angle
delta[Y_AXIS] = (SCARA_theta + SCARA_psi) * SCARA_RAD2DEG; // - equal to sub arm angle (inverted motor)
2016-07-24 18:34:01 -05:00
delta[Z_AXIS] = RAW_Z_POSITION(cartesian[Z_AXIS]);
2015-08-05 06:40:36 -05:00
/**
SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
2015-08-05 06:40:36 -05:00
SERIAL_ECHOPGM("scara x="); SERIAL_ECHO(SCARA_pos[X_AXIS]);
SERIAL_ECHOPGM(" y="); SERIAL_ECHOLN(SCARA_pos[Y_AXIS]);
2015-08-05 06:40:36 -05:00
SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]);
SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]);
SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]);
2015-08-05 06:40:36 -05:00
SERIAL_ECHOPGM("C2="); SERIAL_ECHO(SCARA_C2);
SERIAL_ECHOPGM(" S2="); SERIAL_ECHO(SCARA_S2);
SERIAL_ECHOPGM(" Theta="); SERIAL_ECHO(SCARA_theta);
SERIAL_ECHOPGM(" Psi="); SERIAL_ECHOLN(SCARA_psi);
SERIAL_EOL;
*/
}
#endif // SCARA
#if ENABLED(TEMP_STAT_LEDS)
2015-04-12 20:07:08 -05:00
static bool red_led = false;
static millis_t next_status_led_update_ms = 0;
void handle_status_leds(void) {
2016-04-10 17:55:12 -05:00
if (ELAPSED(millis(), next_status_led_update_ms)) {
2015-04-12 20:07:08 -05:00
next_status_led_update_ms += 500; // Update every 0.5s
2016-08-16 11:19:51 -05:00
float max_temp = 0.0;
#if HAS_TEMP_BED
max_temp = MAX3(max_temp, thermalManager.degTargetBed(), thermalManager.degBed());
#endif
2016-07-09 23:11:17 -05:00
HOTEND_LOOP() {
2016-08-18 22:13:47 -05:00
max_temp = MAX3(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e));
2016-07-09 23:11:17 -05:00
}
2015-04-12 20:07:08 -05:00
bool new_led = (max_temp > 55.0) ? true : (max_temp < 54.0) ? false : red_led;
if (new_led != red_led) {
red_led = new_led;
digitalWrite(STAT_LED_RED, new_led ? HIGH : LOW);
digitalWrite(STAT_LED_BLUE, new_led ? LOW : HIGH);
}
}
}
2015-04-12 20:07:08 -05:00
#endif
void enable_all_steppers() {
enable_x();
enable_y();
enable_z();
enable_e0();
enable_e1();
enable_e2();
enable_e3();
}
void disable_all_steppers() {
2015-04-03 17:31:35 -05:00
disable_x();
disable_y();
disable_z();
disable_e0();
disable_e1();
disable_e2();
disable_e3();
}
2015-05-26 22:08:21 -05:00
/**
* Standard idle routine keeps the machine alive
*/
2016-03-19 00:22:40 -05:00
void idle(
#if ENABLED(FILAMENT_CHANGE_FEATURE)
2016-03-19 00:22:40 -05:00
bool no_stepper_sleep/*=false*/
#endif
) {
2016-06-04 14:29:01 -05:00
lcd_update();
host_keepalive();
2016-03-19 00:22:40 -05:00
manage_inactivity(
#if ENABLED(FILAMENT_CHANGE_FEATURE)
2016-03-19 00:22:40 -05:00
no_stepper_sleep
#endif
);
2016-06-04 14:29:01 -05:00
thermalManager.manage_heater();
2016-04-26 20:13:27 -05:00
#if ENABLED(PRINTCOUNTER)
print_job_timer.tick();
2016-04-26 20:13:27 -05:00
#endif
2016-06-04 14:29:01 -05:00
2016-08-01 23:10:53 -05:00
#if HAS_BUZZER && PIN_EXISTS(BEEPER)
2016-06-04 14:29:01 -05:00
buzzer.tick();
#endif
2015-05-26 22:08:21 -05:00
}
2015-04-03 17:31:35 -05:00
/**
* Manage several activities:
* - Check for Filament Runout
* - Keep the command buffer full
* - Check for maximum inactive time between commands
* - Check for maximum inactive time between stepper commands
* - Check if pin CHDK needs to go LOW
* - Check for KILL button held down
* - Check for HOME button held down
* - Check if cooling fan needs to be switched on
* - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT)
2015-04-03 17:31:35 -05:00
*/
void manage_inactivity(bool ignore_stepper_queue/*=false*/) {
2015-08-05 06:40:36 -05:00
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
2016-07-08 08:00:39 -05:00
if ((IS_SD_PRINTING || print_job_timer.isRunning()) && !(READ(FIL_RUNOUT_PIN) ^ FIL_RUNOUT_INVERTING))
2016-04-18 01:16:49 -05:00
handle_filament_runout();
2015-04-03 17:31:35 -05:00
#endif
if (commands_in_queue < BUFSIZE) get_available_commands();
2015-04-03 17:31:35 -05:00
2015-04-12 20:07:08 -05:00
millis_t ms = millis();
2015-04-03 17:31:35 -05:00
2016-04-10 17:55:12 -05:00
if (max_inactive_time && ELAPSED(ms, previous_cmd_ms + max_inactive_time)) kill(PSTR(MSG_KILLED));
2015-04-03 17:31:35 -05:00
2016-04-10 17:55:12 -05:00
if (stepper_inactive_time && ELAPSED(ms, previous_cmd_ms + stepper_inactive_time)
2016-04-27 20:06:32 -05:00
&& !ignore_stepper_queue && !planner.blocks_queued()) {
#if ENABLED(DISABLE_INACTIVE_X)
disable_x();
#endif
#if ENABLED(DISABLE_INACTIVE_Y)
disable_y();
#endif
#if ENABLED(DISABLE_INACTIVE_Z)
disable_z();
#endif
#if ENABLED(DISABLE_INACTIVE_E)
disable_e0();
disable_e1();
disable_e2();
disable_e3();
#endif
}
#ifdef CHDK // Check if pin should be set to LOW after M240 set it to HIGH
2016-04-10 17:55:12 -05:00
if (chdkActive && PENDING(ms, chdkHigh + CHDK_DELAY)) {
chdkActive = false;
WRITE(CHDK, LOW);
}
#endif
2015-04-03 17:31:35 -05:00
#if HAS_KILL
2015-08-05 06:40:36 -05:00
// Check if the kill button was pressed and wait just in case it was an accidental
// key kill key press
// -------------------------------------------------------------------------------
2015-04-03 17:45:41 -05:00
static int killCount = 0; // make the inactivity button a bit less responsive
const int KILL_DELAY = 750;
2015-04-03 17:31:35 -05:00
if (!READ(KILL_PIN))
killCount++;
else if (killCount > 0)
killCount--;
2015-04-03 17:31:35 -05:00
// Exceeded threshold and we can confirm that it was not accidental
// KILL the machine
// ----------------------------------------------------------------
if (killCount >= KILL_DELAY) kill(PSTR(MSG_KILLED));
#endif
2015-04-03 17:31:35 -05:00
#if HAS_HOME
// Check to see if we have to home, use poor man's debouncer
// ---------------------------------------------------------
2015-04-03 17:45:41 -05:00
static int homeDebounceCount = 0; // poor man's debouncing count
const int HOME_DEBOUNCE_DELAY = 2500;
2015-04-03 17:31:35 -05:00
if (!READ(HOME_PIN)) {
if (!homeDebounceCount) {
2016-02-20 19:35:35 -06:00
enqueue_and_echo_commands_P(PSTR("G28"));
LCD_MESSAGEPGM(MSG_AUTO_HOME);
2015-04-03 17:31:35 -05:00
}
if (homeDebounceCount < HOME_DEBOUNCE_DELAY)
homeDebounceCount++;
else
homeDebounceCount = 0;
}
2015-04-03 17:31:35 -05:00
#endif
2015-08-05 06:40:36 -05:00
2015-04-03 17:31:35 -05:00
#if HAS_CONTROLLERFAN
controllerFan(); // Check if fan should be turned on to cool stepper drivers down
#endif
2015-04-03 17:31:35 -05:00
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
if (ELAPSED(ms, previous_cmd_ms + (EXTRUDER_RUNOUT_SECONDS) * 1000UL)
&& thermalManager.degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP) {
#if ENABLED(SWITCHING_EXTRUDER)
bool oldstatus = E0_ENABLE_READ;
enable_e0();
#else // !SWITCHING_EXTRUDER
bool oldstatus;
switch (active_extruder) {
case 0:
oldstatus = E0_ENABLE_READ;
enable_e0();
break;
#if E_STEPPERS > 1
case 1:
oldstatus = E1_ENABLE_READ;
enable_e1();
break;
#if E_STEPPERS > 2
case 2:
oldstatus = E2_ENABLE_READ;
enable_e2();
break;
#if E_STEPPERS > 3
case 3:
oldstatus = E3_ENABLE_READ;
enable_e3();
break;
#endif
#endif
#endif
}
#endif // !SWITCHING_EXTRUDER
float oldepos = current_position[E_AXIS], oldedes = destination[E_AXIS];
planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS],
destination[E_AXIS] + (EXTRUDER_RUNOUT_EXTRUDE) * (EXTRUDER_RUNOUT_ESTEPS) * planner.steps_to_mm[E_AXIS],
MMM_TO_MMS(EXTRUDER_RUNOUT_SPEED) * (EXTRUDER_RUNOUT_ESTEPS) * planner.steps_to_mm[E_AXIS], active_extruder);
2015-04-03 17:31:35 -05:00
current_position[E_AXIS] = oldepos;
destination[E_AXIS] = oldedes;
2016-05-31 17:39:37 -05:00
planner.set_e_position_mm(oldepos);
2015-04-12 20:07:08 -05:00
previous_cmd_ms = ms; // refresh_cmd_timeout()
stepper.synchronize();
#if ENABLED(SWITCHING_EXTRUDER)
E0_ENABLE_WRITE(oldstatus);
#else
switch (active_extruder) {
case 0:
E0_ENABLE_WRITE(oldstatus);
break;
#if E_STEPPERS > 1
case 1:
E1_ENABLE_WRITE(oldstatus);
break;
#if E_STEPPERS > 2
case 2:
E2_ENABLE_WRITE(oldstatus);
break;
#if E_STEPPERS > 3
case 3:
E3_ENABLE_WRITE(oldstatus);
break;
#endif
#endif
#endif
}
#endif // !SWITCHING_EXTRUDER
}
#endif // EXTRUDER_RUNOUT_PREVENT
2015-04-03 17:31:35 -05:00
#if ENABLED(DUAL_X_CARRIAGE)
// handle delayed move timeout
2016-04-10 17:55:12 -05:00
if (delayed_move_time && ELAPSED(ms, delayed_move_time + 1000UL) && IsRunning()) {
// travel moves have been received so enact them
delayed_move_time = 0xFFFFFFFFUL; // force moves to be done
set_destination_to_current();
prepare_move_to_destination();
}
#endif
2015-04-03 17:31:35 -05:00
#if ENABLED(TEMP_STAT_LEDS)
2015-04-03 17:31:35 -05:00
handle_status_leds();
#endif
2015-04-03 17:31:35 -05:00
2016-04-27 20:06:32 -05:00
planner.check_axes_activity();
}
void kill(const char* lcd_msg) {
2016-07-09 21:50:45 -05:00
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_KILLED);
#if ENABLED(ULTRA_LCD)
2016-07-09 21:50:45 -05:00
kill_screen(lcd_msg);
2015-10-04 10:33:55 -05:00
#else
UNUSED(lcd_msg);
#endif
2016-08-08 23:49:34 -05:00
delay(500); // Wait a short time
2016-07-09 21:50:45 -05:00
cli(); // Stop interrupts
2016-04-28 20:18:13 -05:00
thermalManager.disable_all_heaters();
disable_all_steppers();
2015-03-30 18:50:05 -05:00
#if HAS_POWER_SWITCH
pinMode(PS_ON_PIN, INPUT);
#endif
suicide();
while (1) {
#if ENABLED(USE_WATCHDOG)
watchdog_reset();
#endif
} // Wait for reset
}
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
2015-04-13 19:17:36 -05:00
2016-04-18 01:16:49 -05:00
void handle_filament_runout() {
if (!filament_ran_out) {
filament_ran_out = true;
2016-02-20 19:35:35 -06:00
enqueue_and_echo_commands_P(PSTR(FILAMENT_RUNOUT_SCRIPT));
stepper.synchronize();
2015-04-13 19:17:36 -05:00
}
}
#endif // FILAMENT_RUNOUT_SENSOR
#if ENABLED(FAST_PWM_FAN)
void setPwmFrequency(uint8_t pin, int val) {
val &= 0x07;
switch (digitalPinToTimer(pin)) {
#if defined(TCCR0A)
case TIMER0A:
case TIMER0B:
// TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02));
// TCCR0B |= val;
break;
#endif
#if defined(TCCR1A)
case TIMER1A:
case TIMER1B:
// TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
// TCCR1B |= val;
break;
#endif
#if defined(TCCR2)
case TIMER2:
case TIMER2:
TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
TCCR2 |= val;
break;
#endif
#if defined(TCCR2A)
case TIMER2A:
case TIMER2B:
TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22));
TCCR2B |= val;
break;
#endif
#if defined(TCCR3A)
case TIMER3A:
case TIMER3B:
case TIMER3C:
TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32));
TCCR3B |= val;
break;
#endif
#if defined(TCCR4A)
case TIMER4A:
case TIMER4B:
case TIMER4C:
TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42));
TCCR4B |= val;
break;
#endif
#if defined(TCCR5A)
case TIMER5A:
case TIMER5B:
case TIMER5C:
TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
TCCR5B |= val;
break;
#endif
}
}
#endif // FAST_PWM_FAN
2016-04-18 02:05:22 -05:00
void stop() {
2016-04-28 20:18:13 -05:00
thermalManager.disable_all_heaters();
if (IsRunning()) {
Running = false;
Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
LCD_MESSAGEPGM(MSG_STOPPED);
}
}
float calculate_volumetric_multiplier(float diameter) {
if (!volumetric_enabled || diameter == 0) return 1.0;
float d2 = diameter * 0.5;
return 1.0 / (M_PI * d2 * d2);
}
void calculate_volumetric_multipliers() {
for (uint8_t i = 0; i < COUNT(filament_size); i++)
volumetric_multiplier[i] = calculate_volumetric_multiplier(filament_size[i]);
}