Commit 29152ccf authored by MagoKimbra's avatar MagoKimbra

Update 4.1.2

parent 6a9edf74
......@@ -350,14 +350,21 @@
/**
* MAX_STEP_FREQUENCY differs for TOSHIBA
*/
#ifdef CONFIG_STEPPERS_TOSHIBA
#define MAX_STEP_FREQUENCY 10000 // Max step frequency for Toshiba Stepper Controllers
#define DOUBLE_STEP_FREQUENCY 10000
#elif defined (__SAM3X8E__)
#define MAX_STEP_FREQUENCY 320000
#define DOUBLE_STEP_FREQUENCY 90000 //96kHz is close to maximum for an Arduino Due
#ifdef __SAM3X8E__
#ifdef CONFIG_STEPPERS_TOSHIBA
#define MAX_STEP_FREQUENCY 120000 // Max step frequency for Toshiba Stepper Controllers
#define DOUBLE_STEP_FREQUENCY MAX_STEP_FREQUENCY
#else
#define MAX_STEP_FREQUENCY 480000
#define DOUBLE_STEP_FREQUENCY 120000 //96kHz is close to maximum for an Arduino Due
#endif
#else
#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Arduino mega
#ifdef CONFIG_STEPPERS_TOSHIBA
#define MAX_STEP_FREQUENCY 10000 // Max step frequency for Toshiba Stepper Controllers
#define DOUBLE_STEP_FREQUENCY MAX_STEP_FREQUENCY
#else
#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Arduino mega
#endif
#endif
// MS1 MS2 Stepper Driver Microstepping mode table
......
......@@ -9,18 +9,18 @@
// Mechanisms-settings can be found in configuration_xxxxxx.h
// Advanced settings can be found in Configuration_adv.h
#include "boards.h"
// Choose your board type.
// Either an numeric ID or name defined in boards.h is valid.
// See: https://github.com/MagoKimbra/MarlinKimbra/blob/master/Documentation/Hardware.md
#include "boards.h"
#ifndef MOTHERBOARD
#define MOTHERBOARD BOARD_RAMPS_13_EFB
#endif
#define MOTHERBOARD BOARD_RAMPS_13_EFB
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "4.1.0"
#define STRING_VERSION "4.1.2"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
......@@ -53,7 +53,11 @@
//#define COREXY
//#define DELTA
//#define SCARA
/***********************************************************************\
/***********************************************************************\
********************** Do not touch this section **********************
***********************************************************************/
#if defined(CARTESIAN)
#include "Configuration_Cartesian.h"
#elif defined(COREXY)
......@@ -68,6 +72,9 @@
// This defines the number of extruder real or virtual
#define EXTRUDERS 1
// This defines the number of Driver extruder you have and use
#define DRIVER_EXTRUDERS 1
// This is used for single nozzle and multiple extrusion configuration
// Uncomment below to enable (One Hotend)
//#define SINGLENOZZLE
......@@ -77,40 +84,29 @@
***********************************************************************
* *
* Setting for more extruder width relay system *
* *
* Firmware by MagoKimbra magokimbra@hotmail.com *
* *
* See pins.h for pin command relay *
* *
***********************************************************************/
//#define MKR4
#ifdef MKR4
#define DRIVER_EXTRUDERS 2 // This defines the number of Driver extruder
#endif // END MKR4
//**********************************************************************
/***********************************************************************
*********************** Multiextruder NPr2 ***************************
***********************************************************************
* *
* Setting fot color meccanism NPr2 by NicolaP (www.3dmakerlab.it) *
* *
* Firmware by MagoKimbra magokimbra@hotmail.com *
* *
* Find angle setting by g-Code "M997 Cxxx" *
* *
***********************************************************************/
//#define NPR2
#ifdef NPR2
#define COLOR_STEP {120,25,-65,-155} // CARTER ANGLE
#define COLOR_SLOWRATE 170 // MICROSECOND delay for carter motor routine (Carter Motor Feedrate: upper value-slow feedrate)
#define COLOR_HOMERATE 4 // FEEDRATE for carter home
#define MOTOR_ANGLE 1.8 // Nema angle for single step
#define DRIVER_MICROSTEP 4 // Microstep moltiplicator driver (set jumper MS1-2-3) off-on-off 1/4 microstepping.
#define CARTER_MOLTIPLICATOR 14.22 // CARTER MOLTIPLICATOR (gear ratio 13/31-10/31)
#define DRIVER_EXTRUDERS 2 // This defines the number of Driver extruders
#endif
#define COLOR_STEP {120,25,-65,-155} // CARTER ANGLE
#define COLOR_SLOWRATE 170 // MICROSECOND delay for carter motor routine (Carter Motor Feedrate: upper value-slow feedrate)
#define COLOR_HOMERATE 4 // FEEDRATE for carter home
#define MOTOR_ANGLE 1.8 // Nema angle for single step
#define DRIVER_MICROSTEP 4 // Microstep moltiplicator driver (set jumper MS1-2-3) off-on-off 1/4 microstepping.
#define CARTER_MOLTIPLICATOR 14.22 // CARTER MOLTIPLICATOR (gear ratio 13/31-10/31)
//**********************************************************************
......@@ -123,6 +119,7 @@
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
......@@ -147,7 +144,7 @@
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300C for hotend "Simple ONE " & "Hotend "All In ONE"
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
......@@ -161,7 +158,7 @@
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25C or the temperature defined below.
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
......@@ -207,32 +204,31 @@
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all hotend) HOTEND_WATTS
//#define HOTEND_WATTS (12.0*12.0/6.7) // P=I^2/R
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
//===========================================================================
//============================= PID Settings ================================
//===========================================================================
// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning
// Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#ifdef PIDTEMP
//#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
// If the temperature difference between the target temperature and the actual temperature
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_FUNCTIONAL_RANGE 10 // degC
#define PID_INTEGRAL_DRIVE_MAX PID_MAX // Limit for the integral term
#define K1 0.95 // Smoothing factor within the PID
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
//#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
// If the temperature difference between the target temperature and the actual temperature
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_FUNCTIONAL_RANGE 10 // degC
#define PID_INTEGRAL_DRIVE_MAX PID_MAX // Limit for the integral term
#define K1 0.95 // Smoothing factor within the PID
// HotEnd{HE0,HE1,HE2,HE3}
#define DEFAULT_Kp {40, 40, 40, 40} // Kp for E0, E1, E2, E3
#define DEFAULT_Ki {07, 07, 07, 07} // Ki for E0, E1, E2, E3
#define DEFAULT_Kd {60, 60, 60, 60} // Kd for E0, E1, E2, E3
#define DEFAULT_Kp {40, 40, 40, 40} // Kp for E0, E1, E2, E3
#define DEFAULT_Ki {07, 07, 07, 07} // Ki for E0, E1, E2, E3
#define DEFAULT_Kd {60, 60, 60, 60} // Kd for E0, E1, E2, E3
//===========================================================================
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
......@@ -257,13 +253,11 @@
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#ifdef PIDTEMPBED
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
......@@ -272,7 +266,7 @@
// #define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
//===========================================================================
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
......@@ -284,6 +278,7 @@
#define EXTRUDE_MINTEMP 170 // degC
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//===========================================================================
......@@ -389,10 +384,7 @@ your extruder heater takes 2 minutes to hit the target on heating.
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
//#define RA_CONTROL_PANEL
/**
* I2C Panels
*/
// I2C Panels
//#define LCD_I2C_SAINSMART_YWROBOT
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
......@@ -421,9 +413,8 @@ your extruder heater takes 2 minutes to hit the target on heating.
0 = Voltage level 3.3V
1 = Voltage level 5V
*/
#if MB(ALLIGATOR)
#define UI_VOLTAGE_LEVEL 0 // Set 5 o 3.3 V
#endif
#define UI_VOLTAGE_LEVEL 0 // Set 5 o 3.3 V
//============================== Languages UI =========================
// 1 English
......@@ -459,21 +450,35 @@ your extruder heater takes 2 minutes to hit the target on heating.
// to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
// please keep turned on if you can.
//#define DISABLE_M503
//===========================================================================
//====================== EXTRA SETTINGS ON SD ===============================
// Uncomment SD_SETTINGS to enable the firmware to write some configuration,
// that require frequent update, on the SD card.
//#define SD_SETTINGS
#define SD_CFG_SECONDS 60 //seconds between update
#define CFG_SD_FILE "info.cfg" //name of the configuration file
#define CFG_SD_MAX_KEY_LEN 3+1 //icrease this if you add key name longer than the actual value.
#define CFG_SD_MAX_VALUE_LEN 12+1 //this should be enought for int, long and float if you need to retrive strings increase this carefully
//===========================================================================
//========================= Bowden Filament management ======================
//==================== Bowden Filament management ===========================
//#define EASY_LOAD
#ifdef EASY_LOAD
#define BOWDEN_LENGTH 250 // mm
#define LCD_PURGE_LENGTH 3 // mm
#define LCD_RETRACT_LENGTH 3 // mm
#define LCD_PURGE_FEEDRATE 3 // mm/s
#define LCD_RETRACT_FEEDRATE 10 // mm/s
#define LCD_LOAD_FEEDRATE 8 // mm/s
#define LCD_UNLOAD_FEEDRATE 8 // mm/s
#endif //EASY_LOAD
//============================== Preheat Constants ==========================
#define BOWDEN_LENGTH 250 // mm
#define LCD_PURGE_LENGTH 3 // mm
#define LCD_RETRACT_LENGTH 3 // mm
#define LCD_PURGE_FEEDRATE 3 // mm/s
#define LCD_RETRACT_FEEDRATE 10 // mm/s
#define LCD_LOAD_FEEDRATE 8 // mm/s
#define LCD_UNLOAD_FEEDRATE 8 // mm/s
//===========================================================================
//====================== Preheat Constants ==================================
#define PLA_PREHEAT_HOTEND_TEMP 190
#define PLA_PREHEAT_HPB_TEMP 60
#define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
......@@ -485,6 +490,7 @@ your extruder heater takes 2 minutes to hit the target on heating.
#define GUM_PREHEAT_HOTEND_TEMP 230
#define GUM_PREHEAT_HPB_TEMP 60
#define GUM_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//===========================================================================
//============================= R/C Servo support ===========================
......@@ -500,6 +506,7 @@ your extruder heater takes 2 minutes to hit the target on heating.
//
#define SERVO_ENDSTOPS {-1,-1,0} // Servo index for X, Y, Z. Disable with -1
#define SERVO_ENDSTOP_ANGLES {0,0,0,0,90,0} // X,Y,Z Axis Extend and Retract angles
//===========================================================================
/**********************************************************************\
......@@ -529,6 +536,7 @@ your extruder heater takes 2 minutes to hit the target on heating.
//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status. Status will appear for 5 sec.
//#define FILAMENT_LCD_DISPLAY
//===========================================================================
/**********************************************************************\
......@@ -555,6 +563,8 @@ your extruder heater takes 2 minutes to hit the target on heating.
//When using an LCD, uncomment the line below to display the Power consumption sensor data on the last line instead of status. Status will appear for 5 sec.
//#define POWER_CONSUMPTION_LCD_DISPLAY
//===========================================================================
//=================================== Misc =================================
......@@ -593,6 +603,7 @@ your extruder heater takes 2 minutes to hit the target on heating.
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
//===========================================================================
//============================= Filament Runout Sensor ======================
//===========================================================================
......@@ -607,8 +618,8 @@ your extruder heater takes 2 minutes to hit the target on heating.
//===========================================================================
//============================= Laser Beam Support ==========================
//===========================================================================
// define laser beam support
//#define LASERBEAM
//===========================================================================
#include "Configuration_adv.h"
......
......@@ -14,10 +14,10 @@
*
*/
#define EEPROM_VERSION "V20"
#define EEPROM_VERSION "V21"
/**
* V20 EEPROM Layout:
* V21 EEPROM Layout:
*
* ver
* axis_steps_per_unit (x7)
......@@ -92,7 +92,6 @@
*
* idleoozing_enabled
*
* power_consumption_hour
*
*
*/
......@@ -101,6 +100,7 @@
#include "planner.h"
#include "temperature.h"
#include "ultralcd.h"
#include "cardreader.h"
#include "ConfigurationStore.h"
void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size) {
......@@ -109,8 +109,7 @@ void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size) {
eeprom_write_byte((unsigned char*)pos, *value);
c = eeprom_read_byte((unsigned char*)pos);
if (c != *value) {
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE);
ECHO_LM(ER, MSG_ERR_EEPROM_WRITE);
}
pos++;
value++;
......@@ -260,18 +259,13 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, idleoozing_enabled);
#endif
#if defined(POWER_CONSUMPTION) && defined(STORE_CONSUMPTION)
EEPROM_WRITE_VAR(i, power_consumption_hour);
#endif
char ver2[4] = EEPROM_VERSION;
int j = EEPROM_OFFSET;
EEPROM_WRITE_VAR(j, ver2); // validate data
// Report storage size
SERIAL_ECHO_START;
SERIAL_ECHOPAIR("Settings Stored (", (unsigned long)i);
SERIAL_ECHOLNPGM(" bytes)");
ECHO_SMV(DB, "Settings Stored (", i);
ECHO_EM(" bytes)");
}
void Config_RetrieveSettings() {
......@@ -280,7 +274,6 @@ void Config_RetrieveSettings() {
char stored_ver[4];
char ver[4] = EEPROM_VERSION;
EEPROM_READ_VAR(i, stored_ver); //read stored version
// SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]");
if (strncmp(ver, stored_ver, 3) != 0) {
Config_ResetDefault();
......@@ -419,18 +412,13 @@ void Config_RetrieveSettings() {
EEPROM_READ_VAR(i, idleoozing_enabled);
#endif
#if defined(POWER_CONSUMPTION) && defined(STORE_CONSUMPTION)
EEPROM_READ_VAR(i, power_consumption_hour);
#endif
// Call updatePID (similar to when we have processed M301)
updatePID();
// Report settings retrieved and length
SERIAL_ECHO_START;
SERIAL_ECHO(ver);
SERIAL_ECHOPAIR(" stored settings retrieved (", (unsigned long)i);
SERIAL_ECHOLNPGM(" bytes)");
ECHO_SV(DB, ver);
ECHO_MV(" stored settings retrieved (", i);
ECHO_EM(" bytes)");
}
#ifdef EEPROM_CHITCHAT
......@@ -567,12 +555,15 @@ void Config_ResetDefault() {
idleoozing_enabled = true;
#endif
#if defined(POWER_CONSUMPTION) && defined(STORE_CONSUMPTION)
power_consumption_hour = 0;
#endif
ECHO_LM(DB, "Hardcoded Default Settings Loaded");
}
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Hardcoded Default Settings Loaded");
void ConfigSD_ResetDefault() {
#ifdef POWER_CONSUMPTION
power_consumption_hour = 0;
#endif
printer_usage_seconds = 0;
ECHO_LM(DB, "Hardcoded SD Default Settings Loaded");
}
#ifndef DISABLE_M503
......@@ -581,303 +572,317 @@ void Config_PrintSettings(bool forReplay) {
// Always have this function, even with EEPROM_SETTINGS disabled, the current values will be shown
if (!forReplay) {
SERIAL_ECHOLNPGM("Steps per unit:");
SERIAL_ECHO_START;
ECHO_LM(DB, "Steps per unit:");
}
SERIAL_ECHOPAIR(" M92 X", axis_steps_per_unit[X_AXIS]);
SERIAL_ECHOPAIR(" Y", axis_steps_per_unit[Y_AXIS]);
SERIAL_ECHOPAIR(" Z", axis_steps_per_unit[Z_AXIS]);
SERIAL_ECHOPAIR(" E0 S", axis_steps_per_unit[E_AXIS + 0]);
ECHO_SMV(DB, " M92 X", axis_steps_per_unit[X_AXIS]);
ECHO_MV(" Y", axis_steps_per_unit[Y_AXIS]);
ECHO_MV(" Z", axis_steps_per_unit[Z_AXIS]);
ECHO_MV(" E0 S", axis_steps_per_unit[E_AXIS + 0]);
#if EXTRUDERS > 1
SERIAL_ECHOPAIR(" E1 S", axis_steps_per_unit[E_AXIS + 1]);
ECHO_MV(" E1 S", axis_steps_per_unit[E_AXIS + 1]);
#if EXTRUDERS > 2
SERIAL_ECHOPAIR(" E2 S", axis_steps_per_unit[E_AXIS + 2]);
ECHO_MV(" E2 S", axis_steps_per_unit[E_AXIS + 2]);
#if EXTRUDERS > 3
SERIAL_ECHOPAIR(" E3 S", axis_steps_per_unit[E_AXIS + 3]);
ECHO_MV(" E3 S", axis_steps_per_unit[E_AXIS + 3]);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
SERIAL_EOL;
SERIAL_ECHO_START;
ECHO_E;
#ifdef SCARA
if (!forReplay) {
SERIAL_ECHOLNPGM("Scaling factors:");
SERIAL_ECHO_START;
ECHO_LM(DB, "Scaling factors:");
}
SERIAL_ECHOPAIR(" M365 X", axis_scaling[X_AXIS]);
SERIAL_ECHOPAIR(" Y", axis_scaling[Y_AXIS]);
SERIAL_ECHOPAIR(" Z", axis_scaling[Z_AXIS]);
SERIAL_EOL;
SERIAL_ECHO_START;
ECHO_SMV(DB, " M365 X", axis_scaling[X_AXIS]);
ECHO_MV(" Y", axis_scaling[Y_AXIS]);
ECHO_EMV(" Z", axis_scaling[Z_AXIS]);
#endif // SCARA
if (!forReplay) {
SERIAL_ECHOLNPGM("Maximum feedrates (mm/s):");
SERIAL_ECHO_START;
ECHO_LM(DB, "Maximum feedrates (mm/s):");
}
SERIAL_ECHOPAIR(" M203 X", max_feedrate[X_AXIS]);
SERIAL_ECHOPAIR(" Y", max_feedrate[Y_AXIS] );
SERIAL_ECHOPAIR(" Z", max_feedrate[Z_AXIS] );
SERIAL_ECHOPAIR(" E0 S", max_feedrate[E_AXIS + 0]);
ECHO_SMV(DB, " M203 X", max_feedrate[X_AXIS]);
ECHO_MV(" Y", max_feedrate[Y_AXIS] );
ECHO_MV(" Z", max_feedrate[Z_AXIS] );
ECHO_MV(" E0 S", max_feedrate[E_AXIS + 0]);
#if EXTRUDERS > 1
SERIAL_ECHOPAIR(" E1 S", max_feedrate[E_AXIS + 1]);
ECHO_MV(" E1 S", max_feedrate[E_AXIS + 1]);
#if EXTRUDERS > 2
SERIAL_ECHOPAIR(" E2 S", max_feedrate[E_AXIS + 2]);
ECHO_MV(" E2 S", max_feedrate[E_AXIS + 2]);
#if EXTRUDERS > 3
SERIAL_ECHOPAIR(" E3 S", max_feedrate[E_AXIS + 3]);
ECHO_MV(" E3 S", max_feedrate[E_AXIS + 3]);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
SERIAL_EOL;
ECHO_E;
SERIAL_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Retraction Steps per unit:");
SERIAL_ECHO_START;
ECHO_LM(DB, "Retraction Steps per unit:");
}
SERIAL_ECHOPAIR(" E0 ",max_retraction_feedrate[0]);
ECHO_SMV(DB, " E0 ",max_retraction_feedrate[0]);
#if EXTRUDERS > 1
SERIAL_ECHOPAIR(" E1 ", max_retraction_feedrate[1]);
ECHO_MV(" E1 ", max_retraction_feedrate[1]);
#if EXTRUDERS > 2
SERIAL_ECHOPAIR(" E2 ", max_retraction_feedrate[2]);
ECHO_MV(" E2 ", max_retraction_feedrate[2]);
#if EXTRUDERS > 3
SERIAL_ECHOPAIR(" E3 ", max_retraction_feedrate[3]);
ECHO_MV(" E3 ", max_retraction_feedrate[3]);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
SERIAL_EOL;
ECHO_E;
SERIAL_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Maximum Acceleration (mm/s2):");
SERIAL_ECHO_START;
ECHO_LM(DB, "Maximum Acceleration (mm/s2):");
}
SERIAL_ECHOPAIR(" M201 X", max_acceleration_units_per_sq_second[X_AXIS] );
SERIAL_ECHOPAIR(" Y", max_acceleration_units_per_sq_second[Y_AXIS] );
SERIAL_ECHOPAIR(" Z", max_acceleration_units_per_sq_second[Z_AXIS] );
SERIAL_ECHOPAIR(" E0 S", max_acceleration_units_per_sq_second[E_AXIS]);
ECHO_SMV(DB, " M201 X", max_acceleration_units_per_sq_second[X_AXIS] );
ECHO_MV(" Y", max_acceleration_units_per_sq_second[Y_AXIS] );
ECHO_MV(" Z", max_acceleration_units_per_sq_second[Z_AXIS] );
ECHO_MV(" E0 S", max_acceleration_units_per_sq_second[E_AXIS]);
#if EXTRUDERS > 1
SERIAL_ECHOPAIR(" E1 S", max_acceleration_units_per_sq_second[E_AXIS+1]);
ECHO_MV(" E1 S", max_acceleration_units_per_sq_second[E_AXIS+1]);
#if EXTRUDERS > 2
SERIAL_ECHOPAIR(" E2 S", max_acceleration_units_per_sq_second[E_AXIS+2]);
ECHO_MV(" E2 S", max_acceleration_units_per_sq_second[E_AXIS+2]);
#if EXTRUDERS > 3
SERIAL_ECHOPAIR(" E3 S", max_acceleration_units_per_sq_second[E_AXIS+3]);
ECHO_MV(" E3 S", max_acceleration_units_per_sq_second[E_AXIS+3]);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
SERIAL_EOL;
SERIAL_ECHO_START;
ECHO_E;
if (!forReplay) {
SERIAL_ECHOLNPGM("Accelerations: P=printing, R=retract and T=travel");
SERIAL_ECHO_START;
ECHO_LM(DB, "Accelerations: P=printing, R=retract and T=travel");
}
SERIAL_ECHOPAIR(" M204 P", acceleration );
SERIAL_ECHOPAIR(" R", retract_acceleration);
SERIAL_ECHOPAIR(" T", travel_acceleration);
SERIAL_EOL;
ECHO_SMV(DB," M204 P", acceleration );
ECHO_MV(" R", retract_acceleration);
ECHO_EMV(" T", travel_acceleration);
SERIAL_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum XY jerk (mm/s), Z=maximum Z jerk (mm/s), E=maximum E jerk (mm/s)");
SERIAL_ECHO_START;
ECHO_LM(DB, "Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum XY jerk (mm/s), Z=maximum Z jerk (mm/s), E=maximum E jerk (mm/s)");
}
SERIAL_ECHOPAIR(" M205 S", minimumfeedrate );
SERIAL_ECHOPAIR(" T", mintravelfeedrate );
SERIAL_ECHOPAIR(" B", minsegmenttime );
SERIAL_ECHOPAIR(" X", max_xy_jerk );
SERIAL_ECHOPAIR(" Z", max_z_jerk);
SERIAL_ECHOPAIR(" E", max_e_jerk);
SERIAL_EOL;
SERIAL_ECHO_START;
ECHO_SMV(DB, " M205 S", minimumfeedrate );
ECHO_MV(" T", mintravelfeedrate );
ECHO_MV(" B", minsegmenttime );
ECHO_MV(" X", max_xy_jerk );
ECHO_MV(" Z", max_z_jerk);
ECHO_EMV(" E", max_e_jerk);
if (!forReplay) {
SERIAL_ECHOLNPGM("Home offset (mm):");
SERIAL_ECHO_START;
ECHO_LM(DB, "Home offset (mm):");
}
SERIAL_ECHOPAIR(" M206 X", home_offset[X_AXIS] );
SERIAL_ECHOPAIR(" Y", home_offset[Y_AXIS] );
SERIAL_ECHOPAIR(" Z", home_offset[Z_AXIS] );
SERIAL_EOL;
ECHO_SMV(DB, " M206 X", home_offset[X_AXIS] );
ECHO_MV(" Y", home_offset[Y_AXIS] );
ECHO_EMV(" Z", home_offset[Z_AXIS] );
SERIAL_ECHO_START;
#if HOTENDS > 1
if (!forReplay) {
SERIAL_ECHOLNPGM("Hotend offset (mm):");
SERIAL_ECHO_START;
ECHO_LM(DB, "Hotend offset (mm):");
}
for (int e = 0; e < HOTENDS; e++) {
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M218 T", (long unsigned int)e);
SERIAL_ECHOPAIR(" X", hotend_offset[X_AXIS][e]);
SERIAL_ECHOPAIR(" Y" ,hotend_offset[Y_AXIS][e]);
SERIAL_EOL;
ECHO_SMV(DB, " M218 T", e);
ECHO_MV(" X", hotend_offset[X_AXIS][e]);
ECHO_EMV(" Y" ,hotend_offset[Y_AXIS][e]);
}
#endif //HOTENDS > 1
#ifdef DELTA
SERIAL_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Endstop adjustement (mm):");
SERIAL_ECHO_START;
ECHO_LM(DB, "Endstop adjustement (mm):");
}
ECHO_SMV(DB, " M666 X", endstop_adj[X_AXIS] );
ECHO_MV(" Y", endstop_adj[Y_AXIS] );
ECHO_EMV(" Z", endstop_adj[Z_AXIS] );
if (!forReplay) {
ECHO_LM(DB, "Delta Geometry adjustment:");
}
ECHO_SMV(DB, " M666 A", tower_adj[0]);
ECHO_MV(" B", tower_adj[1]);
ECHO_MV(" C", tower_adj[2]);
ECHO_MV(" E", tower_adj[3]);
ECHO_MV(" F", tower_adj[4]);
ECHO_MV(" G", tower_adj[5]);
ECHO_MV(" R", delta_radius);
ECHO_MV(" D", delta_diagonal_rod);
ECHO_MV(" H", max_pos[2]);
ECHO_EMV(" P", z_probe_offset[3]);
if (!forReplay) {
ECHO_LM(DB, "Tower Positions:");
}
SERIAL_ECHOPAIR(" M666 X", endstop_adj[X_AXIS] );
SERIAL_ECHOPAIR(" Y", endstop_adj[Y_AXIS] );
SERIAL_ECHOPAIR(" Z", endstop_adj[Z_AXIS] );
SERIAL_EOL;
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Delta Geometry adjustment:");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M666 A", tower_adj[0]);
SERIAL_ECHOPAIR(" B", tower_adj[1]);
SERIAL_ECHOPAIR(" C", tower_adj[2]);
SERIAL_ECHOPAIR(" E", tower_adj[3]);
SERIAL_ECHOPAIR(" F", tower_adj[4]);
SERIAL_ECHOPAIR(" G", tower_adj[5]);
SERIAL_ECHOPAIR(" R", delta_radius);
SERIAL_ECHOPAIR(" D", delta_diagonal_rod);
SERIAL_ECHOPAIR(" H", max_pos[2]);
SERIAL_ECHOPAIR(" P", z_probe_offset[3]);
SERIAL_EOL;
SERIAL_ECHOLN("Tower Positions");
SERIAL_ECHOPAIR("Tower1 X:", delta_tower1_x);
SERIAL_ECHOPAIR(" Y:", delta_tower1_y);
SERIAL_EOL;
SERIAL_ECHOPAIR("Tower2 X:", delta_tower2_x);
SERIAL_ECHOPAIR(" Y:", delta_tower2_y);
SERIAL_EOL;
SERIAL_ECHOPAIR("Tower3 X:", delta_tower3_x);
SERIAL_ECHOPAIR(" Y:", delta_tower3_y);
SERIAL_EOL;
ECHO_SMV(DB, " Tower1 X:", delta_tower1_x);
ECHO_MV(" Y:", delta_tower1_y);
ECHO_MV(" Tower2 X:", delta_tower2_x);
ECHO_MV(" Y:", delta_tower2_y);
ECHO_MV(" Tower3 X:", delta_tower3_x);
ECHO_EMV(" Y:", delta_tower3_y);
#elif defined(Z_DUAL_ENDSTOPS)
SERIAL_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Z2 Endstop adjustement (mm):");
SERIAL_ECHO_START;
ECHO_LM(DB, "Z2 Endstop adjustement (mm):");
}
SERIAL_ECHOPAIR(" M666 Z", z_endstop_adj );
SERIAL_EOL;
ECHO_LMV(DB, " M666 Z", z_endstop_adj );
#elif defined(ENABLE_AUTO_BED_LEVELING)
SERIAL_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Z Probe offset (mm)");
SERIAL_ECHO_START;
ECHO_LM(DB, "Z Probe offset (mm)");
}
SERIAL_ECHOPAIR(" M666 P", zprobe_zoffset);
SERIAL_EOL;
ECHO_LMV(DB, " M666 P", zprobe_zoffset);
#endif // DELTA
#if defined(PIDTEMP) || defined(PIDTEMPBED)
SERIAL_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("PID settings:");
SERIAL_ECHO_START;
ECHO_LM(DB, "PID settings:");
}
#if defined(PIDTEMP) && defined(PIDTEMPBED)
SERIAL_EOL;
#endif
#ifdef PIDTEMP
for (int e = 0; e < HOTENDS; e++) {
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M301 E", (long unsigned int)e);
SERIAL_ECHOPAIR(" P", PID_PARAM(Kp, e));
SERIAL_ECHOPAIR(" I", unscalePID_i(PID_PARAM(Ki, e)));
SERIAL_ECHOPAIR(" D", unscalePID_d(PID_PARAM(Kd, e)));
SERIAL_EOL;
ECHO_SMV(DB, " M301 E", e);
ECHO_MV(" P", PID_PARAM(Kp, e));
ECHO_MV(" I", unscalePID_i(PID_PARAM(Ki, e)));
ECHO_EMV(" D", unscalePID_d(PID_PARAM(Kd, e)));
}
#endif
#ifdef PIDTEMPBED
SERIAL_ECHOPAIR(" M304 P", bedKp); // for compatibility with hosts, only echos values for E0
SERIAL_ECHOPAIR(" I", unscalePID_i(bedKi));
SERIAL_ECHOPAIR(" D", unscalePID_d(bedKd));
SERIAL_EOL;
ECHO_SMV(" M304 P", bedKp); // for compatibility with hosts, only echos values for E0
ECHO_MV(" I", unscalePID_i(bedKi));
ECHO_EMV(" D", unscalePID_d(bedKd));
#endif
#endif
#ifdef FWRETRACT
SERIAL_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Retract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)");
SERIAL_ECHO_START;
ECHO_LM(DB,"Retract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)");
}
SERIAL_ECHOPAIR(" M207 S", retract_length);
SERIAL_ECHOPAIR(" F", retract_feedrate*60);
SERIAL_ECHOPAIR(" Z", retract_zlift);
SERIAL_EOL;
SERIAL_ECHO_START;
ECHO_SMV(DB, " M207 S", retract_length);
ECHO_MV(" F", retract_feedrate*60);
ECHO_EMV(" Z", retract_zlift);
if (!forReplay) {
SERIAL_ECHOLNPGM("Recover: S=Extra length (mm) F:Speed (mm/m)");
SERIAL_ECHO_START;
ECHO_LM(DB, "Recover: S=Extra length (mm) F:Speed (mm/m)");
}
SERIAL_ECHOPAIR(" M208 S", retract_recover_length);
SERIAL_ECHOPAIR(" F", retract_recover_feedrate*60);
SERIAL_EOL;
SERIAL_ECHO_START;
ECHO_SMV(DB, " M208 S", retract_recover_length);
ECHO_MV(" F", retract_recover_feedrate*60);
if (!forReplay) {
SERIAL_ECHOLNPGM("Auto-Retract: S=0 to disable, 1 to interpret extrude-only moves as retracts or recoveries");
SERIAL_ECHO_START;
ECHO_LM(DB,"Auto-Retract: S=0 to disable, 1 to interpret extrude-only moves as retracts or recoveries");
}
SERIAL_ECHOPAIR(" M209 S", (unsigned long)(autoretract_enabled ? 1 : 0));
SERIAL_EOL;
ECHO_LMV(DB," M209 S", autoretract_enabled);
#if EXTRUDERS > 1
if (!forReplay) {
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Multi-extruder settings:");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" Swap retract length (mm): ", retract_length_swap);
SERIAL_EOL;
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" Swap rec. addl. length (mm): ", retract_recover_length_swap);
SERIAL_EOL;
ECHO_LM(DB,"Multi-extruder settings:");
ECHO_LMV(DB, " Swap retract length (mm): ", retract_length_swap);
ECHO_LMV(DB, " Swap rec. addl. length (mm): ", retract_recover_length_swap);
}
#endif // EXTRUDERS > 1
#endif // FWRETRACT
SERIAL_ECHO_START;
if (volumetric_enabled) {
if (!forReplay) {
SERIAL_ECHOLNPGM("Filament settings:");
SERIAL_ECHO_START;
ECHO_LM(DB, "Filament settings:");
}
SERIAL_ECHOPAIR(" M200 D", filament_size[0]);
SERIAL_EOL;
ECHO_LMV(DB, " M200 D", filament_size[0]);
#if EXTRUDERS > 1
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M200 T1 D", filament_size[1]);
SERIAL_EOL;
ECHO_LMV(DB, " M200 T1 D", filament_size[1]);
#if EXTRUDERS > 2
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M200 T2 D", filament_size[2]);
SERIAL_EOL;
ECHO_LMV(DB, " M200 T2 D", filament_size[2]);
#if EXTRUDERS > 3
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M200 T3 D", filament_size[3]);
SERIAL_EOL;
ECHO_LMV(DB, " M200 T3 D", filament_size[3]);
#endif
#endif
#endif
} else {
if (!forReplay) {
SERIAL_ECHOLNPGM("Filament settings: Disabled");
ECHO_LM(DB, "Filament settings: Disabled");
}
}
ConfigSD_PrintSettings(forReplay);
}
#if defined(POWER_CONSUMPTION) && defined(STORE_CONSUMPTION)
SERIAL_ECHO_START;
void ConfigSD_PrintSettings(bool forReplay) {
// Always have this function, even with SD_SETTINGS disabled, the current values will be shown
#ifdef POWER_CONSUMPTION
if (!forReplay) {
SERIAL_ECHOLNPGM("Power consumation:");
SERIAL_ECHO_START;
ECHO_LM(DB, "Watt/h consumed:");
}
SERIAL_ECHOPAIR(" W/h:", power_consumption_hour);
SERIAL_EOL;
ECHO_LVM(DB, power_consumption_hour," W/h");
#endif
if (!forReplay) {
ECHO_LM(DB, "Power on time:");
}
char time[30];
int hours = printer_usage_seconds / 60 / 60, minutes = (printer_usage_seconds / 60) % 60;
sprintf_P(time, PSTR("%i " MSG_END_HOUR " %i " MSG_END_MINUTE), hours, minutes);
ECHO_LV(DB, time);
}
#endif //!DISABLE_M503
/**
* Configuration on SD card
*
* Author: Simone Primarosa
*
*/
#if defined(SDSUPPORT) && defined(SD_SETTINGS)
void ConfigSD_StoreSettings() {
if(!IS_SD_INSERTED || card.isFileOpen() || card.sdprinting) return;
card.openFile(CFG_SD_FILE, false, true, false);
char buff[CFG_SD_MAX_VALUE_LEN];
#ifdef POWER_CONSUMPTION
ltoa(power_consumption_hour,buff,10);
card.unparseKeyLine(cfgSD_KEY[SD_CFG_PWR], buff);
#endif
ltoa(printer_usage_seconds,buff,10);
card.unparseKeyLine(cfgSD_KEY[SD_CFG_TME], buff);
card.closeFile(false);
config_last_update = millis();
}
void ConfigSD_RetrieveSettings(bool addValue) {
if(!IS_SD_INSERTED || card.isFileOpen() || card.sdprinting || !card.cardOK) return;
char key[CFG_SD_MAX_KEY_LEN], value[CFG_SD_MAX_VALUE_LEN];
int k_idx;
int k_len, v_len;
card.openFile(CFG_SD_FILE, true, true, false);
while(true) {
k_len = CFG_SD_MAX_KEY_LEN;
v_len = CFG_SD_MAX_VALUE_LEN;
card.parseKeyLine(key, value, k_len, v_len);
if(k_len == 0 || v_len == 0) break; //no valid key or value founded
k_idx = ConfigSD_KeyIndex(key);
if(k_idx == -1) continue; //unknow key ignore it
switch(k_idx) {
#ifdef POWER_CONSUMPTION
case SD_CFG_PWR: {
if(addValue) power_consumption_hour += (unsigned long)atol(value);
else power_consumption_hour = (unsigned long)atol(value);
}
break;
#endif
case SD_CFG_TME: {
if(addValue) printer_usage_seconds += (unsigned long)atol(value);
else printer_usage_seconds = (unsigned long)atol(value);
}
break;
}
}
card.closeFile(false);
config_readed = true;
}
int ConfigSD_KeyIndex(char *key) { //At the moment a binary search algorithm is used for simplicity, if it will be necessary (Eg. tons of key), an hash search algorithm will be implemented.
int begin = 0, end = SD_CFG_END - 1, middle, cond;
while(begin <= end) {
middle = (begin + end) / 2;
cond = strcmp(cfgSD_KEY[middle], key);
if(!cond) return middle;
else if(cond < 0) begin = middle + 1;
else end = middle - 1;
}
return -1;
}
#endif
......@@ -4,11 +4,14 @@
#include "Configuration.h"
void Config_ResetDefault();
void ConfigSD_ResetDefault();
#ifndef DISABLE_M503
void Config_PrintSettings(bool forReplay=false);
void ConfigSD_PrintSettings(bool forReplay=false);
#else
FORCE_INLINE void Config_PrintSettings(bool forReplay=false) {}
FORCE_INLINE void ConfigSD_PrintSettings(bool forReplay=false) {}
#endif
#ifdef EEPROM_SETTINGS
......@@ -19,4 +22,27 @@ void Config_ResetDefault();
FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); }
#endif
#if defined(SDSUPPORT) && defined(SD_SETTINGS)
static const char *cfgSD_KEY[] = { //Keep this in lexicographical order for better search performance(O(Nlog2(N)) insted of O(N*N)) (if you don't keep this sorted, the algorithm for find the key index won't work, keep attention.)
#ifdef POWER_CONSUMPTION
"PWR",
#endif
"TME",
};
enum cfgSD_ENUM { //This need to be in the same order as cfgSD_KEY
#ifdef POWER_CONSUMPTION
SD_CFG_PWR,
#endif
SD_CFG_TME,
SD_CFG_END //Leave this always as the last
};
void ConfigSD_StoreSettings();
void ConfigSD_RetrieveSettings(bool addValue = false);
int ConfigSD_KeyIndex(char *key);
#else
FORCE_INLINE void ConfigSD_RetrieveSettings() { ConfigSD_ResetDefault(); ConfigSD_PrintSettings(); }
#endif
#endif //CONFIGURATIONSTORE_H
......@@ -36,13 +36,14 @@
// Z-Probe variables
// Start and end location values are used to deploy/retract the probe (will move from start to end and back again)
#define PROBING_FEEDRATE 500 // Speed for individual probe Use: G30 A F600
#define Z_PROBE_OFFSET {0,0,-1,0} // X, Y, Z, E distance between hotend nozzle and deployed bed leveling probe.
#define Z_PROBE_DEPLOY_START_LOCATION {0,0,30,0} // X, Y, Z, E start location for z-probe deployment sequence
#define Z_PROBE_DEPLOY_END_LOCATION {0,0,30,0} // X, Y, Z, E end location for z-probe deployment sequence
#define Z_PROBE_RETRACT_START_LOCATION {0,0,30,0}// X, Y, Z, E start location for z-probe retract sequence
#define Z_PROBE_RETRACT_END_LOCATION {0,0,30,0} // X, Y, Z, E end location for z-probe retract sequence
#define AUTOLEVEL_GRID 20 // Distance between autolevel Z probing points, should be less than print surface radius/3.
#define PROBING_FEEDRATE 500 // Speed for individual probe Use: G30 A F600
#define Z_PROBE_OFFSET {0, 0, -1, 0} // X, Y, Z, E distance between hotend nozzle and deployed bed leveling probe.
#define Z_PROBE_DEPLOY_START_LOCATION {0, 0, 30, 0} // X, Y, Z, E start location for z-probe deployment sequence
#define Z_PROBE_DEPLOY_END_LOCATION {0, 0, 30, 0} // X, Y, Z, E end location for z-probe deployment sequence
#define Z_PROBE_RETRACT_START_LOCATION {0, 0, 30, 0} // X, Y, Z, E start location for z-probe retract sequence
#define Z_PROBE_RETRACT_END_LOCATION {0, 0, 30, 0} // X, Y, Z, E end location for z-probe retract sequence
#define Z_RAISE_BETWEEN_PROBINGS 1 // How much the extruder will be raised when travelling from between next probing points
#define AUTOLEVEL_GRID 24 // Distance between autolevel Z probing points, should be less than print surface radius/3.
//===========================================================================
//=============================Mechanical Settings===========================
......
......@@ -46,9 +46,11 @@
//The M105 command return, besides traditional information, the ADC value read from temperature sensors.
//#define SHOW_TEMP_ADC_VALUES
// extruder idle oozing prevention
//if the extruder motor is idle for more than SECONDS, and the temperature over MINTEMP, some filament is retracted. The filament retracted is re-added before the next extrusion
//or when the target temperature is less than EXTRUDE_MINTEMP and the actual temperature is greater than IDLE_OOZING_MINTEMP and less than IDLE_OOZING_FEEDRATE
//extruder idle oozing prevention
//if the extruder motor is idle for more than SECONDS, and the temperature over MINTEMP,
//some filament is retracted. The filament retracted is re-added before the next extrusion
//or when the target temperature is less than EXTRUDE_MINTEMP and the actual temperature
//is greater than IDLE_OOZING_MINTEMP and less than IDLE_OOZING_FEEDRATE
//#define IDLE_OOZING_PREVENT
#define IDLE_OOZING_MINTEMP EXTRUDE_MINTEMP + 5
#define IDLE_OOZING_MAXTEMP IDLE_OOZING_MINTEMP + 5
......
......@@ -45,78 +45,7 @@ typedef unsigned long millis_t;
#define analogInputToDigitalPin(p) ((p) + 0xA0)
#endif
#ifdef AT90USB
#include "HardwareSerial.h"
#endif
#ifndef __SAM3X8E__
#include "MarlinSerial.h"
#endif
#ifndef cbi
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
#endif
#ifndef sbi
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
#endif
#include "WString.h"
#ifdef AT90USB
#ifdef BTENABLED
#define MYSERIAL bt
#else
#define MYSERIAL Serial
#endif // BTENABLED
#else
#ifdef __SAM3X8E__
#define MYSERIAL Serial
#else
#define MYSERIAL MSerial
#endif
#endif
#define SERIAL_CHAR(x) MYSERIAL.write(x)
#define SERIAL_EOL SERIAL_CHAR('\n')
#define SERIAL_PROTOCOLCHAR(x) SERIAL_CHAR(x)
#define SERIAL_PROTOCOL(x) MYSERIAL.print(x)
#define SERIAL_PROTOCOL_F(x,y) MYSERIAL.print(x,y)
#define SERIAL_PROTOCOLPGM(x) serialprintPGM(PSTR(x))
#define SERIAL_PROTOCOLLN(x) do{ MYSERIAL.print(x),MYSERIAL.write('\n'); }while(0)
#define SERIAL_PROTOCOLLNPGM(x) do{ serialprintPGM(PSTR(x)),MYSERIAL.write('\n'); }while(0)
extern const char errormagic[] PROGMEM;
extern const char echomagic[] PROGMEM;
#define SERIAL_ERROR_START serialprintPGM(errormagic)
#define SERIAL_ERROR(x) SERIAL_PROTOCOL(x)
#define SERIAL_ERRORPGM(x) SERIAL_PROTOCOLPGM(x)
#define SERIAL_ERRORLN(x) SERIAL_PROTOCOLLN(x)
#define SERIAL_ERRORLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
#define SERIAL_ECHO_START serialprintPGM(echomagic)
#define SERIAL_ECHO(x) SERIAL_PROTOCOL(x)
#define SERIAL_ECHOPGM(x) SERIAL_PROTOCOLPGM(x)
#define SERIAL_ECHOLN(x) SERIAL_PROTOCOLLN(x)
#define SERIAL_ECHOLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
#define SERIAL_ECHOPAIR(name,value) do{ serial_echopair_P(PSTR(name),(value)); }while(0)
void serial_echopair_P(const char *s_P, float v);
void serial_echopair_P(const char *s_P, double v);
void serial_echopair_P(const char *s_P, unsigned long v);
// Things to write to serial from Program memory. Saves 400 to 2k of RAM.
FORCE_INLINE void serialprintPGM(const char *str) {
char ch;
while ((ch = pgm_read_byte(str))) {
MYSERIAL.write(ch);
str++;
}
}
#include "Comunication.h"
void get_command();
void process_commands();
......@@ -311,6 +240,8 @@ extern bool axis_known_position[3];
extern float lastpos[4];
extern float zprobe_zoffset;
extern unsigned long printer_usage_seconds; //this can old about 136 year before go overflow. If you belive that you can live more than this please contact me.
#ifdef PREVENT_DANGEROUS_EXTRUDE
extern float extrude_min_temp;
#endif
......@@ -362,6 +293,11 @@ extern int fanSpeed;
extern int laser_ttl_modulation;
#endif
#if defined(SDSUPPORT) && defined(SD_SETTINGS)
extern millis_t config_last_update;
extern bool config_readed;
#endif
extern millis_t print_job_start_ms;
extern millis_t print_job_stop_ms;
......
......@@ -247,8 +247,6 @@ uint8_t debugLevel = 0;
int fanSpeed = 0;
bool cancel_heatup = false;
const char errormagic[] PROGMEM = "Error:";
const char echomagic[] PROGMEM = "echo:";
const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
static float offset[3] = { 0 };
......@@ -269,6 +267,8 @@ static uint8_t target_extruder;
bool no_wait_for_cooling = true;
bool target_direction;
unsigned long printer_usage_seconds;
#ifndef DELTA
int xy_travel_speed = XY_TRAVEL_SPEED;
float zprobe_zoffset = 0;
......@@ -406,6 +406,10 @@ bool target_direction;
#ifdef SDSUPPORT
static bool fromsd[BUFSIZE];
#ifdef SD_SETTINGS
millis_t config_last_update = 0;
bool config_readed = false;
#endif
#endif
#ifdef FILAMENTCHANGEENABLE
......@@ -454,14 +458,9 @@ bool target_direction;
//===========================================================================
//================================ Functions ================================
//===========================================================================
void get_arc_coordinates();
bool setTargetedHotend(int code);
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); }
#ifdef PREVENT_DANGEROUS_EXTRUDE
float extrude_min_temp = EXTRUDE_MINTEMP;
#endif
......@@ -539,10 +538,7 @@ bool enqueuecommand(const char *cmd) {
// This is dangerous if a mixing of serial and this happens
char *command = command_queue[cmd_queue_index_w];
strcpy(command, cmd);
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_Enqueueing);
SERIAL_ECHO(command);
SERIAL_ECHOLNPGM("\"");
ECHO_LMV(OK, MSG_ENQUEUEING,command);
cmd_queue_index_w = (cmd_queue_index_w + 1) % BUFSIZE;
commands_in_queue++;
return true;
......@@ -669,39 +665,31 @@ void setup() {
setup_killpin();
setup_filrunoutpin();
setup_powerhold();
MYSERIAL.begin(BAUDRATE);
SERIAL_PROTOCOLLNPGM("start");
SERIAL_ECHO_START;
SERIAL_INIT(BAUDRATE);
ECHO_S(START);
ECHO_E;
// 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);
if (mcu & 1) ECHO_LM(OK,MSG_POWERUP);
if (mcu & 2) ECHO_LM(OK,MSG_EXTERNAL_RESET);
if (mcu & 4) ECHO_LM(OK,MSG_BROWNOUT_RESET);
if (mcu & 8) ECHO_LM(OK,MSG_WATCHDOG_RESET);
if (mcu & 32) ECHO_LM(OK,MSG_SOFTWARE_RESET);
MCUSR = 0;
SERIAL_ECHOPGM(MSG_MARLIN);
SERIAL_ECHOLNPGM(" " STRING_VERSION);
ECHO_LM(OK, MSG_MARLIN " " STRING_VERSION);
#ifdef STRING_VERSION_CONFIG_H
#ifdef STRING_CONFIG_H_AUTHOR
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_CONFIGURATION_VER);
SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
SERIAL_ECHOPGM(MSG_AUTHOR);
SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
SERIAL_ECHOPGM("Compiled: ");
SERIAL_ECHOLNPGM(__DATE__);
ECHO_LM(OK, MSG_CONFIGURATION_VER STRING_VERSION_CONFIG_H MSG_AUTHOR STRING_CONFIG_H_AUTHOR MSG_COMPILED __DATE__);
#endif // STRING_CONFIG_H_AUTHOR
#endif // STRING_VERSION_CONFIG_H
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);
ECHO_SMV(OK, MSG_FREE_MEMORY, freeMemory());
ECHO_M(MSG_PLANNER_BUFFER_BYTES);
ECHO_EV((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
#ifdef SDSUPPORT
for (int8_t i = 0; i < BUFSIZE; i++) fromsd[i] = false;
......@@ -709,6 +697,13 @@ void setup() {
// loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
Config_RetrieveSettings();
// loads custom configuration from SDCARD if available else uses defaults
#if defined(SDSUPPORT) && defined(SD_SETTINGS)
ConfigSD_ResetDefault(); //this reset variable to default value as we can't load in the setup for different reason. Will load the value in the loop()
#else
ConfigSD_RetrieveSettings();
#endif
tp_init(); // Initialize temperature loop
plan_init(); // Initialize planner;
......@@ -717,7 +712,7 @@ void setup() {
setup_photpin();
setup_laserbeampin(); // Initialize Laserbeam pin
servo_init();
lcd_init();
_delay_ms(1000); // wait 1sec to display the splash screen
......@@ -774,8 +769,8 @@ void loop() {
char *command = command_queue[cmd_queue_index_r];
if (strstr_P(command, PSTR("M29"))) {
// M29 closes the file
card.closefile();
SERIAL_PROTOCOLLNPGM(MSG_FILE_SAVED);
card.closeFile();
ECHO_EM(MSG_FILE_SAVED);
}
else {
// Write the string from the read buffer to SD
......@@ -783,7 +778,7 @@ void loop() {
if (card.logging)
process_commands(); // The card is saving because it's logging
else
SERIAL_PROTOCOLLNPGM(MSG_OK);
ECHO_EM(MSG_OK);
}
}
else
......@@ -838,10 +833,7 @@ void get_command() {
strchr_pointer = strchr(command, 'N');
gcode_N = (strtol(strchr_pointer + 1, NULL, 10));
if (gcode_N != gcode_LastN + 1 && strstr_P(command, PSTR("M110")) == NULL) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_LINE_NO);
SERIAL_ERRORLN(gcode_LastN);
//Serial.println(gcode_N);
ECHO_LMV(ER, MSG_ERR_LINE_NO, gcode_LastN);
FlushSerialRequestResend();
serial_count = 0;
return;
......@@ -854,9 +846,7 @@ void get_command() {
strchr_pointer = strchr(command, '*');
if (strtol(strchr_pointer + 1, NULL, 10) != checksum) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_CHECKSUM_MISMATCH);
SERIAL_ERRORLN(gcode_LastN);
ECHO_LMV(ER, MSG_ERR_CHECKSUM_MISMATCH, gcode_LastN);
FlushSerialRequestResend();
serial_count = 0;
return;
......@@ -864,9 +854,7 @@ void get_command() {
//if no errors, continue parsing
}
else {
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_NO_CHECKSUM);
SERIAL_ERRORLN(gcode_LastN);
ECHO_LMV(ER, MSG_ERR_NO_CHECKSUM, gcode_LastN);
FlushSerialRequestResend();
serial_count = 0;
return;
......@@ -877,9 +865,7 @@ void get_command() {
}
else { // if we don't receive 'N' but still see '*'
if ((strchr(command, '*') != NULL)) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM);
SERIAL_ERRORLN(gcode_LastN);
ECHO_LMV(ER, MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM, gcode_LastN);
serial_count = 0;
return;
}
......@@ -893,7 +879,7 @@ void get_command() {
case 2:
case 3:
if (IsStopped()) {
SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
ECHO_LM(ER,MSG_ERR_STOPPED);
LCD_MESSAGEPGM(MSG_STOPPED);
}
break;
......@@ -943,14 +929,13 @@ void get_command() {
serial_count >= (MAX_CMD_SIZE - 1) || n == -1
) {
if (card.eof()) {
SERIAL_PROTOCOLLNPGM(MSG_FILE_PRINTED);
ECHO_LM(DB, MSG_FILE_PRINTED);
print_job_stop_ms = millis();
char time[30];
millis_t t = (print_job_stop_ms - print_job_start_ms) / 1000;
int hours = t / 60 / 60, minutes = (t / 60) % 60;
sprintf_P(time, PSTR("%i " MSG_END_HOUR " %i " MSG_END_MINUTE), hours, minutes);
SERIAL_ECHO_START;
SERIAL_ECHOLN(time);
ECHO_LV(DB,time);
lcd_setstatus(time, true);
card.printingHasFinished();
card.checkautostart(true);
......@@ -1071,7 +1056,7 @@ inline void set_homing_bump_feedrate(AxisEnum axis) {
feedrate = homing_feedrate[axis] / homing_bump_divisor[X_AXIS];
else {
feedrate = homing_feedrate[axis] / 10;
SERIAL_ECHOLN("Warning: The Homing Bump Feedrate Divisor cannot be less than 1");
ECHO_LM(ER, MSG_ERR_HOMING_DIV);
}
#else // No DELTA
const int homing_bump_divisor[] = HOMING_BUMP_DIVISOR;
......@@ -1079,7 +1064,7 @@ inline void set_homing_bump_feedrate(AxisEnum axis) {
feedrate = homing_feedrate[axis] / homing_bump_divisor[axis];
else {
feedrate = homing_feedrate[axis] / 10;
SERIAL_ECHOLN("Warning: The Homing Bump Feedrate Divisor cannot be less than 1");
ECHO_LM(ER, MSG_ERR_HOMING_DIV);
}
#endif // No DELTA
}
......@@ -1134,27 +1119,27 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
if (axis < 2) {
for (int i = 0; i < 3; i++) homeposition[i] = base_home_pos(i);
// SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
// SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]);
// ECHO_SMV(DB, "homeposition[x]= ", homeposition[0]);
// ECHO_EMV("homeposition[y]= ", homeposition[1]);
// Works out real Homeposition angles using inverse kinematics,
// and calculates homing offset using forward kinematics
calculate_delta(homeposition);
// SERIAL_ECHOPGM("base Theta= "); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" base Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
// ECHO_SMV(DB,"base Theta= ", delta[X_AXIS]);
// ECHO_EMV(" base Psi+Theta=", delta[Y_AXIS]);
for (int i = 0; i < 2; i++) delta[i] -= home_offset[i];
// SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(home_offset[X_AXIS]);
// SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(home_offset[Y_AXIS]);
// SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
// ECHO_SMV(DB,"addhome X=", home_offset[X_AXIS]);
// ECHO_MV(" addhome Y=", home_offset[Y_AXIS]);
// ECHO_MV(" addhome Theta=", delta[X_AXIS]);
// ECHO_EMV(" addhome Psi+Theta=", delta[Y_AXIS]);
calculate_SCARA_forward_Transform(delta);
// SERIAL_ECHOPGM("Delta X="); SERIAL_ECHO(delta[X_AXIS]);
// SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]);
// ECHO_SMV(DB,"Delta X=", delta[X_AXIS]);
// ECHO_EMV(" Delta Y=", delta[Y_AXIS]);
current_position[axis] = delta[axis];
// SCARA home positions are based on configuration since the actual limits are determined by the
......@@ -1375,14 +1360,10 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
#endif
if (verbose_level > 2) {
SERIAL_PROTOCOLPGM("Bed");
SERIAL_PROTOCOLPGM(" 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;
ECHO_SM(DB, MSG_BED_LEVELLING_BED);
ECHO_MV(MSG_BED_LEVELLING_X, x, 3);
ECHO_MV(MSG_BED_LEVELLING_Y, y, 3);
ECHO_EMV(MSG_BED_LEVELLING_Z, measured_z, 3);
}
return measured_z;
}
......@@ -1658,7 +1639,7 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
saved_position[Z_AXIS] = float((st_get_position(Z_AXIS)) / axis_steps_per_unit[Z_AXIS]);
feedrate = homing_feedrate[Z_AXIS];
destination[Z_AXIS] = mm + 2;
destination[Z_AXIS] = mm + Z_RAISE_BETWEEN_PROBINGS;
prepare_move_raw();
return mm;
}
......@@ -1712,12 +1693,12 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
bed_level[6][3-y] = bed_level[5][3-y];
}
// Print calibration results for manual frame adjustment.
ECHO_S(DB);
for (int x = -3; x <= 3; x++)
{
SERIAL_PROTOCOL_F(bed_level[x+3][3-y], 3);
SERIAL_PROTOCOLPGM(" ");
ECHO_VM(bed_level[x+3][3-y], " ", 3);
}
SERIAL_EOL;
ECHO_E;
}
}
......@@ -1812,44 +1793,29 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
void calibration_report() {
//Display Report
SERIAL_ECHOLN("\tZ-Tower\t\t\tEndstop Offsets");
SERIAL_ECHO("\t");
SERIAL_PROTOCOL_F(bed_level_z, 4);
SERIAL_ECHOPAIR("\t\t\tX:", endstop_adj[0]);
SERIAL_ECHOPAIR(" Y:", endstop_adj[1]);
SERIAL_ECHOPAIR(" Z:", endstop_adj[2]);
SERIAL_EOL;
SERIAL_PROTOCOL_F(bed_level_oy, 4);
SERIAL_PROTOCOLPGM("\t\t");
SERIAL_PROTOCOL_F(bed_level_ox, 4);
SERIAL_ECHOLN("\t\tTower Position Adjust");
SERIAL_PROTOCOLPGM("\t");
SERIAL_PROTOCOL_F(bed_level_c, 4);
SERIAL_ECHOPAIR("\t\t\tA:",tower_adj[0]);
SERIAL_ECHOPAIR(" B:",tower_adj[1]);
SERIAL_ECHOPAIR(" C:",tower_adj[2]);
SERIAL_EOL;
SERIAL_PROTOCOL_F(bed_level_x, 4);
SERIAL_PROTOCOLPGM("\t\t");
SERIAL_PROTOCOL_F(bed_level_y, 4);
SERIAL_ECHOPAIR("\t\tI:",tower_adj[3]);
SERIAL_ECHOPAIR(" J:",tower_adj[4]);
SERIAL_ECHOPAIR(" K:",tower_adj[5]);
SERIAL_EOL;
SERIAL_PROTOCOLPGM("\t");
SERIAL_PROTOCOL_F(bed_level_oz, 4);
SERIAL_PROTOCOLPGM("\t\t\tDelta Radius: ");
SERIAL_PROTOCOL_F(delta_radius, 4);
SERIAL_EOL;
SERIAL_PROTOCOLPGM("X-Tower\t\tY-Tower\t\tDiag Rod: ");
SERIAL_PROTOCOL_F(delta_diagonal_rod, 4);
SERIAL_EOL;
ECHO_SMV(DB, "\tZ-Tower\t\t\tEndstop Offsets\t", bed_level_z, 4);
ECHO_MV("\t\t\tX:", endstop_adj[0]);
ECHO_MV(" Y:", endstop_adj[1]);
ECHO_EMV(" Z:", endstop_adj[2]);
ECHO_SVM(DB, bed_level_oy, "\t\t", 4);
ECHO_EVM(bed_level_ox, "\t\tTower Position Adjust", 4);
ECHO_SMV(DB, "\t", bed_level_c, 4);
ECHO_MV("\t\t\tA:",tower_adj[0]);
ECHO_MV(" B:",tower_adj[1]);
ECHO_EMV(" C:",tower_adj[2]);
ECHO_SV(DB, bed_level_x, 4);
ECHO_MV("\t\t", bed_level_y, 4);
ECHO_MV("\t\tI:",tower_adj[3]);
ECHO_MV(" J:",tower_adj[4]);
ECHO_EMV(" K:",tower_adj[5]);
ECHO_SMV(DB, "\t", bed_level_oz, 4);
ECHO_EMV("\t\t\tDelta Radius: ", delta_radius, 4);
ECHO_LMV(DB, "X-Tower\t\tY-Tower\t\tDiag Rod: ", delta_diagonal_rod, 4);
}
void save_carriage_positions(int position_num) {
......@@ -1944,19 +1910,19 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
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);
ECHO_MSV(DB,"grid_x=", grid_x);
ECHO_MV(" grid_y=", grid_y);
ECHO_MV(" floor_x=", floor_x);
ECHO_MV(" floor_y=", floor_y);
ECHO_MV(" ratio_x=", ratio_x);
ECHO_MV(" ratio_y=", ratio_y);
ECHO_MV(" z1=", z1);
ECHO_MV(" z2=", z2);
ECHO_MV(" z3=", z3);
ECHO_MV(" z4=", z4);
ECHO_MV(" left=", left);
ECHO_MV(" right=", right);
ECHO_EMV(" offset=", offset);
*/
}
......@@ -1975,24 +1941,20 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
float h_endstop = -100, l_endstop = 100;
float probe_error, ftemp;
SERIAL_ECHOLN("Starting Auto Calibration..");
ECHO_SMV(DB,"Starting Auto Calibration... Calibration precision: +/- ", ac_prec, 3);
ECHO_EMV("mm Total Iteration: ", iterations);
LCD_MESSAGEPGM("Auto Calibration...");
SERIAL_ECHO("Calibration precision: +/- ");
SERIAL_PROTOCOL_F(ac_prec, 3);
SERIAL_ECHOLN("mm");
SERIAL_ECHO("Total Iteration: ");
SERIAL_ECHO(iterations);
SERIAL_EOL;
if (code_seen('D')) {
delta_diagonal_rod = code_value();
adj_dr_allowed = false;
SERIAL_ECHOPAIR("Using diagional rod length: ", delta_diagonal_rod);
SERIAL_ECHOLN("mm (will not be adjusted)");
ECHO_SMV(DB, "Using diagional rod length: ", delta_diagonal_rod);
ECHO_EM("mm (will not be adjusted)");
}
// First Check for control endstop
SERIAL_ECHOLN("First check for adjust Z-Height");
ECHO_LM(DB, "First check for adjust Z-Height");
home_delta_axis();
deploy_z_probe();
//Probe all points
......@@ -2009,15 +1971,12 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
if (bed_level_z + endstop_adj[2] < l_endstop) l_endstop = bed_level_z + endstop_adj[2];
if (h_endstop - l_endstop > 3) {
SERIAL_ECHOLN("The position of the endstop switches on this printer are not within limits");
SERIAL_ECHOLN("Adjust endstop switches so that they are within 3mm Z-height of each other");
SERIAL_EOL;
SERIAL_ECHOPAIR("Current Endstop Positions - X: ", bed_level_x + endstop_adj[0]);
SERIAL_ECHOPAIR(" Y: ", bed_level_y + endstop_adj[1]);
SERIAL_ECHOPAIR(" Z: ", bed_level_z + endstop_adj[2]);
SERIAL_EOL;
SERIAL_EOL;
SERIAL_ECHOLN("Auto calibration aborted");
ECHO_LM(DB, "The position of the endstop switches on this printer are not within limits");
ECHO_LM(DB, "Adjust endstop switches so that they are within 3mm Z-height of each other");
ECHO_SMV(DB, "Current Endstop Positions - X: ", bed_level_x + endstop_adj[0]);
ECHO_MV(" Y: ", bed_level_y + endstop_adj[1]);
ECHO_EMV(" Z: ", bed_level_z + endstop_adj[2]);
ECHO_LV(ER,"Auto calibration aborted");
retract_z_probe();
......@@ -2028,21 +1987,19 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
}
do {
SERIAL_ECHO("Iteration: ");
SERIAL_ECHO(loopcount);
SERIAL_EOL;
ECHO_LMV(DB, "Iteration: ", loopcount);
if ((bed_level_c > 3) or (bed_level_c < -3)) {
//Build height is not set correctly ..
max_pos[Z_AXIS] -= bed_level_c + 2;
set_delta_constants();
SERIAL_ECHOPAIR("Adjusting Z-Height to: ", max_pos[Z_AXIS]);
SERIAL_ECHOLN(" mm..");
ECHO_SMV(DB, "Adjusting Z-Height to: ", max_pos[Z_AXIS]);
ECHO_EM(" mm..");
}
else {
if ((bed_level_x < -ac_prec) or (bed_level_x > ac_prec) or (bed_level_y < -ac_prec) or (bed_level_y > ac_prec) or (bed_level_z < -ac_prec) or (bed_level_z > ac_prec)) {
//Endstop req adjustment
SERIAL_ECHOLN("Adjusting Endstop..");
ECHO_LM(DB,"Adjusting Endstop..");
endstop_adj[0] += bed_level_x / 1.05;
endstop_adj[1] += bed_level_y / 1.05;
endstop_adj[2] += bed_level_z / 1.05;
......@@ -2059,12 +2016,12 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
}
max_pos[Z_AXIS] -= h_endstop + 2;
set_delta_constants();
SERIAL_ECHOPAIR("Adjusting Z-Height to: ", max_pos[Z_AXIS]);
SERIAL_ECHOLN(" mm..");
ECHO_SMV(DB,"Adjusting Z-Height to: ", max_pos[Z_AXIS]);
ECHO_EM(" mm..");
}
}
else {
SERIAL_ECHOLN("Endstop: OK");
ECHO_LM(DB,"Endstop: OK");
adj_r_target = (bed_level_x + bed_level_y + bed_level_z) / 3;
adj_dr_target = (bed_level_ox + bed_level_oy + bed_level_oz) / 3;
......@@ -2077,7 +2034,7 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
else adj_tower_done = true;
if ((adj_r_done == false) or (adj_dr_done == false) or (adj_tower_done == false)) {
//delta geometry adjustment required
SERIAL_ECHOLN("Adjusting Delta Geometry..");
ECHO_LM(DB,"Adjusting Delta Geometry..");
//set initial direction and magnitude for delta radius & diagonal rod adjustment
if (adj_r == 0) {
if (adj_r_target > bed_level_c) adj_r = 1;
......@@ -2096,17 +2053,17 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
do {
//Apply adjustments
if (adj_r_done == false) {
SERIAL_ECHOPAIR("Adjusting Delta Radius (", delta_radius);
SERIAL_ECHOPAIR(" -> ", delta_radius + adj_r);
SERIAL_ECHOLN(")");
ECHO_SMV(DB,"Adjusting Delta Radius (", delta_radius);
ECHO_MV(" -> ", delta_radius + adj_r);
ECHO_EM(")");
delta_radius += adj_r;
}
if (adj_dr_allowed == false) adj_dr_done = true;
if (adj_dr_done == false) {
SERIAL_ECHOPAIR("Adjusting Diagonal Rod Length (", delta_diagonal_rod);
SERIAL_ECHOPAIR(" -> ", delta_diagonal_rod + adj_dr);
SERIAL_ECHOLN(")");
ECHO_SMV(DB,"Adjusting Diagonal Rod Length (", delta_diagonal_rod);
ECHO_MV(" -> ", delta_diagonal_rod + adj_dr);
ECHO_EM(")");
delta_diagonal_rod += adj_dr;
}
......@@ -2162,70 +2119,67 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
#ifdef DEBUG_MESSAGES
if (equalAB == true) {
SERIAL_ECHOPAIR("Tower AB Equal (A = ", radiusErrorA);
SERIAL_ECHOPAIR(" B=", radiusErrorB);
SERIAL_ECHOLN(")");
ECHO_SMV(DB, "Tower AB Equal (A = ", radiusErrorA);
ECHO_MV(" B=", radiusErrorB);
ECHO_EM(")");
}
else SERIAL_ECHOLN("equalAB = false");
else ECHO_LM(DB, "equalAB = false");
if (equalBC == true) {
SERIAL_ECHOPAIR("Tower BC Equal (B=", radiusErrorB);
SERIAL_ECHOPAIR(" C = ", radiusErrorC);
SERIAL_ECHOLN(")");
ECHO_SMV(DB, "Tower BC Equal (B=", radiusErrorB);
ECHO_MV(" C = ", radiusErrorC);
ECHO_EM(")");
}
else SERIAL_ECHOLN("equalBC = false");
else ECHO_LM(DB, "equalBC = false");
if (equalCA == true) {
SERIAL_ECHOPAIR("Tower CA Equal (C = ", radiusErrorC);
SERIAL_ECHOPAIR(" A = ", radiusErrorA);
SERIAL_ECHOLN(")");
ECHO_SMV(DB, "Tower CA Equal (C = ", radiusErrorC);
ECHO_MV(" A = ", radiusErrorA);
ECHO_EM(")");
}
else SERIAL_ECHOLN("equalCA = false");
else ECHO_LM(DB, "equalCA = false");
#endif //DEBUG_MESSAGES
if ((equalAB == true) and (equalBC == true) and (equalCA == true)) {
// all tower radius out by the same amount (within 0.02) - allow adjustment with delta rod length
#ifdef DEBUG_MESSAGES
SERIAL_ECHOLN("All tower radius errors equal");
ECHO_LM(DB, "All tower radius errors equal");
#endif
adj_RadiusA = adj_RadiusB = adj_RadiusC = 0;
}
if ((equalAB == true) and (equalBC == false) and (equalCA == false)) {
//Tower C radius error.. adjust it
SERIAL_ECHOLN("TowerC Radius error - adjusting");
ECHO_LM(DB, "TowerC Radius error - adjusting");
if (adj_RadiusC == 0) {
if (bed_level_z < bed_level_oz) adj_RadiusC = 0.5;
if (bed_level_z > bed_level_oz) adj_RadiusC = -0.5;
#ifdef DEBUG_MESSAGES
SERIAL_ECHOPAIR("adj_RadiusC set to ",adj_RadiusC);
SERIAL_EOL;
ECHO_LMV(DB, "adj_RadiusC set to ",adj_RadiusC);
#endif
}
}
if ((equalBC == true) and (equalAB == false) and (equalCA == false)) {
//Tower A radius error .. adjust it
SERIAL_ECHOLN("TowerA Radius error - adjusting");
ECHO_LM(DB, "TowerA Radius error - adjusting");
if (adj_RadiusA == 0) {
if (bed_level_x < bed_level_ox) adj_RadiusA = 0.5;
if (bed_level_x > bed_level_ox) adj_RadiusA = -0.5;
#ifdef DEBUG_MESSAGES
SERIAL_ECHOPAIR("adj_RadiusA set to ",adj_RadiusA);
SERIAL_EOL;
ECHO_LMV(DB, "adj_RadiusA set to ",adj_RadiusA);
#endif
}
}
if ((equalCA == true) and (equalAB == false) and (equalBC == false)) {
//Tower B radius error .. adjust it
SERIAL_ECHOLN("TowerB Radius error - adjusting");
ECHO_LM(DB, "TowerB Radius error - adjusting");
if (adj_RadiusB == 0) {
if (bed_level_y < bed_level_oy) adj_RadiusB = 0.5;
if (bed_level_y > bed_level_oy) adj_RadiusB = -0.5;
#ifdef DEBUG_MESSAGES
SERIAL_ECHOPAIR("adj_RadiusB set to ",adj_RadiusB);
SERIAL_EOL;
ECHO_LMV(DB, "adj_RadiusB set to ",adj_RadiusB);
#endif
}
}
......@@ -2254,46 +2208,38 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
else adj_dr_done = false;
#ifdef DEBUG_MESSAGES
SERIAL_ECHOPAIR("c: ", bed_level_c);
SERIAL_ECHOPAIR(" x: ", bed_level_x);
SERIAL_ECHOPAIR(" y: ", bed_level_y);
SERIAL_ECHOPAIR(" z: ", bed_level_z);
SERIAL_ECHOPAIR(" ox: ", bed_level_ox);
SERIAL_ECHOPAIR(" oy: ", bed_level_oy);
SERIAL_ECHOPAIR(" oz: ", bed_level_oz);
SERIAL_EOL;
SERIAL_ECHO("radius:");
SERIAL_PROTOCOL_F(delta_radius, 4);
SERIAL_ECHO(" diagrod:");
SERIAL_PROTOCOL_F(delta_diagonal_rod, 4);
SERIAL_EOL;
SERIAL_ECHO("Radius Adj Complete: ");
if (adj_r_done == true) SERIAL_ECHO("Yes");
else SERIAL_ECHO("No");
SERIAL_ECHO(" DiagRod Adj Complete: ");
if (adj_dr_done == true) SERIAL_ECHO("Yes");
else SERIAL_ECHO("No");
SERIAL_EOL;
SERIAL_ECHOPAIR("RadiusA Error: ",radiusErrorA);
SERIAL_ECHOPAIR(" (adjust: ",adj_RadiusA);
SERIAL_ECHOLN(")");
SERIAL_ECHOPAIR("RadiusB Error: ",radiusErrorB);
SERIAL_ECHOPAIR(" (adjust: ",adj_RadiusB);
SERIAL_ECHOLN(")");
SERIAL_ECHOPAIR("RadiusC Error: ",radiusErrorC);
SERIAL_ECHOPAIR(" (adjust: ",adj_RadiusC);
SERIAL_ECHOLN(")");
SERIAL_ECHOPAIR("DeltaAlphaA: ",adj_AlphaA);
SERIAL_EOL;
SERIAL_ECHOPAIR("DeltaAlphaB: ",adj_AlphaB);
SERIAL_EOL;
SERIAL_ECHOPAIR("DeltaAlphaC: ",adj_AlphaC);
SERIAL_EOL;
ECHO_SMV(DB, "c: ", bed_level_c);
ECHO_MV(" x: ", bed_level_x);
ECHO_MV(" y: ", bed_level_y);
ECHO_MV(" z: ", bed_level_z);
ECHO_MV(" ox: ", bed_level_ox);
ECHO_MV(" oy: ", bed_level_oy);
ECHO_EMV(" oz: ", bed_level_oz);
ECHO_EMV("radius:", delta_radius, 4);
ECHO_EMV(" diagrod:", delta_diagonal_rod, 4);
ECHO_SM(DB, "Radius Adj Complete: ");
if (adj_r_done == true) ECHO_M("Yes");
else ECHO_M("No");
ECHO_M(" DiagRod Adj Complete: ");
if (adj_dr_done == true) ECHO_EM("Yes");
else ECHO_EM("No");
ECHO_SMV(DB, "RadiusA Error: ",radiusErrorA);
ECHO_MV(" (adjust: ",adj_RadiusA);
ECHO_EM(")");
ECHO_SMV(DB, "RadiusB Error: ",radiusErrorB);
ECHO_MV(" (adjust: ",adj_RadiusB);
ECHO_EM(")");
ECHO_SMV(DB, "RadiusC Error: ",radiusErrorC);
ECHO_MV(" (adjust: ",adj_RadiusC);
ECHO_EM(")");
ECHO_LMV(DB, "DeltaAlphaA: ",adj_AlphaA);
ECHO_LMV(DB, "DeltaAlphaB: ",adj_AlphaB);
ECHO_LMV(DB, "DeltaAlphaC: ",adj_AlphaC);
#endif
} while (((adj_r_done == false) or (adj_dr_done = false)) and (loopcount < iterations));
}
else {
SERIAL_ECHOLN("Delta Geometry: OK");
ECHO_LM(DB, "Delta Geometry: OK");
}
}
}
......@@ -2331,16 +2277,15 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
} while(loopcount < iterations);
SERIAL_ECHOLN("Auto Calibration Complete");
ECHO_LM(DB, "Auto Calibration Complete");
LCD_MESSAGEPGM("Complete");
SERIAL_ECHOLN("Issue M500 Command to save calibration settings to EPROM (if enabled)");
ECHO_LM(DB, "Issue M500 Command to save calibration settings to EPROM (if enabled)");
/*
if ((abs(delta_diagonal_rod - saved_delta_diagonal_rod) > 1) and (adj_dr_allowed == true)) {
SERIAL_EOL;
SERIAL_ECHOPAIR("WARNING: The length of diagonal rods specified (", saved_delta_diagonal_rod);
SERIAL_ECHOLN(" mm) appears to be incorrect");
SERIAL_ECHOLN("If you have measured your rods and you believe that this value is correct, this could indicate");
SERIAL_ECHOLN("excessive twisting movement of carriages and/or loose screws/joints on carriages or end effector");
ECHO_SMV(DB, "WARNING: The length of diagonal rods specified (", saved_delta_diagonal_rod);
ECHO_EV(" mm) appears to be incorrect");
ECHO_LM(DB, "If you have measured your rods and you believe that this value is correct, this could indicate");
ECHO_LM(DB,"excessive twisting movement of carriages and/or loose screws/joints on carriages or end effector");
}
*/
......@@ -2356,7 +2301,6 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
#ifdef IDLE_OOZING_PREVENT
void IDLE_OOZING_retract(bool retracting) {
if (retracting && !IDLE_OOZING_retracted[active_extruder]) {
//SERIAL_ECHOLN("RETRACT FOR OOZING PREVENT");
set_destination_to_current();
current_position[E_AXIS]+=IDLE_OOZING_LENGTH/volumetric_multiplier[active_extruder];
plan_set_e_position(current_position[E_AXIS]);
......@@ -2367,7 +2311,6 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
feedrate = oldFeedrate;
}
else if(!retracting && IDLE_OOZING_retracted[active_extruder]) {
//SERIAL_ECHOLN("EXTRUDE FOR OOZING PREVENT");
set_destination_to_current();
current_position[E_AXIS]-=(IDLE_OOZING_LENGTH+IDLE_OOZING_RECOVER_LENGTH)/volumetric_multiplier[active_extruder];
plan_set_e_position(current_position[E_AXIS]);
......@@ -2446,8 +2389,7 @@ inline void set_destination_to_current() { memcpy(destination, current_position,
static void dock_sled(bool dock, int offset=0) {
if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) {
LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN);
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_POSITION_UNKNOWN);
ECHO_LM(DB, MSG_POSITION_UNKNOWN);
return;
}
......@@ -2470,7 +2412,7 @@ inline void lcd_beep(int number_beep = 3) {
lcd_buzz(1000/6,100);
}
#else
for(int8_t i=0;i<number_beep;i++) {
for(int8_t i = 0; i < number_beep; i++) {
lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS,LCD_FEEDBACK_FREQUENCY_HZ);
}
#endif
......@@ -2484,7 +2426,7 @@ inline void lcd_beep(int number_beep = 3) {
delay(100);
}
#else
for(int8_t i = 0; i < number_beep; i++) {
for(int8_t i=0;i<number_beep;i++) {
WRITE(BEEPER,HIGH);
delay(1000000 / LCD_FEEDBACK_FREQUENCY_HZ / 2);
WRITE(BEEPER,LOW);
......@@ -2516,21 +2458,19 @@ inline void wait_heater() {
{ // while loop
if (millis() > temp_ms + 1000UL) { //Print temp & remaining time every 1s while waiting
SERIAL_PROTOCOLPGM("T:");
SERIAL_PROTOCOL_F(degHotend(target_extruder),1);
SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOL((int)target_extruder);
ECHO_SMV(OK, "T:", degHotend(target_extruder),1);
ECHO_MV(" E:", target_extruder);
#ifdef TEMP_RESIDENCY_TIME
SERIAL_PROTOCOLPGM(" W:");
ECHO_M(" W:");
if (residency_start_ms > -1) {
temp_ms = ((TEMP_RESIDENCY_TIME * 1000UL) - (millis() - residency_start_ms)) / 1000UL;
SERIAL_PROTOCOLLN(temp_ms);
ECHO_EV(temp_ms);
}
else {
SERIAL_PROTOCOLLNPGM("?");
ECHO_EM("?");
}
#else
SERIAL_EOL;
ECHO_E;
#endif
temp_ms = millis();
}
......@@ -2565,13 +2505,9 @@ inline void wait_bed() {
if (ms > temp_ms + 1000UL) { //Print Temp Reading every 1 second while heating up.
temp_ms = ms;
float tt = degHotend(active_extruder);
SERIAL_PROTOCOLPGM("T:");
SERIAL_PROTOCOL(tt);
SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOL((int)active_extruder);
SERIAL_PROTOCOLPGM(" B:");
SERIAL_PROTOCOL_F(degBed(), 1);
SERIAL_PROTOCOLLN("");
ECHO_SMV(OK, "T:", tt);
ECHO_MV(" E:", active_extruder);
ECHO_EMV(" B:", degBed(), 1);
}
manage_heater();
manage_inactivity();
......@@ -2852,7 +2788,7 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
if (code_seen('M') && !(homeX || homeY)) {
// Manual G28 bed level
#ifdef ULTIPANEL
SERIAL_ECHOLN(" --LEVEL PLATE SCRIPT--");
ECHO_LM(DB, " --LEVEL PLATE SCRIPT--");
set_ChangeScreen(true);
while(!lcd_clicked()) {
set_pageShowInfo(0);
......@@ -2986,14 +2922,12 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
}
else {
LCD_MESSAGEPGM(MSG_ZPROBE_OUT);
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_ZPROBE_OUT);
ECHO_LM(DB, MSG_ZPROBE_OUT);
}
}
else {
LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN);
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_POSITION_UNKNOWN);
ECHO_LM(DB, MSG_POSITION_UNKNOWN);
}
}
#elif defined(Z_SAFE_HOMING)
......@@ -3078,14 +3012,13 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
// Don't allow auto-leveling without homing first
if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) {
LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN);
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_POSITION_UNKNOWN);
ECHO_LM(ER, MSG_POSITION_UNKNOWN);
return;
}
int verbose_level = code_seen('V') || code_seen('v') ? code_value_short() : 1;
if (verbose_level < 0 || verbose_level > 4) {
SERIAL_ECHOLNPGM("?(V)erbose Level is implausible (0-4).");
ECHO_LM(ER,"?(V)erbose Level is implausible (0-4).");
return;
}
......@@ -3097,13 +3030,13 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
bool do_topography_map = verbose_level > 2 || code_seen('T') || code_seen('t');
if (verbose_level > 0) {
SERIAL_PROTOCOLPGM("G29 Auto Bed Leveling\n");
if (dryrun) SERIAL_ECHOLNPGM("Running in DRY-RUN mode");
ECHO_LM(DB, "G29 Auto Bed Leveling");
if (dryrun) ECHO_LM(DB,"Running in DRY-RUN mode");
}
int auto_bed_leveling_grid_points = code_seen('P') ? code_value_long() : AUTO_BED_LEVELING_GRID_POINTS;
if (auto_bed_leveling_grid_points < 2) {
SERIAL_PROTOCOLPGM("?Number of probed (P)oints is implausible (2 minimum).\n");
ECHO_LM(ER, "?Number of probed (P)oints is implausible (2 minimum).\n");
return;
}
......@@ -3125,19 +3058,19 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
if (left_out || right_out || front_out || back_out) {
if (left_out) {
SERIAL_PROTOCOLPGM("?Probe (L)eft position out of range.\n");
ECHO_LM(ER, "?Probe (L)eft position out of range.\n");
left_probe_bed_position = left_out_l ? MIN_PROBE_X : right_probe_bed_position - MIN_PROBE_EDGE;
}
if (right_out) {
SERIAL_PROTOCOLPGM("?Probe (R)ight position out of range.\n");
ECHO_LM(ER, "?Probe (R)ight position out of range.\n");
right_probe_bed_position = right_out_r ? MAX_PROBE_X : left_probe_bed_position + MIN_PROBE_EDGE;
}
if (front_out) {
SERIAL_PROTOCOLPGM("?Probe (F)ront position out of range.\n");
ECHO_LM(ER, "?Probe (F)ront position out of range.\n");
front_probe_bed_position = front_out_f ? MIN_PROBE_Y : back_probe_bed_position - MIN_PROBE_EDGE;
}
if (back_out) {
SERIAL_PROTOCOLPGM("?Probe (B)ack position out of range.\n");
ECHO_LM(ER, "?Probe (B)ack position out of range.\n");
back_probe_bed_position = back_out_b ? MAX_PROBE_Y : front_probe_bed_position + MIN_PROBE_EDGE;
}
return;
......@@ -3252,42 +3185,34 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
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;
ECHO_SMV(DB, "Eqn coefficients: a: ", plane_equation_coefficients[0], 8);
ECHO_MV(" b: ", plane_equation_coefficients[1], 8);
ECHO_EMV(" d: ", plane_equation_coefficients[2], 8);
if (verbose_level > 2) {
SERIAL_PROTOCOLPGM("Mean of sampled points: ");
SERIAL_PROTOCOL_F(mean, 8);
SERIAL_EOL;
ECHO_LMV(DB, "Mean of sampled points: ", mean, 8);
}
}
if (do_topography_map) {
SERIAL_PROTOCOLPGM(" \nBed Height Topography: \n");
SERIAL_PROTOCOLPGM("+-----------+\n");
SERIAL_PROTOCOLPGM("|...Back....|\n");
SERIAL_PROTOCOLPGM("|Left..Right|\n");
SERIAL_PROTOCOLPGM("|...Front...|\n");
SERIAL_PROTOCOLPGM("+-----------+\n");
ECHO_LM(DB, "Bed Height Topography:");
ECHO_LM(DB, "+-----------+");
ECHO_LM(DB, "|...Back....|");
ECHO_LM(DB, "|Left..Right|");
ECHO_LM(DB, "|...Front...|");
ECHO_LM(DB, "+-----------+");
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 = yy * auto_bed_leveling_grid_points + xx;
float diff = eqnBVector[ind] - mean;
if (diff >= 0.0)
SERIAL_PROTOCOLPGM(" +"); // Include + for column alignment
else
SERIAL_PROTOCOLCHAR(' ');
SERIAL_PROTOCOL_F(diff, 5);
if (diff >= 0.0) ECHO_M(" +"); // Include + for column alignment
else ECHO_M(" ");
ECHO_V(diff, 5);
} // xx
SERIAL_EOL;
ECHO_E;
} // yy
SERIAL_EOL;
ECHO_E;
} //do_topography_map
......@@ -3344,14 +3269,10 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
feedrate = homing_feedrate[Z_AXIS];
run_z_probe();
SERIAL_PROTOCOLPGM("Bed");
SERIAL_PROTOCOLPGM(" X: ");
SERIAL_PROTOCOL(current_position[X_AXIS] + 0.0001);
SERIAL_PROTOCOLPGM(" Y: ");
SERIAL_PROTOCOL(current_position[Y_AXIS] + 0.0001);
SERIAL_PROTOCOLPGM(" Z: ");
SERIAL_PROTOCOL(current_position[Z_AXIS] + 0.0001);
SERIAL_EOL;
ECHO_SM(DB, "Bed");
ECHO_M(" X: ", current_position[X_AXIS] + 0.0001);
ECHO_M(" Y: ", current_position[Y_AXIS] + 0.0001);
ECHO_EMV(" Z: ", current_position[Z_AXIS] + 0.0001);
clean_up_after_endstop_move();
stow_z_probe(); // Retract Z Servo endstop if available
......@@ -3366,14 +3287,13 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
*/
inline void gcode_G29() {
if (code_seen('D')) {
SERIAL_ECHOLN("Current bed level array values:");
SERIAL_EOL;
ECHO_LM(DB, "Current bed level array values:");
for (int y = 0; y < 7; y++) {
ECHO_S(DB);
for (int x = 0; x < 7; x++) {
SERIAL_PROTOCOL_F(bed_level[x][y], 3);
SERIAL_PROTOCOLPGM(" ");
ECHO_VM(bed_level[x][y], " ", 3);
}
SERIAL_EOL;
ECHO_E;
}
return;
}
......@@ -3405,15 +3325,12 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
if (code_seen('C')) {
//Show carriage positions
SERIAL_ECHOLN("Carriage Positions for last scan:");
ECHO_LM(DB, "Carriage Positions for last scan: ");
for(int8_t i=0; i < 7; i++) {
SERIAL_ECHO("[");
SERIAL_ECHO(saved_positions[i][X_AXIS]);
SERIAL_ECHO(", ");
SERIAL_ECHO(saved_positions[i][Y_AXIS]);
SERIAL_ECHO(", ");
SERIAL_ECHO(saved_positions[i][Z_AXIS]);
SERIAL_ECHOLN("]");
ECHO_SMV(DB, "[", saved_positions[i][X_AXIS]);
ECHO_MV(", ", saved_positions[i][Y_AXIS]);
ECHO_MV(", ", saved_positions[i][Z_AXIS]);
ECHO_EM("]");
}
return;
}
......@@ -3430,21 +3347,14 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
deploy_z_probe();
probe_value = probe_bed(x, y);
SERIAL_ECHO("Bed Z-Height at X:");
SERIAL_ECHO(x);
SERIAL_ECHO(" Y:");
SERIAL_ECHO(y);
SERIAL_ECHO(" = ");
SERIAL_PROTOCOL_F(probe_value, 4);
SERIAL_EOL;
SERIAL_ECHO("Carriage Positions: [");
SERIAL_ECHO(saved_position[X_AXIS]);
SERIAL_ECHO(", ");
SERIAL_ECHO(saved_position[Y_AXIS]);
SERIAL_ECHO(", ");
SERIAL_ECHO(saved_position[Z_AXIS]);
SERIAL_ECHOLN("]");
ECHO_SMV(DB, "Bed Z-Height at X:", x);
ECHO_MV(" Y:", y);
ECHO_EMV(" = ", probe_value, 4);
ECHO_SMV(DB, "Carriage Positions: [", saved_position[X_AXIS]);
ECHO_MV(", ", saved_position[Y_AXIS]);
ECHO_MV(", ", saved_position[Z_AXIS]);
ECHO_EM("]");
retract_z_probe();
return;
}
......@@ -3479,11 +3389,10 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
// G60: Store in memory actual position
inline void gcode_G60() {
memcpy(lastpos, current_position, sizeof(lastpos));
//SERIAL_ECHOPAIR(" Lastpos X: ", lastpos[X_AXIS]);
//SERIAL_ECHOPAIR(" Lastpos Y: ", lastpos[Y_AXIS]);
//SERIAL_ECHOPAIR(" Lastpos Z: ", lastpos[Z_AXIS]);
//SERIAL_ECHOPAIR(" Lastpos E: ", lastpos[E_AXIS]);
//SERIAL_EOL;
//ECHO_SMV(DB, " Lastpos X: ", lastpos[X_AXIS]);
//ECHO_MV(" Lastpos Y: ", lastpos[Y_AXIS]);
//ECHO_MV(" Lastpos Z: ", lastpos[Z_AXIS]);
//ECHO_EMV(" Lastpos E: ", lastpos[E_AXIS]);
}
// G61: move to X Y Z in memory
......@@ -3496,11 +3405,10 @@ inline void gcode_G61() {
destination[i] = current_position[i];
}
}
//SERIAL_ECHOPAIR(" Move to X: ", destination[X_AXIS]);
//SERIAL_ECHOPAIR(" Move to Y: ", destination[Y_AXIS]);
//SERIAL_ECHOPAIR(" Move to Z: ", destination[Z_AXIS]);
//SERIAL_ECHOPAIR(" Move to E: ", destination[E_AXIS]);
//SERIAL_EOL;
//ECHO_SMV(DB, " Move to X: ", destination[X_AXIS]);
//ECHO_MV(" Move to Y: ", destination[Y_AXIS]);
//ECHO_MV(" Move to Z: ", destination[Z_AXIS]);
//ECHO_EMV(" Move to E: ", destination[E_AXIS]);
if(code_seen('F')) {
next_feedrate = code_value();
......@@ -3625,7 +3533,9 @@ inline void gcode_G92() {
inline void gcode_M11() {
printing = true;
paused = false;
SERIAL_ECHOLN("Start Printing, pause pin active.");
ECHO_LM(DB, "Start Printing, pause pin active.");
ECHO_S(RESUME);
ECHO_E;
#if HAS_POWER_CONSUMPTION_SENSOR
startpower = power_consumption_hour;
#endif
......@@ -3646,9 +3556,9 @@ inline void gcode_M17() {
* M20: List SD card to serial output
*/
inline void gcode_M20() {
SERIAL_PROTOCOLLNPGM(MSG_BEGIN_FILE_LIST);
ECHO_EM(MSG_BEGIN_FILE_LIST);
card.ls();
SERIAL_PROTOCOLLNPGM(MSG_END_FILE_LIST);
ECHO_EM(MSG_END_FILE_LIST);
}
/**
......@@ -3735,7 +3645,7 @@ inline void gcode_M17() {
*/
inline void gcode_M30() {
if (card.cardOK) {
card.closefile();
card.closeFile();
char* starpos = strchr(strchr_pointer + 4, '*');
if (starpos) {
char* npos = strchr(command_queue[cmd_queue_index_r], 'N');
......@@ -3756,8 +3666,7 @@ inline void gcode_M31() {
int min = t / 60, sec = t % 60;
char time[30];
sprintf_P(time, PSTR("%i min, %i sec"), min, sec);
SERIAL_ECHO_START;
SERIAL_ECHOLN(time);
ECHO_LV(OK, time);
lcd_setstatus(time);
autotempShutdown();
}
......@@ -3871,21 +3780,20 @@ inline void gcode_M42() {
if (code_seen('V') || code_seen('v')) {
verbose_level = code_value_short();
if (verbose_level < 0 || verbose_level > 4 ) {
SERIAL_PROTOCOLPGM("?Verbose Level not plausible (0-4).\n");
ECHO_LM(ER,"?Verbose Level not plausible (0-4).");
return;
}
}
if (verbose_level > 0)
SERIAL_PROTOCOLPGM("M49 Z-Probe Repeatability test\n");
if (code_seen('P') || code_seen('p')) {
n_samples = code_value_short();
if (n_samples < 4 || n_samples > 50) {
SERIAL_PROTOCOLPGM("?Sample size not plausible (4-50).\n");
ECHO_LM(ER, "?Sample size not plausible (4-50).");
return;
}
}
if (verbose_level > 0) ECHO_LM(DB, "M49 Z-Probe Repeatability test");
double X_probe_location, Y_probe_location,
X_current = X_probe_location = st_get_position_mm(X_AXIS),
......@@ -3899,7 +3807,7 @@ inline void gcode_M42() {
if (code_seen('X') || code_seen('x')) {
X_probe_location = code_value() - X_PROBE_OFFSET_FROM_EXTRUDER;
if (X_probe_location < X_MIN_POS || X_probe_location > X_MAX_POS) {
SERIAL_PROTOCOLPGM("?X position out of range.\n");
ECHO_LM(ER, "?X position out of range.");
return;
}
}
......@@ -3907,7 +3815,7 @@ inline void gcode_M42() {
if (code_seen('Y') || code_seen('y')) {
Y_probe_location = code_value() - Y_PROBE_OFFSET_FROM_EXTRUDER;
if (Y_probe_location < Y_MIN_POS || Y_probe_location > Y_MAX_POS) {
SERIAL_PROTOCOLPGM("?Y position out of range.\n");
ECHO_LM(ER, "?Y position out of range.");
return;
}
}
......@@ -3916,7 +3824,7 @@ inline void gcode_M42() {
n_legs = code_value_short();
if (n_legs == 1) n_legs = 2;
if (n_legs < 0 || n_legs > 15) {
SERIAL_PROTOCOLPGM("?Number of legs in movement not plausible (0-15).\n");
ECHO_LM(ER, "?Number of legs in movement not plausible (0-15).");
return;
}
}
......@@ -3936,7 +3844,7 @@ inline void gcode_M42() {
// use that as a starting point for each probe.
//
if (verbose_level > 2)
SERIAL_PROTOCOLPGM("Positioning the probe...\n");
ECHO_LM(DB, "Positioning the probe...");
plan_buffer_line(X_probe_location, Y_probe_location, Z_start_location, ext_position, homing_feedrate[X_AXIS]/60, active_extruder, active_driver);
st_synchronize();
......@@ -3975,10 +3883,9 @@ inline void gcode_M42() {
theta = RADIANS(ms % 360L);
float dir = (ms & 0x0001) ? 1 : -1; // clockwise or counter clockwise
//SERIAL_ECHOPAIR("starting radius: ",radius);
//SERIAL_ECHOPAIR(" theta: ",theta);
//SERIAL_ECHOPAIR(" direction: ",dir);
//SERIAL_EOL;
//ECHO_SMV(DB, "starting radius: ",radius);
//ECHO_MV(" theta: ",theta);
//ECHO_EMV(" direction: ",dir);
for (uint8_t l = 0; l < n_legs - 1; l++) {
ms = millis();
......@@ -3992,9 +3899,8 @@ inline void gcode_M42() {
Y_current = constrain(Y_current, Y_MIN_POS, Y_MAX_POS);
if (verbose_level > 3) {
SERIAL_ECHOPAIR("x: ", X_current);
SERIAL_ECHOPAIR("y: ", Y_current);
SERIAL_EOL;
ECHO_SMV(DB, "x: ", X_current);
ECHO_EMV("y: ", Y_current);
}
do_blocking_move_to(X_current, Y_current, Z_current); // this also updates current_position
......@@ -4035,21 +3941,16 @@ inline void gcode_M42() {
sigma = sqrt(sum / (n + 1));
if (verbose_level > 1) {
SERIAL_PROTOCOL(n+1);
SERIAL_PROTOCOLPGM(" of ");
SERIAL_PROTOCOL(n_samples);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL_F(current_position[Z_AXIS], 6);
ECHO_SV(n+1);
ECHO_MV(" of ", n_samples);
ECHO_MV(" z: ", 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);
ECHO_MV(" mean: ", mean,6);
ECHO_MV(" sigma: ", sigma,6);
}
ECHO_E;
}
if (verbose_level > 0) SERIAL_EOL;
plan_buffer_line(X_probe_location, Y_probe_location, Z_start_location, current_position[E_AXIS], homing_feedrate[Z_AXIS]/60, active_extruder, active_driver);
st_synchronize();
......@@ -4069,14 +3970,10 @@ inline void gcode_M42() {
// enable_endstops(true);
if (verbose_level > 0) {
SERIAL_PROTOCOLPGM("Mean: ");
SERIAL_PROTOCOL_F(mean, 6);
SERIAL_EOL;
ECHO_LMV("Mean: ",mean, 6);
}
SERIAL_PROTOCOLPGM("Standard Deviation: ");
SERIAL_PROTOCOL_F(sigma, 6);
SERIAL_EOL; SERIAL_EOL;
ECHO_LMV("Standard Deviation: ", sigma, 6);
}
#endif // ENABLE_AUTO_BED_LEVELING && Z_PROBE_REPEATABILITY_TEST
......@@ -4226,66 +4123,51 @@ inline void gcode_M105() {
if (setTargetedHotend(105)) return;
#if HAS_TEMP_0 || HAS_TEMP_BED
SERIAL_PROTOCOLPGM("ok");
ECHO_S(OK);
#if HAS_TEMP_0
SERIAL_PROTOCOLPGM(" T:");
SERIAL_PROTOCOL_F(degHotend(target_extruder), 1);
SERIAL_PROTOCOLPGM(" /");
SERIAL_PROTOCOL_F(degTargetHotend(target_extruder), 1);
ECHO_MV(" T:", degHotend(target_extruder), 1);
ECHO_MV(" /", degTargetHotend(target_extruder), 1);
#endif
#if HAS_TEMP_BED
SERIAL_PROTOCOLPGM(" B:");
SERIAL_PROTOCOL_F(degBed(), 1);
SERIAL_PROTOCOLPGM(" /");
SERIAL_PROTOCOL_F(degTargetBed(), 1);
ECHO_MV(" B:", degBed(), 1);
ECHO_MV(" /", degTargetBed(), 1);
#endif
for (int8_t e = 0; e < EXTRUDERS; ++e) {
SERIAL_PROTOCOLPGM(" T");
SERIAL_PROTOCOL(e);
SERIAL_PROTOCOLCHAR(':');
SERIAL_PROTOCOL_F(degHotend(e), 1);
SERIAL_PROTOCOLPGM(" /");
SERIAL_PROTOCOL_F(degTargetHotend(e), 1);
ECHO_MV(" T", e);
ECHO_MV(":", degHotend(e), 1);
ECHO_MV(" /", degTargetHotend(e), 1);
}
#else // !HAS_TEMP_0 && !HAS_TEMP_BED
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_NO_THERMISTORS);
ECHO_LM(ER, MSG_ERR_NO_THERMISTORS);
return;
#endif
SERIAL_PROTOCOLPGM(" @:");
ECHO_M(" @:");
#ifdef HOTEND_WATTS
SERIAL_PROTOCOL((HOTEND_WATTS * getHeaterPower(target_extruder))/127);
SERIAL_PROTOCOLCHAR('W');
ECHO_VM((HOTEND_WATTS * getHeaterPower(target_extruder))/127, "W");
#else
SERIAL_PROTOCOL(getHeaterPower(target_extruder));
ECHO_V(getHeaterPower(target_extruder));
#endif
SERIAL_PROTOCOLPGM(" B@:");
ECHO_M(" B@:");
#ifdef BED_WATTS
SERIAL_PROTOCOL((BED_WATTS * getHeaterPower(-1))/127);
SERIAL_PROTOCOLCHAR('W');
ECHO_VM((BED_WATTS * getHeaterPower(-1))/127, "W");
#else
SERIAL_PROTOCOL(getHeaterPower(-1));
ECHO_V(getHeaterPower(-1));
#endif
#ifdef SHOW_TEMP_ADC_VALUES
#if HAS_TEMP_BED
SERIAL_PROTOCOLPGM(" ADC B:");
SERIAL_PROTOCOL_F(degBed(),1);
SERIAL_PROTOCOLPGM("C->");
SERIAL_PROTOCOL_F(rawBedTemp()/OVERSAMPLENR,0);
ECHO_MV(" ADC B:", degBed(),1);
ECHO_MV("C->", rawBedTemp()/OVERSAMPLENR,0);
#endif
for (int8_t cur_extruder = 0; cur_extruder < HOTENDS; ++cur_extruder) {
SERIAL_PROTOCOLPGM(" T");
SERIAL_PROTOCOL(cur_extruder);
SERIAL_PROTOCOLCHAR(':');
SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
SERIAL_PROTOCOLPGM("C->");
SERIAL_PROTOCOL_F(rawHotendTemp(cur_extruder)/OVERSAMPLENR,0);
ECHO_MV(" T", cur_extruder);
ECHO_MV(":", degHotend(cur_extruder),1);
ECHO_MV("C->", rawHotendTemp(cur_extruder)/OVERSAMPLENR,0);
}
#endif
SERIAL_EOL;
ECHO_E;
}
#if HAS_FAN
......@@ -4339,7 +4221,7 @@ inline void gcode_M109() {
inline void gcode_M111() {
if (code_seen('S')) debugLevel = code_value_short();
if (debugDryrun()) {
SERIAL_ECHOLN("DEBUG DRYRUN ENABLED");
ECHO_LM(DB, MSG_DRYRUN_ENABLED);
setTargetBed(0);
for (int8_t cur_hotend = 0; cur_hotend < HOTENDS; ++cur_hotend) {
setTargetHotend(0, cur_hotend);
......@@ -4358,42 +4240,24 @@ inline void gcode_M112() {
* M114: Output current position to serial port
*/
inline void gcode_M114() {
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]);
SERIAL_PROTOCOLPGM(MSG_COUNT_X);
SERIAL_PROTOCOL(float(st_get_position(X_AXIS))/axis_steps_per_unit[X_AXIS]);
SERIAL_PROTOCOLPGM(" Y:");
SERIAL_PROTOCOL(float(st_get_position(Y_AXIS))/axis_steps_per_unit[Y_AXIS]);
SERIAL_PROTOCOLPGM(" Z:");
SERIAL_PROTOCOL(float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]);
SERIAL_EOL;
ECHO_SMV(DB, "X:", current_position[X_AXIS]);
ECHO_MV(" Y:", current_position[Y_AXIS]);
ECHO_MV(" Z:", current_position[Z_AXIS]);
ECHO_MV(" E:", current_position[E_AXIS]);
ECHO_MV(MSG_COUNT_X, float(st_get_position(X_AXIS))/axis_steps_per_unit[X_AXIS]);
ECHO_MV(" Y:", float(st_get_position(Y_AXIS))/axis_steps_per_unit[Y_AXIS]);
ECHO_EMV(" Z:", float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]);
#ifdef SCARA
SERIAL_PROTOCOLPGM("SCARA Theta:");
SERIAL_PROTOCOL(delta[X_AXIS]);
SERIAL_PROTOCOLPGM(" Psi+Theta:");
SERIAL_PROTOCOL(delta[Y_AXIS]);
SERIAL_EOL;
ECHO_SMV(DB, "SCARA Theta:", delta[X_AXIS]);
ECHO_EMV(" Psi+Theta:", delta[Y_AXIS]);
SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
SERIAL_PROTOCOL(delta[X_AXIS]+home_offset[X_AXIS]);
SERIAL_PROTOCOLPGM(" Psi+Theta (90):");
SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+home_offset[Y_AXIS]);
SERIAL_EOL;
ECHO_SMV(DB, "SCARA Cal - Theta:", delta[X_AXIS]+home_offset[X_AXIS]);
ECHO_EMV(" Psi+Theta (90):", delta[Y_AXIS]-delta[X_AXIS]-90+home_offset[Y_AXIS]);
SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
SERIAL_PROTOCOL(delta[X_AXIS]/90*axis_steps_per_unit[X_AXIS]);
SERIAL_PROTOCOLPGM(" Psi+Theta:");
SERIAL_PROTOCOL((delta[Y_AXIS]-delta[X_AXIS])/90*axis_steps_per_unit[Y_AXIS]);
SERIAL_EOL; SERIAL_EOL;
ECHO_SMV(DB, "SCARA step Cal - Theta:", delta[X_AXIS]/90*axis_steps_per_unit[X_AXIS]);
ECHO_EMV(" Psi+Theta:", (delta[Y_AXIS]-delta[X_AXIS])/90*axis_steps_per_unit[Y_AXIS]);
#endif
}
......@@ -4401,7 +4265,7 @@ inline void gcode_M114() {
* M115: Capabilities string
*/
inline void gcode_M115() {
SERIAL_PROTOCOLPGM(MSG_M115_REPORT);
ECHO_M(MSG_M115_REPORT);
}
/**
......@@ -4418,47 +4282,38 @@ inline void gcode_M117() {
* M119: Output endstop states to serial output
*/
inline void gcode_M119() {
SERIAL_PROTOCOLLN(MSG_M119_REPORT);
ECHO_LV(DB, MSG_M119_REPORT);
#if HAS_X_MIN
SERIAL_PROTOCOLPGM(MSG_X_MIN);
SERIAL_PROTOCOLLN(((READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_X_MIN, ((READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if HAS_X_MAX
SERIAL_PROTOCOLPGM(MSG_X_MAX);
SERIAL_PROTOCOLLN(((READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_X_MAX, ((READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if HAS_Y_MIN
SERIAL_PROTOCOLPGM(MSG_Y_MIN);
SERIAL_PROTOCOLLN(((READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_Y_MIN, ((READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if HAS_Y_MAX
SERIAL_PROTOCOLPGM(MSG_Y_MAX);
SERIAL_PROTOCOLLN(((READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_Y_MAX, ((READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if HAS_Z_MIN
SERIAL_PROTOCOLPGM(MSG_Z_MIN);
SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_Z_MIN, ((READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if HAS_Z_MAX
SERIAL_PROTOCOLPGM(MSG_Z_MAX);
SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_Z_MAX, ((READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if HAS_Z2_MAX
SERIAL_PROTOCOLPGM(MSG_Z2_MAX);
SERIAL_PROTOCOLLN(((READ(Z2_MAX_PIN)^Z2_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_Z2_MAX, ((READ(Z2_MAX_PIN)^Z2_MAX_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if HAS_Z_PROBE
SERIAL_PROTOCOLPGM(MSG_Z_PROBE);
SERIAL_PROTOCOLLN(((READ(Z_PROBE_PIN)^Z_PROBE_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_Z_PROBE, ((READ(Z_PROBE_PIN)^Z_PROBE_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if HAS_E_MIN
SERIAL_PROTOCOLPGM(MSG_E_MIN);
SERIAL_PROTOCOLLN(((READ(E_MIN_PIN)^E_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_E_MIN, ((READ(E_MIN_PIN)^E_MIN_ENDSTOP_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
#if HAS_FILRUNOUT
SERIAL_PROTOCOLPGM(MSG_FILRUNOUT_PIN);
SERIAL_PROTOCOLLN(((READ(FILRUNOUT_PIN)^FILRUNOUT_PIN_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
ECHO_EMV(MSG_FILRUNOUT_PIN, ((READ(FILRUNOUT_PIN)^FILRUNOUT_PIN_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
#endif
ECHO_E;
}
/**
......@@ -4544,8 +4399,7 @@ inline void gcode_M200() {
if (code_seen('T')) {
tmp_extruder = code_value_short();
if (tmp_extruder >= EXTRUDERS) {
SERIAL_ECHO_START;
SERIAL_ECHO(MSG_M200_INVALID_EXTRUDER);
ECHO_LM(ER, MSG_M200_INVALID_EXTRUDER);
return;
}
}
......@@ -4616,23 +4470,19 @@ inline void gcode_M204() {
if (code_seen('S')) { // Kept for legacy compatibility. Should NOT BE USED for new developments.
acceleration = code_value();
travel_acceleration = acceleration;
SERIAL_ECHOPAIR("Setting Print and Travel Acceleration: ", acceleration );
SERIAL_EOL;
ECHO_LMV(DB, "Setting Print and Travel Acceleration: ", acceleration );
}
if (code_seen('P')) {
acceleration = code_value();
SERIAL_ECHOPAIR("Setting Print Acceleration: ", acceleration );
SERIAL_EOL;
ECHO_LMV(DB, "Setting Print Acceleration: ", acceleration );
}
if (code_seen('R')) {
retract_acceleration = code_value();
SERIAL_ECHOPAIR("Setting Retract Acceleration: ", retract_acceleration );
SERIAL_EOL;
ECHO_LMV(DB, "Setting Retract Acceleration: ", retract_acceleration );
}
if (code_seen('T')) {
travel_acceleration = code_value();
SERIAL_ECHOPAIR("Setting Travel Acceleration: ", travel_acceleration );
SERIAL_EOL;
ECHO_LMV(DB, "Setting Travel Acceleration: ", travel_acceleration );
}
}
......@@ -4704,10 +4554,8 @@ inline void gcode_M206() {
autoretract_enabled = true;
break;
default:
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_UNKNOWN_COMMAND);
SERIAL_ECHO(command_queue[cmd_queue_index_r]);
SERIAL_ECHOLNPGM("\"");
ECHO_SM(ER, MSG_UNKNOWN_COMMAND);
ECHO_EVM(command_queue[cmd_queue_index_r], "\"");
return;
}
for (int i=0; i < EXTRUDERS; i++) retracted[i] = false;
......@@ -4730,19 +4578,15 @@ inline void gcode_M206() {
if (code_seen('Z')) hotend_offset[Z_AXIS][target_extruder] = code_value();
#endif
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_HOTEND_OFFSET);
ECHO_SM(DB, MSG_HOTEND_OFFSET);
for (int e = 0; e < EXTRUDERS; e++) {
SERIAL_CHAR(' ');
SERIAL_ECHO(hotend_offset[X_AXIS][e]);
SERIAL_CHAR(',');
SERIAL_ECHO(hotend_offset[Y_AXIS][e]);
ECHO_MV(" ", hotend_offset[X_AXIS][e]);
ECHO_MV(",", hotend_offset[Y_AXIS][e]);
#ifdef DUAL_X_CARRIAGE
SERIAL_CHAR(',');
SERIAL_ECHO(hotend_offset[Z_AXIS][e]);
ECHO_MV(",", hotend_offset[Z_AXIS][e]);
#endif
}
SERIAL_EOL;
ECHO_E;
}
#endif //HOTENDS > 1
......@@ -4855,9 +4699,7 @@ inline void gcode_M226() {
*/
inline void gcode_M250() {
if (code_seen('C')) lcd_setcontrast(code_value_short() & 0x3F);
SERIAL_PROTOCOLPGM("lcd contrast value: ");
SERIAL_PROTOCOL(lcd_contrast);
SERIAL_EOL;
ECHO_LMV(DB, "lcd contrast value: ", lcd_contrast);
}
#endif // DOGLCD
......@@ -4882,19 +4724,14 @@ inline void gcode_M226() {
#endif
}
else {
SERIAL_ECHO_START;
SERIAL_ECHO("Servo ");
SERIAL_ECHO(servo_index);
SERIAL_ECHOLN(" out of range");
ECHO_SM(ER, "Servo ");
ECHO_EMV(servo_index, " out of range");
}
}
else if (servo_index >= 0) {
SERIAL_PROTOCOL(MSG_OK);
SERIAL_PROTOCOL(" Servo ");
SERIAL_PROTOCOL(servo_index);
SERIAL_PROTOCOL(": ");
SERIAL_PROTOCOL(servo[servo_index].read());
SERIAL_EOL;
ECHO_S(DB);
ECHO_MV("Servo ", servo_index);
ECHO_EMV(": ", servo[servo_index].read());
}
}
#endif // NUM_SERVOS > 0
......@@ -4941,20 +4778,14 @@ inline void gcode_M226() {
if (code_seen('D')) PID_PARAM(Kd, e) = scalePID_d(code_value());
updatePID();
SERIAL_PROTOCOL(MSG_OK);
SERIAL_PROTOCOL(" e:"); // specify hotend in serial output
SERIAL_PROTOCOL(e);
SERIAL_PROTOCOL(" p:");
SERIAL_PROTOCOL(PID_PARAM(Kp, e));
SERIAL_PROTOCOL(" i:");
SERIAL_PROTOCOL(unscalePID_i(PID_PARAM(Ki, e)));
SERIAL_PROTOCOL(" d:");
SERIAL_PROTOCOL(unscalePID_d(PID_PARAM(Kd, e)));
SERIAL_EOL;
ECHO_S(DB);
ECHO_MV(" e:", e);
ECHO_MV(" p:", PID_PARAM(Kp, e));
ECHO_MV(" i:", unscalePID_i(PID_PARAM(Ki, e)));
ECHO_EMV(" d:", unscalePID_d(PID_PARAM(Kd, e)));
}
else {
SERIAL_ECHO_START;
SERIAL_ECHOLN(MSG_INVALID_EXTRUDER);
ECHO_LM(ER, MSG_INVALID_EXTRUDER);
}
}
#endif // PIDTEMP
......@@ -4993,14 +4824,10 @@ inline void gcode_M303() {
if (code_seen('D')) bedKd = scalePID_d(code_value());
updatePID();
SERIAL_PROTOCOL(MSG_OK);
SERIAL_PROTOCOL(" p:");
SERIAL_PROTOCOL(bedKp);
SERIAL_PROTOCOL(" i:");
SERIAL_PROTOCOL(unscalePID_i(bedKi));
SERIAL_PROTOCOL(" d:");
SERIAL_PROTOCOL(unscalePID_d(bedKd));
SERIAL_EOL;
ECHO_S(DB);
ECHO_MV(" p:", bedKp);
ECHO_MV(" i:", unscalePID_i(bedKi));
ECHO_EMV(" d:", unscalePID_d(bedKd));
}
#endif // PIDTEMPBED
......@@ -5035,7 +4862,7 @@ inline void gcode_M303() {
#ifdef SCARA
bool SCARA_move_to_cal(uint8_t delta_x, uint8_t delta_y) {
//SoftEndsEnabled = false; // Ignore soft endstops during calibration
//SERIAL_ECHOLN(" Soft endstops disabled ");
//ECHO_LM(DB, " Soft endstops disabled ");
if (IsRunning()) {
//get_coordinates(); // For X Y Z E F
delta[X_AXIS] = delta_x;
......@@ -5054,7 +4881,7 @@ inline void gcode_M303() {
* M360: SCARA calibration: Move to cal-position ThetaA (0 deg calibration)
*/
inline bool gcode_M360() {
SERIAL_ECHOLN(" Cal: Theta 0 ");
ECHO_LM(DB, " Cal: Theta 0 ");
return SCARA_move_to_cal(0, 120);
}
......@@ -5062,7 +4889,7 @@ inline void gcode_M303() {
* M361: SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree)
*/
inline bool gcode_M361() {
SERIAL_ECHOLN(" Cal: Theta 90 ");
ECHO_LM(DB, " Cal: Theta 90 ");
return SCARA_move_to_cal(90, 130);
}
......@@ -5070,7 +4897,7 @@ inline void gcode_M303() {
* M362: SCARA calibration: Move to cal-position PsiA (0 deg calibration)
*/
inline bool gcode_M362() {
SERIAL_ECHOLN(" Cal: Psi 0 ");
ECHO_LM(DB, " Cal: Psi 0 ");
return SCARA_move_to_cal(60, 180);
}
......@@ -5078,7 +4905,7 @@ inline void gcode_M303() {
* M363: SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree)
*/
inline bool gcode_M363() {
SERIAL_ECHOLN(" Cal: Psi 90 ");
ECHO_LM(DB," Cal: Psi 90 ");
return SCARA_move_to_cal(50, 90);
}
......@@ -5086,7 +4913,7 @@ inline void gcode_M303() {
* M364: SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position)
*/
inline bool gcode_M364() {
SERIAL_ECHOLN(" Cal: Theta-Psi 90 ");
ECHO_LM(DB, " Cal: Theta-Psi 90 ");
return SCARA_move_to_cal(45, 135);
}
......@@ -5124,8 +4951,7 @@ inline void gcode_M303() {
break;
#endif
default:
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_INVALID_SOLENOID);
ECHO_LM(ER, MSG_INVALID_SOLENOID);
break;
}
}
......@@ -5180,8 +5006,7 @@ inline void gcode_M400() { st_synchronize(); }
filament_width_nominal = code_value();
}
else {
SERIAL_PROTOCOLPGM("Filament dia (nominal mm):");
SERIAL_PROTOCOLLN(filament_width_nominal);
ECHO_LMV(DB, "Filament dia (nominal mm):", filament_width_nominal);
}
#endif
}
......@@ -5204,10 +5029,8 @@ inline void gcode_M400() { st_synchronize(); }
filament_sensor = true;
//SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
//SERIAL_PROTOCOL(filament_width_meas);
//SERIAL_PROTOCOLPGM("Extrusion ratio(%):");
//SERIAL_PROTOCOL(extruder_multiply[active_extruder]);
//ECHO_SMV(DB, "Filament dia (measured mm):", filament_width_meas);
//ECHO_EMV("Extrusion ratio(%):", extruder_multiply[active_extruder]);
}
/**
......@@ -5219,8 +5042,7 @@ inline void gcode_M400() { st_synchronize(); }
* M407: Get measured filament diameter on serial output
*/
inline void gcode_M407() {
SERIAL_PROTOCOLPGM("Filament dia (measured mm):");
SERIAL_PROTOCOLLN(filament_width_meas);
ECHO_LMV(DB, "Filament dia (measured mm):", filament_width_meas);
}
#endif // FILAMENT_SENSOR
......@@ -5333,7 +5155,7 @@ inline void gcode_M503() {
}
int old_target_temperature_bed = target_temperature_bed;
millis_t last_set = millis();
PRESSBUTTON:
LCD_ALERTMESSAGEPGM(MSG_FILAMENTCHANGE);
while (!lcd_clicked()) {
......@@ -5431,16 +5253,11 @@ inline void gcode_M503() {
case DXC_DUPLICATION_MODE:
if (code_seen('X')) duplicate_extruder_x_offset = max(code_value(), X2_MIN_POS - x_home_pos(0));
if (code_seen('R')) duplicate_extruder_temp_offset = code_value();
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_HOTEND_OFFSET);
SERIAL_CHAR(' ');
SERIAL_ECHO(extruder_offset[X_AXIS][0]);
SERIAL_CHAR(',');
SERIAL_ECHO(extruder_offset[Y_AXIS][0]);
SERIAL_CHAR(' ');
SERIAL_ECHO(duplicate_extruder_x_offset);
SERIAL_CHAR(',');
SERIAL_ECHOLN(extruder_offset[Y_AXIS][1]);
ECHO_SM(DB, MSG_HOTEND_OFFSET);
ECHO_MV(" ", extruder_offset[X_AXIS][0]);
ECHO_MV(",", extruder_offset[Y_AXIS][0]);
ECHO_MV(" ", duplicate_extruder_x_offset);
ECHO_EMV(",", extruder_offset[Y_AXIS][1]);
break;
case DXC_FULL_CONTROL_MODE:
case DXC_AUTO_PARK_MODE:
......@@ -5462,8 +5279,7 @@ inline void gcode_M503() {
zprobe_zoffset = code_value();
}
if (code_seen('L')) {
SERIAL_ECHOPAIR("P (Z-Probe Offset):", zprobe_zoffset);
SERIAL_EOL;
ECHO_LMV(DB, "P (Z-Probe Offset):", zprobe_zoffset);
}
}
#endif
......@@ -5524,35 +5340,22 @@ inline void gcode_M503() {
}
}
if (code_seen('L')) {
SERIAL_ECHOLN("Current Delta geometry values:");
SERIAL_ECHOPAIR("X (Endstop Adj): ",endstop_adj[0]);
SERIAL_EOL;
SERIAL_ECHOPAIR("Y (Endstop Adj): ",endstop_adj[1]);
SERIAL_EOL;
SERIAL_ECHOPAIR("Z (Endstop Adj): ",endstop_adj[2]);
SERIAL_EOL;
SERIAL_ECHOPAIR("P (Z-Probe Offset): X", z_probe_offset[0]);
SERIAL_ECHOPAIR(" Y", z_probe_offset[1]);
SERIAL_ECHOPAIR(" Z", z_probe_offset[2]);
SERIAL_EOL;
SERIAL_ECHOPAIR("A (Tower A Position Correction): ",tower_adj[0]);
SERIAL_EOL;
SERIAL_ECHOPAIR("B (Tower B Position Correction): ",tower_adj[1]);
SERIAL_EOL;
SERIAL_ECHOPAIR("C (Tower C Position Correction): ",tower_adj[2]);
SERIAL_EOL;
SERIAL_ECHOPAIR("I (Tower A Radius Correction): ",tower_adj[3]);
SERIAL_EOL;
SERIAL_ECHOPAIR("J (Tower B Radius Correction): ",tower_adj[4]);
SERIAL_EOL;
SERIAL_ECHOPAIR("K (Tower C Radius Correction): ",tower_adj[5]);
SERIAL_EOL;
SERIAL_ECHOPAIR("R (Delta Radius): ",delta_radius);
SERIAL_EOL;
SERIAL_ECHOPAIR("D (Diagonal Rod Length): ",delta_diagonal_rod);
SERIAL_EOL;
SERIAL_ECHOPAIR("H (Z-Height): ",max_pos[Z_AXIS]);
SERIAL_EOL;
ECHO_LM(DB, "Current Delta geometry values:");
ECHO_LMV(DB, "X (Endstop Adj): ",endstop_adj[0]);
ECHO_LMV(DB, "Y (Endstop Adj): ",endstop_adj[1]);
ECHO_LMV(DB, "Z (Endstop Adj): ",endstop_adj[2]);
ECHO_SMV(DB, "P (Z-Probe Offset): X", z_probe_offset[0]);
ECHO_MV(" Y", z_probe_offset[1]);
ECHO_EMV(" Z", z_probe_offset[2]);
ECHO_LMV(DB, "A (Tower A Position Correction): ",tower_adj[0]);
ECHO_LMV(DB, "B (Tower B Position Correction): ",tower_adj[1]);
ECHO_LMV(DB, "C (Tower C Position Correction): ",tower_adj[2]);
ECHO_LMV(DB, "I (Tower A Radius Correction): ",tower_adj[3]);
ECHO_LMV(DB, "J (Tower B Radius Correction): ",tower_adj[4]);
ECHO_LMV(DB, "K (Tower C Radius Correction): ",tower_adj[5]);
ECHO_LMV(DB, "R (Delta Radius): ",delta_radius);
ECHO_LMV(DB, "D (Diagonal Rod Length): ",delta_diagonal_rod);
ECHO_LMV(DB, "H (Z-Height): ",max_pos[Z_AXIS]);
}
}
#endif
......@@ -5604,9 +5407,7 @@ inline void gcode_M907() {
long csteps;
if (code_seen('C')) {
csteps = code_value() * color_step_moltiplicator;
SERIAL_ECHO_START;
SERIAL_ECHO("csteps: ");
SERIAL_PROTOCOLLN(csteps);
ECHO_LMV(DB, "csteps: ", csteps);
if (csteps < 0) colorstep(-csteps,false);
if (csteps > 0) colorstep(csteps,true);
}
......@@ -5630,25 +5431,16 @@ inline void gcode_M999() {
value = code_value();
if (Z_PROBE_OFFSET_RANGE_MIN <= value && value <= Z_PROBE_OFFSET_RANGE_MAX) {
zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_ZPROBE_ZOFFSET " " MSG_OK);
SERIAL_EOL;
ECHO_LM(DB, MSG_ZPROBE_ZOFFSET " " MSG_OK);
}
else {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_ZPROBE_ZOFFSET);
SERIAL_ECHOPGM(MSG_Z_MIN);
SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MIN);
SERIAL_ECHOPGM(MSG_Z_MAX);
SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MAX);
SERIAL_EOL;
ECHO_S(DB, MSG_ZPROBE_ZOFFSET);
ECHO_LMV(DB, MSG_Z_MIN, Z_PROBE_OFFSET_RANGE_MIN);
ECHO_LMV(DB, MSG_Z_MAX,Z_PROBE_OFFSET_RANGE_MAX);
}
}
else {
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_ZPROBE_ZOFFSET " : ");
SERIAL_ECHO(-zprobe_zoffset);
SERIAL_EOL;
ECHO_LM(DB, MSG_ZPROBE_ZOFFSET " : ", -zprobe_zoffset);
}
}
......@@ -5658,10 +5450,8 @@ inline void gcode_T() {
int tmp_extruder = code_value();
long csteps;
if (tmp_extruder >= EXTRUDERS) {
SERIAL_ECHO_START;
SERIAL_CHAR('T');
SERIAL_ECHO(tmp_extruder);
SERIAL_ECHOLN(MSG_INVALID_EXTRUDER);
ECHO_SMV(DB, "T", tmp_extruder);
ECHO_EM(MSG_INVALID_EXTRUDER);
}
else {
target_extruder = tmp_extruder;
......@@ -5847,12 +5637,8 @@ inline void gcode_T() {
}
#endif // E0E1_CHOICE_PIN E0E2_CHOICE_PIN E1E3_CHOICE_PIN
active_extruder = target_extruder;
SERIAL_ECHO_START;
SERIAL_ECHO("Active Driver: ");
SERIAL_PROTOCOLLN((int)active_driver);
SERIAL_ECHO_START;
SERIAL_ECHO(MSG_ACTIVE_EXTRUDER);
SERIAL_PROTOCOLLN((int)active_extruder);
ECHO_LM(DB, MSG_ACTIVE_DRIVER, active_driver);
ECHO_LM(DB, MSG_ACTIVE_EXTRUDER, active_extruder);
#elif defined(NPR2)
st_synchronize(); // Finish all movement
if (old_color == 99)
......@@ -5867,14 +5653,10 @@ inline void gcode_T() {
if (csteps > 0) colorstep(csteps,true);
old_color = active_extruder = target_extruder;
active_driver = 0;
SERIAL_ECHO_START;
SERIAL_ECHO("Active Color: ");
SERIAL_PROTOCOLLN((int)active_extruder);
ECHO_LM(DB, MSG_ACTIVE_COLOR, active_extruder);
#else
active_driver = active_extruder = target_extruder;
SERIAL_ECHO_START;
SERIAL_ECHO(MSG_ACTIVE_EXTRUDER);
SERIAL_PROTOCOLLN((int)active_extruder);
ECHO_S(DB, MSG_ACTIVE_EXTRUDER, active_extruder);
#endif // end MKR4 || NPR2
#endif // end no DUAL_X_CARRIAGE
......@@ -6291,10 +6073,8 @@ void process_commands() {
}
else {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_UNKNOWN_COMMAND);
SERIAL_ECHO(command_queue[cmd_queue_index_r]);
SERIAL_ECHOLNPGM("\"");
ECHO_SM(ER, MSG_UNKNOWN_COMMAND);
ECHO_EVM(command_queue[cmd_queue_index_r], "\"");
}
ClearToSend();
......@@ -6303,8 +6083,7 @@ void process_commands() {
void FlushSerialRequestResend() {
//char command_queue[cmd_queue_index_r][100]="Resend:";
MYSERIAL.flush();
SERIAL_PROTOCOLPGM(MSG_RESEND);
SERIAL_PROTOCOLLN(gcode_LastN + 1);
ECHO_LV(RS, gcode_LastN + 1);
ClearToSend();
}
......@@ -6313,7 +6092,8 @@ void ClearToSend() {
#ifdef SDSUPPORT
if (fromsd[cmd_queue_index_r]) return;
#endif
SERIAL_PROTOCOLLNPGM(MSG_OK);
ECHO_S(OK);
ECHO_E;
}
void get_coordinates() {
......@@ -6377,15 +6157,13 @@ void clamp_to_software_endstops(float target[3]) {
if (de) {
if (degHotend(active_extruder) < extrude_min_temp) {
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);
ECHO_LM(ER, MSG_ERR_COLD_EXTRUDE_STOP);
return 0;
}
#ifdef 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);
ECHO_LM(ER, MSG_ERR_LONG_EXTRUDE_STOP);
return 0;
}
#endif
......@@ -6414,25 +6192,23 @@ void prepare_move() {
float seconds = 6000 * cartesian_mm / feedrate / feedrate_multiplier;
int steps = max(1, int(scara_segments_per_second * seconds));
//SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
//SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
//SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
//ECHO_SMV(DB, "mm=", cartesian_mm);
//ECHO_MV(" seconds=", seconds);
//ECHO_EMV(" steps=", steps);
for (int s = 1; s <= steps; s++) {
float fraction = float(s) / float(steps);
for (int8_t i = 0; i < NUM_AXIS; i++) destination[i] = current_position[i] + difference[i] * fraction;
calculate_delta(destination);
//SERIAL_ECHOPGM("destination[X_AXIS]="); SERIAL_ECHOLN(destination[X_AXIS]);
//SERIAL_ECHOPGM("destination[Y_AXIS]="); SERIAL_ECHOLN(destination[Y_AXIS]);
//SERIAL_ECHOPGM("destination[Z_AXIS]="); SERIAL_ECHOLN(destination[Z_AXIS]);
//SERIAL_ECHOPGM("delta[X_AXIS]="); SERIAL_ECHOLN(delta[X_AXIS]);
//SERIAL_ECHOPGM("delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
//SERIAL_ECHOPGM("delta[Z_AXIS]="); SERIAL_ECHOLN(delta[Z_AXIS]);
//ECHO_SMV(DB, "destination[X_AXIS]=", destination[X_AXIS]);
//ECHO_MV("destination[Y_AXIS]=", destination[Y_AXIS]);
//ECHO_MV("destination[Z_AXIS]=", destination[Z_AXIS]);
//ECHO_MV("delta[X_AXIS]=", delta[X_AXIS]);
//ECHO_MV("delta[Y_AXIS]=", delta[Y_AXIS]);
//ECHO_EMV("delta[Z_AXIS]=", delta[Z_AXIS]);
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS],
destination[E_AXIS], feedrate*feedrate_multiplier/60/100.0,
active_extruder);
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], feedrate*feedrate_multiplier/60/100.0, active_extruder, active_driver);
}
#endif // SCARA
......@@ -6447,9 +6223,9 @@ void prepare_move() {
float seconds = 6000 * cartesian_mm / feedrate / feedrate_multiplier;
int steps = max(1, int(DELTA_SEGMENTS_PER_SECOND * seconds));
// SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
// SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
// SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
// ECHO_SMV(DB,"mm=", cartesian_mm);
// ECHO_MV(" seconds=", seconds);
// ECHO_EMV(" steps=", steps);
for (int s = 1; s <= steps; s++) {
float fraction = float(s) / float(steps);
......@@ -6567,24 +6343,24 @@ void calculate_SCARA_forward_Transform(float f_scara[3])
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]);
//ECHO_SMV(DB,"f_delta x=", f_scara[X_AXIS]);
//ECHO_MV(" y=", 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);
//ECHO_MV(" x_sin=", x_sin);
//ECHO_MV(" x_cos=", x_cos);
//ECHO_MV(" y_sin=", y_sin);
//ECHO_MV(" y_cos=", 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
//SERIAL_ECHOPGM(" delta[X_AXIS]="); SERIAL_ECHO(delta[X_AXIS]);
//SERIAL_ECHOPGM(" delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
//ECHO_MV(" delta[X_AXIS]=", delta[X_AXIS]);
//ECHO_EMV(" delta[Y_AXIS]=", delta[Y_AXIS]);
}
void calculate_delta(float cartesian[3]){
......@@ -6617,22 +6393,22 @@ void calculate_delta(float cartesian[3]){
delta[Z_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]);
ECHO_SMV(DB, "cartesian x=", cartesian[X_AXIS]);
ECHO_MV(" y=", cartesian[Y_AXIS]);
ECHO_MV(" z=", cartesian[Z_AXIS]);
SERIAL_ECHOPGM("scara x="); SERIAL_ECHO(SCARA_pos[X_AXIS]);
SERIAL_ECHOPGM(" y="); SERIAL_ECHOLN(SCARA_pos[Y_AXIS]);
ECHO_MV("scara x=", SCARA_pos[X_AXIS]);
ECHO_MV(" y=", Y_AXIS]);
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]);
ECHO_MV("delta x=", delta[X_AXIS]);
ECHO_MV(" y=", delta[Y_AXIS]);
ECHO_MV(" z=", delta[Z_AXIS]);
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_ECHOLN(" ");*/
ECHO_MV("C2=", SCARA_C2);
ECHO_MV(" S2=", SCARA_S2);
ECHO_MV(" Theta=", SCARA_theta);
ECHO_EMV(" Psi=", SCARA_psi);
*/
}
#endif
......@@ -6834,16 +6610,32 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) {
if (!filament_changing)
#endif
{
if (degHotend(active_extruder) < IDLE_OOZING_MAXTEMP && degTargetHotend(active_extruder) < IDLE_OOZING_MINTEMP) {
if(degTargetHotend(active_extruder) < IDLE_OOZING_MINTEMP) {
IDLE_OOZING_retract(false);
}
else if((millis() - axis_last_activity) > IDLE_OOZING_SECONDS*1000) {
else if((millis() - axis_last_activity) > IDLE_OOZING_SECONDS*1000UL) {
IDLE_OOZING_retract(true);
}
}
}
#endif
#if defined(SDSUPPORT) && defined(SD_SETTINGS)
if(IS_SD_INSERTED && !IS_SD_PRINTING) {
if(!config_readed) {
ConfigSD_RetrieveSettings(true);
ConfigSD_StoreSettings();
}
else if((millis() - config_last_update) > SD_CFG_SECONDS*1000UL) {
ConfigSD_StoreSettings();
}
}
#endif
#ifdef TEMP_STAT_LEDS
handle_status_leds();
#endif
#ifdef TEMP_STAT_LEDS
handle_status_leds();
#endif
......@@ -6851,8 +6643,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) {
check_axes_activity();
}
void kill()
{
void kill() {
cli(); // Stop interrupts
disable_all_heaters();
......@@ -6862,10 +6653,9 @@ void kill()
SET_INPUT(PS_ON_PIN);
#endif
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_KILLED);
ECHO_LM(ER, MSG_ERR_KILLED);
LCD_ALERTMESSAGEPGM(MSG_KILLED);
// FMC small patch to update the LCD before ending
sei(); // enable interrupts
for (int i = 5; i--; lcd_update()) delay(200); // Wait a short time
......@@ -6888,8 +6678,9 @@ void Stop() {
if (IsRunning()) {
Running = false;
Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
ECHO_LM(ER, MSG_ERR_STOPPED);
ECHO_S(PAUSE);
ECHO_E;
LCD_MESSAGEPGM(MSG_STOPPED);
}
}
......@@ -6966,25 +6757,25 @@ bool setTargetedHotend(int code) {
if (code_seen('T')) {
target_extruder = code_value_short();
if (target_extruder >= EXTRUDERS) {
SERIAL_ECHO_START;
ECHO_S(ER);
switch(code) {
case 104:
SERIAL_ECHO(MSG_M104_INVALID_EXTRUDER);
ECHO_M(MSG_M104_INVALID_EXTRUDER);
break;
case 105:
SERIAL_ECHO(MSG_M105_INVALID_EXTRUDER);
ECHO_M(MSG_M105_INVALID_EXTRUDER);
break;
case 109:
SERIAL_ECHO(MSG_M109_INVALID_EXTRUDER);
ECHO_M(MSG_M109_INVALID_EXTRUDER);
break;
case 218:
SERIAL_ECHO(MSG_M218_INVALID_EXTRUDER);
ECHO_M(MSG_M218_INVALID_EXTRUDER);
break;
case 221:
SERIAL_ECHO(MSG_M221_INVALID_EXTRUDER);
ECHO_M(MSG_M221_INVALID_EXTRUDER);
break;
}
SERIAL_ECHOLN(target_extruder);
ECHO_EV(target_extruder);
return true;
}
}
......
......@@ -60,9 +60,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
SdFile dir;
if (!dir.open(parent, lfilename, O_READ)) {
if (lsAction == LS_SerialPrint) {
SERIAL_ECHO_START;
SERIAL_ECHOLN(MSG_SD_CANT_OPEN_SUBDIR);
SERIAL_ECHOLN(lfilename);
ECHO_LMV(ER, MSG_SD_CANT_OPEN_SUBDIR, lfilename);
}
}
lsDive(path, dir);
......@@ -84,8 +82,8 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
//if (cnt++ != nr) continue;
createFilename(filename, p);
if (lsAction == LS_SerialPrint) {
SERIAL_PROTOCOL(prepend);
SERIAL_PROTOCOLLN(filename);
ECHO_V(prepend);
ECHO_EV(filename);
}
else if (lsAction == LS_Count) {
nrFiles++;
......@@ -122,35 +120,29 @@ void CardReader::initsd() {
&& !card.init(SPI_SPEED, LCD_SDSS)
#endif
) {
//if (!card.init(SPI_HALF_SPEED,SDSS))
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_SD_INIT_FAIL);
ECHO_LM(ER, MSG_SD_INIT_FAIL);
}
else if (!volume.init(&card)) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_SD_VOL_INIT_FAIL);
ECHO_LM(ER, MSG_SD_VOL_INIT_FAIL);
}
else if (!root.openRoot(&volume)) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_SD_OPENROOT_FAIL);
ECHO_LM(ER, MSG_SD_OPENROOT_FAIL);
}
else {
cardOK = true;
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_SD_CARD_OK);
ECHO_LM(OK, MSG_SD_CARD_OK);
}
workDir = root;
curDir = &root;
/*
if (!workDir.openRoot(&volume)) {
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
}
*/
/*if (!workDir.openRoot(&volume)) {
ECHO_EM(MSG_SD_WORKDIR_FAIL);
}*/
}
void CardReader::setroot() {
/*if (!workDir.openRoot(&volume)) {
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
ECHO_EM(MSG_SD_WORKDIR_FAIL);
}*/
workDir = root;
curDir = &workDir;
......@@ -189,44 +181,25 @@ void CardReader::getAbsFilename(char *t) {
t[0] = 0;
}
void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/) {
void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/, bool lcd_status/*=true*/) {
if (!cardOK) return;
if (file.isOpen()) { //replacing current file by new file, or subfile call
if (!replace_current) {
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
SERIAL_ERRORLN(SD_PROCEDURE_DEPTH);
kill();
return;
}
SERIAL_ECHO_START;
SERIAL_ECHOPGM("SUBROUTINE CALL target:\"");
SERIAL_ECHO(name);
SERIAL_ECHOPGM("\" parent:\"");
//store current filename and position
getAbsFilename(filenames[file_subcall_ctr]);
SERIAL_ECHO(filenames[file_subcall_ctr]);
SERIAL_ECHOPGM("\" pos");
SERIAL_ECHOLN(sdpos);
filespos[file_subcall_ctr] = sdpos;
file_subcall_ctr++;
}
else {
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Now doing file: ");
SERIAL_ECHOLN(name);
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
ECHO_LMV(ER, MSG_SD_MAX_DEPTH, SD_PROCEDURE_DEPTH);
kill();
return;
}
//store current filename and position
getAbsFilename(filenames[file_subcall_ctr]);
filespos[file_subcall_ctr] = sdpos;
file_subcall_ctr++;
}
file.close();
}
else { //opening fresh file
file_subcall_ctr = 0; //resetting procedure depth in case user cancels print while in procedure
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Now fresh file: ");
SERIAL_ECHOLN(name);
}
sdprinting = false;
......@@ -239,30 +212,20 @@ void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/)
dirname_start = &name[1];
while(dirname_start > 0) {
dirname_end = strchr(dirname_start, '/');
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start - name));
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end - name));
if (dirname_end > 0 && dirname_end > dirname_start) {
char subdirname[FILENAME_LENGTH];
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
subdirname[dirname_end - dirname_start] = 0;
SERIAL_ECHOLN(subdirname);
if (!myDir.open(curDir, subdirname, O_READ)) {
SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
SERIAL_PROTOCOL(subdirname);
SERIAL_PROTOCOLCHAR('.');
ECHO_LMV(ER, MSG_SD_OPEN_FILE_FAIL, subdirname);
return;
}
else {
//SERIAL_ECHOLN("dive ok");
}
curDir = &myDir;
dirname_start = dirname_end + 1;
}
else { // the remainder after all /fsa/fdsa/ is the filename
fname = dirname_start;
//SERIAL_ECHOLN("remainder");
//SERIAL_ECHOLN(fname);
break;
}
}
......@@ -274,33 +237,24 @@ void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/)
if (read) {
if (file.open(curDir, fname, O_READ)) {
filesize = file.fileSize();
SERIAL_PROTOCOLPGM(MSG_SD_FILE_OPENED);
SERIAL_PROTOCOL(fname);
SERIAL_PROTOCOLPGM(MSG_SD_SIZE);
SERIAL_PROTOCOLLN(filesize);
ECHO_SMV(OK,MSG_SD_FILE_OPENED, fname);
ECHO_EMV(MSG_SD_SIZE, filesize);
sdpos = 0;
SERIAL_PROTOCOLLNPGM(MSG_SD_FILE_SELECTED);
getfilename(0, fname);
lcd_setstatus(longFilename[0] ? longFilename : fname);
if(lcd_status) lcd_setstatus(longFilename[0] ? longFilename : fname);
}
else {
SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
SERIAL_PROTOCOL(fname);
SERIAL_PROTOCOLCHAR('.');
ECHO_LMV(ER,MSG_SD_OPEN_FILE_FAIL,fname);
}
}
else { //write
if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) {
SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
SERIAL_PROTOCOL(fname);
SERIAL_PROTOCOLCHAR('.');
if (file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) {
saving = true;
ECHO_LMV(OK, MSG_SD_WRITE_TO_FILE, name);
if(lcd_status) lcd_setstatus(fname);
}
else {
saving = true;
SERIAL_PROTOCOLPGM(MSG_SD_WRITE_TO_FILE);
SERIAL_PROTOCOLLN(name);
lcd_setstatus(fname);
ECHO_LMV(ER, MSG_SD_OPEN_FILE_FAIL,fname);
}
}
}
......@@ -320,30 +274,20 @@ void CardReader::removeFile(char* name) {
dirname_start = strchr(name, '/') + 1;
while (dirname_start > 0) {
dirname_end = strchr(dirname_start, '/');
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start - name));
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end - name));
if (dirname_end > 0 && dirname_end > dirname_start) {
char subdirname[FILENAME_LENGTH];
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
subdirname[dirname_end - dirname_start] = 0;
SERIAL_ECHOLN(subdirname);
if (!myDir.open(curDir, subdirname, O_READ)) {
SERIAL_PROTOCOLPGM("open failed, File: ");
SERIAL_PROTOCOL(subdirname);
SERIAL_PROTOCOLCHAR('.');
ECHO_LMV(ER, MSG_SD_OPEN_FILE_FAIL, subdirname);
return;
}
else {
//SERIAL_ECHOLN("dive ok");
}
curDir = &myDir;
dirname_start = dirname_end + 1;
}
else { // the remainder after all /fsa/fdsa/ is the filename
fname = dirname_start;
//SERIAL_ECHOLN("remainder");
//SERIAL_ECHOLN(fname);
break;
}
}
......@@ -353,26 +297,21 @@ void CardReader::removeFile(char* name) {
}
if (file.remove(curDir, fname)) {
SERIAL_PROTOCOLPGM("File deleted:");
SERIAL_PROTOCOLLN(fname);
ECHO_LMV(OK, MSG_SD_FILE_DELETED, fname);
sdpos = 0;
}
else {
SERIAL_PROTOCOLPGM("Deletion failed, File: ");
SERIAL_PROTOCOL(fname);
SERIAL_PROTOCOLCHAR('.');
ECHO_LMV(ER, MSG_SD_FILE_DELETION_ERR,fname);
}
}
void CardReader::getStatus() {
if (cardOK) {
SERIAL_PROTOCOLPGM(MSG_SD_PRINTING_BYTE);
SERIAL_PROTOCOL(sdpos);
SERIAL_PROTOCOLCHAR('/');
SERIAL_PROTOCOLLN(filesize);
ECHO_SMV(OK, MSG_SD_PRINTING_BYTE, sdpos);
ECHO_EMV(MSG_SD_SLASH, filesize);
}
else {
SERIAL_PROTOCOLLNPGM(MSG_SD_NOT_PRINTING);
ECHO_LM(OK, MSG_SD_NOT_PRINTING);
}
}
......@@ -391,8 +330,7 @@ void CardReader::write_command(char *buf) {
end[3] = '\0';
file.write(begin);
if (file.writeError) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_SD_ERR_WRITE_TO_FILE);
ECHO_LM(ER, MSG_SD_ERR_WRITE_TO_FILE);
}
}
......@@ -432,7 +370,7 @@ void CardReader::checkautostart(bool force) {
autostart_index++;
}
void CardReader::closefile(bool store_location) {
void CardReader::closeFile(bool store_location) {
file.sync();
file.close();
saving = logging = false;
......@@ -443,6 +381,103 @@ void CardReader::closefile(bool store_location) {
}
}
/**
* File parser for KEY->VALUE format from files
*
* Author: Simone Primarosa
*
*/
void CardReader::parseKeyLine(char *key, char *value, int &len_k, int &len_v) {
if (!cardOK || !isFileOpen()) {
key[0] = value[0] = '\0';
len_k = len_v = 0;
return;
}
int ln_buf = 0;
char ln_char;
bool ln_space = false, ln_ignore = false, key_found = false;
while(!eof()) { //READ KEY
ln_char = (char)get();
if(ln_char == '\n') {
ln_buf = 0;
ln_ignore = false; //We've reached a new line try to find a key again
continue;
}
if(ln_ignore) continue;
if(ln_char == ' ') {
ln_space = true;
continue;
}
if(ln_char == '=') {
key[ln_buf] = '\0';
len_k = ln_buf;
key_found = true;
break; //key finded and buffered
}
if(ln_char == ';' || ln_buf+1 >= len_k || ln_space && ln_buf > 0) { //comments on key is not allowd. Also key len can't be longer than len_k or contain spaces. Stop buffering and try the next line
ln_ignore = true;
continue;
}
ln_space = false;
key[ln_buf] = ln_char;
ln_buf++;
}
if(!key_found) { //definitly there isn't no more key that can be readed in the file
key[0] = value[0] = '\0';
len_k = len_v = 0;
return;
}
ln_buf = 0;
ln_ignore = false;
while(!eof()) { //READ VALUE
ln_char = (char)get();
if(ln_char == '\n') {
value[ln_buf] = '\0';
len_v = ln_buf;
break; //new line reached, we can stop
}
if(ln_ignore|| ln_char == ' ' && ln_buf == 0) continue; //ignore also initial spaces of the value
if(ln_char == ';' || ln_buf+1 >= len_v) { //comments reached or value len longer than len_v. Stop buffering and go to the next line.
ln_ignore = true;
continue;
}
value[ln_buf] = ln_char;
ln_buf++;
}
}
void CardReader::unparseKeyLine(const char *key, char *value) {
if (!cardOK || !isFileOpen()) return;
file.writeError = false;
file.write(key);
if (file.writeError) {
ECHO_LM(ER, MSG_SD_ERR_WRITE_TO_FILE);
return;
}
file.writeError = false;
file.write("=");
if (file.writeError) {
ECHO_LM(ER, MSG_SD_ERR_WRITE_TO_FILE);
return;
}
file.writeError = false;
file.write(value);
if (file.writeError) {
ECHO_LM(ER, MSG_SD_ERR_WRITE_TO_FILE);
return;
}
file.writeError = false;
file.write("\n");
if (file.writeError) {
ECHO_LM(ER, MSG_SD_ERR_WRITE_TO_FILE);
return;
}
}
/**
* Get the name of a file in the current directory by index
*/
......@@ -460,7 +495,6 @@ uint16_t CardReader::getnrfilenames() {
nrFiles = 0;
curDir->rewind();
lsDive("", *curDir);
//SERIAL_ECHOLN(nrFiles);
return nrFiles;
}
......@@ -470,24 +504,22 @@ void CardReader::chdir(const char * relpath) {
if (workDir.isOpen()) parent = &workDir;
if (!newfile.open(*parent, relpath, O_READ)) {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
SERIAL_ECHOLN(relpath);
}
else {
if (newfile.open(*parent, relpath, O_READ)) {
if (workDirDepth < MAX_DIR_DEPTH) {
++workDirDepth;
workDirDepth++;
for (int d = workDirDepth; d--;) workDirParents[d + 1] = workDirParents[d];
workDirParents[0] = *parent;
}
workDir = newfile;
}
else {
ECHO_LMV(ER, MSG_SD_CANT_ENTER_SUBDIR, relpath);
}
}
void CardReader::updir() {
if (workDirDepth > 0) {
--workDirDepth;
workDirDepth--;
workDir = workDirParents[0];
for (uint16_t d = 0; d < workDirDepth; d++)
workDirParents[d] = workDirParents[d+1];
......
......@@ -18,17 +18,19 @@ public:
//this is to delay autostart and hence the initialisaiton of the sd card to some seconds after the normal init, so the device is available quick after a reset
void checkautostart(bool x);
void openFile(char* name,bool read,bool replace_current=true);
void openFile(char* name, bool read, bool replace_current = true, bool lcd_status = true);
void openLogFile(char* name);
void removeFile(char* name);
void closefile(bool store_location=false);
void closeFile(bool store_location = false);
void parseKeyLine(char *key, char *value, int &len_k, int &len_v);
void unparseKeyLine(const char *key, char *value);
void release();
void startFileprint();
void pauseSDPrint();
void getStatus();
void printingHasFinished();
void getfilename(uint16_t nr, const char* const match=NULL);
void getfilename(uint16_t nr, const char* const match = NULL);
uint16_t getnrfilenames();
void getAbsFilename(char *t);
......
......@@ -186,13 +186,13 @@ static void lcd_implementation_init() {
// digitalWrite(17, HIGH);
#ifdef LCD_SCREEN_ROT_90
u8g.setRot90(); // Rotate screen by 90
u8g.setRot90(); // Rotate screen by 90°
#elif defined(LCD_SCREEN_ROT_180)
u8g.setRot180(); // Rotate screen by 180
u8g.setRot180(); // Rotate screen by 180°
#elif defined(LCD_SCREEN_ROT_270)
u8g.setRot270(); // Rotate screen by 270
u8g.setRot270(); // Rotate screen by 270°
#endif
// Show splashscreen
int offx = (u8g.getWidth() - START_BMPWIDTH) / 2;
#ifdef START_BMPHIGH
......
......@@ -14,225 +14,224 @@ static char serial_answer;
void FirmwareTest()
{
SERIAL_ECHOLN("---------- FIRMWARE TEST --------------");
SERIAL_ECHOLN("--------- by MarlinKimbra -------------");
SERIAL_ECHOLN(" ");
SERIAL_ECHOLN(MSG_FWTEST_01);
SERIAL_ECHOLN(MSG_FWTEST_02);
SERIAL_ECHOLN(MSG_FWTEST_YES_NO);
ECHO_EM("---------- FIRMWARE TEST --------------");
ECHO_EM("--------- by MarlinKimbra -------------");
ECHO_EV(MSG_FWTEST_01);
ECHO_EV(MSG_FWTEST_02);
ECHO_EV(MSG_FWTEST_YES_NO);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && serial_answer!='n' && serial_answer!='N') {
serial_answer = MYSERIAL.read();
}
if (serial_answer=='y' || serial_answer=='Y') {
SERIAL_ECHOLN(MSG_FWTEST_03);
ECHO_EV(MSG_FWTEST_03);
SERIAL_ECHOLN(" ");
SERIAL_ECHOLN("***** ENDSTOP X *****");
ECHO_EM(" ");
ECHO_EM("***** ENDSTOP X *****");
#if defined(X_MIN_PIN) && X_MIN_PIN > -1 && X_HOME_DIR == -1
if (!READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING) {
SERIAL_ECHO("MIN ENDSTOP X: ");
SERIAL_ECHOLN(MSG_ENDSTOP_OPEN);
ECHO_M("MIN ENDSTOP X: ");
ECHO_EV(MSG_ENDSTOP_OPEN);
}
else
{
SERIAL_ECHOLN("X ENDSTOP ERROR");
SERIAL_ECHO(MSG_FWTEST_INVERT);
SERIAL_ECHOLN("#define X_MIN_ENDSTOP_INVERTING");
ECHO_EM("X ENDSTOP ERROR");
ECHO_V(MSG_FWTEST_INVERT);
ECHO_EM("#define X_MIN_ENDSTOP_INVERTING");
return;
}
SERIAL_ECHO(MSG_FWTEST_PRESS);
SERIAL_ECHOLN("X");
SERIAL_ECHOLN(MSG_FWTEST_YES);
ECHO_V(MSG_FWTEST_PRESS);
ECHO_EM("X");
ECHO_EV(MSG_FWTEST_YES);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && !(READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING)){
serial_answer = MYSERIAL.read();
}
if (READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING) {
SERIAL_ECHO("MIN ENDSTOP X: ");
SERIAL_ECHOLN(MSG_ENDSTOP_HIT);
ECHO_M("MIN ENDSTOP X: ");
ECHO_EV(MSG_ENDSTOP_HIT);
}
else
{
SERIAL_ECHO("X ");
SERIAL_ECHOLN(MSG_FWTEST_ENDSTOP_ERR);
ECHO_M("X ");
ECHO_EV(MSG_FWTEST_ENDSTOP_ERR);
return;
}
#elif defined(X_MAX_PIN) && X_MAX_PIN > -1 && X_HOME_DIR == 1
if (!READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING) {
SERIAL_ECHO("MAX ENDSTOP X: ");
SERIAL_ECHOLN(MSG_ENDSTOP_OPEN);
ECHO_M("MAX ENDSTOP X: ");
ECHO_EV(MSG_ENDSTOP_OPEN);
}
else
{
SERIAL_ECHOLN("X ENDSTOP ERROR");
SERIAL_ECHO(MSG_FWTEST_INVERT);
SERIAL_ECHOLN("#define X_MAX_ENDSTOP_INVERTING");
ECHO_EM("X ENDSTOP ERROR");
ECHO_V(MSG_FWTEST_INVERT);
ECHO_EM("#define X_MAX_ENDSTOP_INVERTING");
return;
}
SERIAL_ECHO(MSG_FWTEST_PRESS);
SERIAL_ECHOLN("X");
SERIAL_ECHOLN(MSG_FWTEST_YES);
ECHO_V(MSG_FWTEST_PRESS);
ECHO_EM("X");
ECHO_EV(MSG_FWTEST_YES);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && !(READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING)) {
serial_answer = MYSERIAL.read();
}
if (READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING) {
SERIAL_ECHO("MAX ENDSTOP X: ");
SERIAL_ECHOLN(MSG_ENDSTOP_HIT);
ECHO_M("MAX ENDSTOP X: ");
ECHO_EV(MSG_ENDSTOP_HIT);
}
else
{
SERIAL_ECHO("X ");
SERIAL_ECHOLN(MSG_FWTEST_ENDSTOP_ERR);
ECHO_M("X ");
ECHO_EV(MSG_FWTEST_ENDSTOP_ERR);
return;
}
#elif X_HOME_DIR == -1
SERIAL_ECHOLN("ERROR!!! X_MIN_PIN not defined");
ECHO_EM("ERROR!!! X_MIN_PIN not defined");
return;
#elif X_HOME_DIR == 1
SERIAL_ECHOLN("ERROR!!! X_MAX_PIN not defined");
ECHO_EM("ERROR!!! X_MAX_PIN not defined");
return;
#endif
SERIAL_ECHOLN(" ");
SERIAL_ECHOLN("***** ENDSTOP Y *****");
ECHO_EM(" ");
ECHO_EM("***** ENDSTOP Y *****");
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1 && Y_HOME_DIR == -1
if (!READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING){
SERIAL_ECHO("MIN ENDSTOP Y: ");
SERIAL_ECHOLN(MSG_ENDSTOP_OPEN);
ECHO_M("MIN ENDSTOP Y: ");
ECHO_EV(MSG_ENDSTOP_OPEN);
}
else
{
SERIAL_ECHOLN("Y ENDSTOP ERROR");
SERIAL_ECHO(MSG_FWTEST_INVERT);
SERIAL_ECHOLN("#define Y_MIN_ENDSTOP_INVERTING");
ECHO_EM("Y ENDSTOP ERROR");
ECHO_V(MSG_FWTEST_INVERT);
ECHO_EM("#define Y_MIN_ENDSTOP_INVERTING");
return;
}
SERIAL_ECHO(MSG_FWTEST_PRESS);
SERIAL_ECHOLN("Y");
SERIAL_ECHOLN(MSG_FWTEST_YES);
ECHO_V(MSG_FWTEST_PRESS);
ECHO_EM("Y");
ECHO_EV(MSG_FWTEST_YES);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && !(READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING)){
serial_answer = MYSERIAL.read();
}
if (READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING){
SERIAL_ECHO("MIN ENDSTOP Y: ");
SERIAL_ECHOLN(MSG_ENDSTOP_HIT);
ECHO_M("MIN ENDSTOP Y: ");
ECHO_EV(MSG_ENDSTOP_HIT);
}
else
{
SERIAL_ECHO("Y ");
SERIAL_ECHOLN(MSG_FWTEST_ENDSTOP_ERR);
ECHO_M("Y ");
ECHO_EV(MSG_FWTEST_ENDSTOP_ERR);
return;
}
#elif defined(Y_MAX_PIN) && Y_MAX_PIN > -1 && Y_HOME_DIR == 1
if (!READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING){
SERIAL_ECHO("MAX ENDSTOP Y: ");
SERIAL_ECHOLN(MSG_ENDSTOP_OPEN);
ECHO_M("MAX ENDSTOP Y: ");
ECHO_EV(MSG_ENDSTOP_OPEN);
}
else
{
SERIAL_ECHOLN("Y ENDSTOP ERROR");
SERIAL_ECHO(MSG_FWTEST_INVERT);
SERIAL_ECHOLN("#define Y_MAX_ENDSTOP_INVERTING");
ECHO_EM("Y ENDSTOP ERROR");
ECHO_V(MSG_FWTEST_INVERT);
ECHO_EM("#define Y_MAX_ENDSTOP_INVERTING");
return;
}
SERIAL_ECHO(MSG_FWTEST_PRESS);
SERIAL_ECHOLN("Y");
SERIAL_ECHOLN(MSG_FWTEST_YES);
ECHO_V(MSG_FWTEST_PRESS);
ECHO_EM("Y");
ECHO_EV(MSG_FWTEST_YES);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && !(READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING)){
serial_answer = MYSERIAL.read();
}
if (READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING){
SERIAL_ECHO("MAX ENDSTOP Y: ");
SERIAL_ECHOLN(MSG_ENDSTOP_HIT);
ECHO_M("MAX ENDSTOP Y: ");
ECHO_EV(MSG_ENDSTOP_HIT);
}
else
{
SERIAL_ECHO("Y ");
SERIAL_ECHOLN(MSG_FWTEST_ENDSTOP_ERR);
ECHO_M("Y ");
ECHO_EV(MSG_FWTEST_ENDSTOP_ERR);
return;
}
#elif Y_HOME_DIR == -1
SERIAL_ECHOLN("ERROR!!! Y_MIN_PIN not defined");
ECHO_EM("ERROR!!! Y_MIN_PIN not defined");
return;
#elif Y_HOME_DIR == 1
SERIAL_ECHOLN("ERROR!!! Y_MAX_PIN not defined");
ECHO_EM("ERROR!!! Y_MAX_PIN not defined");
return;
#endif
SERIAL_ECHOLN(" ");
SERIAL_ECHOLN("***** ENDSTOP Z *****");
ECHO_EM(" ");
ECHO_EM("***** ENDSTOP Z *****");
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1 && Z_HOME_DIR == -1
if (!READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING){
SERIAL_ECHO("MIN ENDSTOP Z: ");
SERIAL_ECHOLN(MSG_ENDSTOP_OPEN);
ECHO_M("MIN ENDSTOP Z: ");
ECHO_EV(MSG_ENDSTOP_OPEN);
}
else
{
SERIAL_ECHOLN("Z ENDSTOP ERROR");
SERIAL_ECHO(MSG_FWTEST_INVERT);
SERIAL_ECHOLN("#define Z_MIN_ENDSTOP_INVERTING");
ECHO_EM("Z ENDSTOP ERROR");
ECHO_V(MSG_FWTEST_INVERT);
ECHO_EM("#define Z_MIN_ENDSTOP_INVERTING");
return;
}
SERIAL_ECHO(MSG_FWTEST_PRESS);
SERIAL_ECHOLN("Z");
SERIAL_ECHOLN(MSG_FWTEST_YES);
ECHO_V(MSG_FWTEST_PRESS);
ECHO_EM("Z");
ECHO_EV(MSG_FWTEST_YES);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && !(READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING)){
serial_answer = MYSERIAL.read();
}
if (READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING){
SERIAL_ECHO("MIN ENDSTOP Z: ");
SERIAL_ECHOLN(MSG_ENDSTOP_HIT);
ECHO_M("MIN ENDSTOP Z: ");
ECHO_EV(MSG_ENDSTOP_HIT);
}
else
{
SERIAL_ECHO("Z ");
SERIAL_ECHOLN(MSG_FWTEST_ENDSTOP_ERR);
ECHO_M("Z ");
ECHO_EV(MSG_FWTEST_ENDSTOP_ERR);
return;
}
#elif defined(Z_MAX_PIN) && Z_MAX_PIN > -1 && Z_HOME_DIR == 1
if (!READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING){
SERIAL_ECHO("MAX ENDSTOP Z: ");
SERIAL_ECHOLN(MSG_ENDSTOP_OPEN);
ECHO_M("MAX ENDSTOP Z: ");
ECHO_EV(MSG_ENDSTOP_OPEN);
}
else
{
SERIAL_ECHOLN("Z ENDSTOP ERROR");
SERIAL_ECHO(MSG_FWTEST_INVERT);
SERIAL_ECHOLN("#define Z_MAX_ENDSTOP_INVERTING");
ECHO_EM("Z ENDSTOP ERROR");
ECHO_V(MSG_FWTEST_INVERT);
ECHO_EM("#define Z_MAX_ENDSTOP_INVERTING");
return;
}
SERIAL_ECHO(MSG_FWTEST_PRESS);
SERIAL_ECHOLN("Z");
SERIAL_ECHOLN(MSG_FWTEST_YES);
ECHO_V(MSG_FWTEST_PRESS);
ECHO_EM("Z");
ECHO_EV(MSG_FWTEST_YES);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && !(READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING)){
serial_answer = MYSERIAL.read();
}
if (READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING){
SERIAL_ECHO("MAX ENDSTOP Z: ");
SERIAL_ECHOLN(MSG_ENDSTOP_HIT);
ECHO_M("MAX ENDSTOP Z: ");
ECHO_EV(MSG_ENDSTOP_HIT);
}
else
{
SERIAL_ECHO("Z ");
SERIAL_ECHOLN(MSG_FWTEST_ENDSTOP_ERR);
ECHO_M("Z ");
ECHO_EV(MSG_FWTEST_ENDSTOP_ERR);
return;
}
#elif Z_HOME_DIR == -1
SERIAL_ECHOLN("ERROR!!! Z_MIN_PIN not defined");
ECHO_EM("ERROR!!! Z_MIN_PIN not defined");
return;
#elif Z_HOME_DIR == 1
SERIAL_ECHOLN("ERROR!!! Z_MAX_PIN not defined");
ECHO_EM("ERROR!!! Z_MAX_PIN not defined");
return;
#endif
SERIAL_ECHOLN("ENDSTOP OK");
SERIAL_ECHOLN(" ");
ECHO_EM("ENDSTOP OK");
ECHO_EM(" ");
}
#if HAS_POWER_SWITCH
......@@ -245,76 +244,76 @@ void FirmwareTest()
for(int8_t i=0; i < NUM_AXIS; i++) current_position[i] = 0;
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
SERIAL_ECHOLN("***** TEST MOTOR *****");
SERIAL_ECHOLN(MSG_FWTEST_ATTENTION);
SERIAL_ECHOLN(MSG_FWTEST_YES);
ECHO_EM("***** TEST MOTOR *****");
ECHO_EV(MSG_FWTEST_ATTENTION);
ECHO_EV(MSG_FWTEST_YES);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y'){
serial_answer = MYSERIAL.read();
}
SERIAL_ECHOLN(MSG_FWTEST_04);
SERIAL_ECHOLN(" ");
SERIAL_ECHOLN("***** MOTOR X *****");
ECHO_EV(MSG_FWTEST_04);
ECHO_EM(" ");
ECHO_EM("***** MOTOR X *****");
destination[X_AXIS] = 10;
prepare_move();
st_synchronize();
SERIAL_ECHOLN(MSG_FWTEST_XAXIS);
SERIAL_ECHOLN(MSG_FWTEST_YES_NO);
ECHO_EV(MSG_FWTEST_XAXIS);
ECHO_EV(MSG_FWTEST_YES_NO);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && serial_answer!='n' && serial_answer!='N'){
serial_answer = MYSERIAL.read();
}
if(serial_answer=='y' || serial_answer=='Y'){
SERIAL_ECHOLN("MOTOR X OK");
ECHO_EM("MOTOR X OK");
}
else
{
SERIAL_ECHO(MSG_FWTEST_INVERT);
SERIAL_ECHOLN("#define INVERT_X_DIR");
ECHO_V(MSG_FWTEST_INVERT);
ECHO_EM("#define INVERT_X_DIR");
return;
}
SERIAL_ECHOLN(" ");
SERIAL_ECHOLN("***** MOTOR Y *****");
ECHO_EM(" ");
ECHO_EM("***** MOTOR Y *****");
destination[Y_AXIS] = 10;
prepare_move();
st_synchronize();
SERIAL_ECHOLN(MSG_FWTEST_YAXIS);
SERIAL_ECHOLN(MSG_FWTEST_YES_NO);
ECHO_EV(MSG_FWTEST_YAXIS);
ECHO_EV(MSG_FWTEST_YES_NO);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && serial_answer!='n' && serial_answer!='N'){
serial_answer = MYSERIAL.read();
}
if(serial_answer=='y' || serial_answer=='Y'){
SERIAL_ECHOLN("MOTOR Y OK");
ECHO_EM("MOTOR Y OK");
}
else
{
SERIAL_ECHO(MSG_FWTEST_INVERT);
SERIAL_ECHOLN("#define INVERT_Y_DIR");
ECHO_V(MSG_FWTEST_INVERT);
ECHO_EM("#define INVERT_Y_DIR");
return;
}
SERIAL_ECHOLN(" ");
SERIAL_ECHOLN("***** MOTOR Z *****");
ECHO_EM(" ");
ECHO_EM("***** MOTOR Z *****");
destination[Z_AXIS] = 10;
prepare_move();
st_synchronize();
SERIAL_ECHOLN(MSG_FWTEST_ZAXIS);
SERIAL_ECHOLN(MSG_FWTEST_YES_NO);
ECHO_EV(MSG_FWTEST_ZAXIS);
ECHO_EV(MSG_FWTEST_YES_NO);
serial_answer = ' ';
while(serial_answer!='y' && serial_answer!='Y' && serial_answer!='n' && serial_answer!='N'){
serial_answer = MYSERIAL.read();
}
if(serial_answer=='y' || serial_answer=='Y'){
SERIAL_ECHOLN("MOTOR Z OK");
ECHO_EM("MOTOR Z OK");
}
else
{
SERIAL_ECHO(MSG_FWTEST_INVERT);
SERIAL_ECHOLN("#define INVERT_Z_DIR");
ECHO_V(MSG_FWTEST_INVERT);
ECHO_EM("#define INVERT_Z_DIR");
return;
}
SERIAL_ECHOLN("MOTOR OK");
SERIAL_ECHOLN(" ");
SERIAL_ECHO(MSG_FWTEST_END);
ECHO_EM("MOTOR OK");
ECHO_EM(" ");
ECHO_V(MSG_FWTEST_END);
}
......@@ -81,7 +81,7 @@
// Serial Console Messages (do not translate those!)
#define MSG_Enqueueing "enqueueing \""
#define MSG_ENQUEUEING "enqueueing \""
#define MSG_POWERUP "PowerUp"
#define MSG_EXTERNAL_RESET " External Reset"
#define MSG_BROWNOUT_RESET " Brown out Reset"
......@@ -116,9 +116,10 @@
#define MSG_COUNT_X " Count X: "
#define MSG_ERR_KILLED "Printer halted. kill() called!"
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
#define MSG_RESEND "Resend: "
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
#define MSG_ACTIVE_DRIVER "Active Driver: "
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
#define MSG_ACTIVE_COLOR "Active Color: "
#define MSG_INVALID_EXTRUDER "Invalid extruder"
#define MSG_INVALID_SOLENOID "Invalid solenoid"
#define MSG_X_MIN "x_min: "
......@@ -152,6 +153,10 @@
#define MSG_SD_NOT_PRINTING "Not SD printing"
#define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
#define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
#define MSG_SD_FILE_DELETED "File deleted:"
#define MSG_SD_SLASH "/"
#define MSG_SD_FILE_DELETION_ERR "Deletion failed, File: "
#define MSG_SD_MAX_DEPTH "trying to call sub-gcode files with too many levels. MAX level is:"
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
#define MSG_ENDSTOPS_HIT "endstops hit: "
......@@ -161,6 +166,17 @@
#define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
#define MSG_MICROSTEP_MS1_MS2 "MS1,MS2 Pins"
#define MSG_MICROSTEP_X "X:"
#define MSG_MICROSTEP_Y "Y:"
#define MSG_MICROSTEP_Z "Z:"
#define MSG_MICROSTEP_E0 "E0:"
#define MSG_MICROSTEP_E1 "E1:"
#define MSG_ENDSTOP_X " X:"
#define MSG_ENDSTOP_Y " Y:"
#define MSG_ENDSTOP_Z " Z:"
#define MSG_ENDSTOP_E " E:"
#define MSG_ENDSTOP_ZP " ZP:"
#define MSG_ERR_EEPROM_WRITE "Error writing to EEPROM!"
......@@ -181,26 +197,43 @@
#define MSG_KP " Kp: "
#define MSG_KI " Ki: "
#define MSG_KD " Kd: "
#define MSG_OK_B "ok B:"
#define MSG_OK_T "ok T:"
#define MSG_B " B:"
#define MSG_T " T:"
#define MSG_AT " @:"
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from above into Configuration.h or send command M500 for save in EEPROM the new value!"
#define MSG_PID_DEBUG " PID_DEBUG "
#define MSG_PID_DEBUG_INPUT ": Input "
#define MSG_PID_DEBUG_OUTPUT " Output "
#define MSG_PID_DEBUG_PTERM " pTerm "
#define MSG_PID_DEBUG_ITERM " iTerm "
#define MSG_PID_DEBUG_DTERM " dTerm "
#define MSG_HEATING_FAILED "Heating failed"
#define MSG_THERMAL_RUNAWAY_STOP "Thermal Runaway, system stopped! Heater_ID: "
#define MSG_THERMAL_RUNAWAY_BED "bed"
#define MSG_TEMP_READ_ERROR "Temp measurement error!"
#define MSG_TEMP_BED "bed"
#define MSG_EXTRUDER_SWITCHED_OFF "Extruder switched off. Temperature difference between temp sensors is too high !"
#define MSG_INVALID_EXTRUDER_NUM " - Invalid extruder number !"
#define MSG_THERMAL_RUNAWAY_STOP "Thermal Runaway, system stopped! Heater_ID: "
#define MSG_SWITCHED_OFF_MAX " switched off. MAXTEMP triggered !!"
#define MSG_MINTEMP_EXTRUDER_OFF ": Extruder switched off. MINTEMP triggered !"
#define MSG_MAXTEMP_EXTRUDER_OFF ": Extruder" MSG_SWITCHED_OFF_MAX
#define MSG_MAXTEMP_BED_OFF "Heated bed" MSG_SWITCHED_OFF_MAX
#define MSG_ENDSTOP_XS "X"
#define MSG_ENDSTOP_YS "Y"
#define MSG_ENDSTOP_ZS "Z"
#define MSG_ENDSTOP_ZPS "ZP"
#define MSG_ENDSTOP_ES "E"
//watchdog.cpp
#define MSG_WATCHDOG_RESET "Something is wrong, please turn off the printer."
//other
#define MSG_COMPILED "Compiled: "
#define MSG_ERR_HOMING_DIV "The Homing Bump Feedrate Divisor cannot be less than 1"
#define MSG_BED_LEVELLING_BED "Bed"
#define MSG_BED_LEVELLING_X " X: "
#define MSG_BED_LEVELLING_Y " Y: "
#define MSG_BED_LEVELLING_Z " Z: "
#define MSG_DRYRUN_ENABLED "DEBUG DRYRUN ENABLED"
// LCD Menu Messages
#if !(defined( DISPLAY_CHARSET_HD44780_JAPAN ) || defined( DISPLAY_CHARSET_HD44780_WESTERN ) || defined( DISPLAY_CHARSET_HD44780_CYRILLIC ))
......
......@@ -151,6 +151,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_E_BOWDEN_LENGTH "Extrude " STRINGIFY(BOWDEN_LENGTH) "mm"
......
......@@ -152,6 +152,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -150,6 +150,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -160,6 +160,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_E_BOWDEN_LENGTH "Extrude " STRINGIFY(BOWDEN_LENGTH) "mm"
......
......@@ -150,6 +150,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -150,6 +150,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -150,6 +150,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Kalibroi Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -151,6 +151,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -160,6 +160,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibra Centro"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configurazione"
#define MSG_E_BOWDEN_LENGTH "Extrude " STRINGIFY(BOWDEN_LENGTH) "mm"
......
......@@ -150,6 +150,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -150,6 +150,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -160,6 +160,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_E_BOWDEN_LENGTH "Extrude " STRINGIFY(BOWDEN_LENGTH) "mm"
......
......@@ -150,6 +150,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -150,6 +150,11 @@
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA
#ifdef SCARA
#define MSG_XSCALE "X Scale"
#define MSG_YSCALE "Y Scale"
#endif
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration"
#define MSG_BAUDRATE "Baudrate"
......
......@@ -518,8 +518,8 @@ float junction_deviation = 0.1;
if (degHotend(extruder) < extrude_min_temp && !debugDryrun()) {
position[E_AXIS] = target[E_AXIS]; //behave as if the move really took place, but ignore E part
de = 0; // no difference
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP);
ECHO_S(OK);
ECHO_EM(MSG_ERR_COLD_EXTRUDE_STOP);
}
}
......@@ -530,8 +530,8 @@ float junction_deviation = 0.1;
#endif
position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part
de = 0; // no difference
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP);
ECHO_S(OK);
ECHO_EM(MSG_ERR_LONG_EXTRUDE_STOP);
#ifdef EASY_LOAD
}
allow_lengthy_extrude_once = false;
......@@ -887,7 +887,7 @@ float junction_deviation = 0.1;
block->acceleration = acc_st / steps_per_mm;
#ifdef __SAM3X8E__
block->acceleration_rate = (long)(acc_st * ( 16777216.0 / HAL_TIMER_RATE));
block->acceleration_rate = (long)(acc_st * ( 4294967296.0 / (float)HAL_TIMER_RATE));
#else
block->acceleration_rate = (long)(acc_st * 16777216.0 / (F_CPU / 8.0));
#endif
......@@ -993,12 +993,12 @@ float junction_deviation = 0.1;
block->advance_rate = acc_dist ? advance / (float)acc_dist : 0;
}
/*
SERIAL_ECHO_START;
SERIAL_ECHOPGM("advance :");
SERIAL_ECHO(block->advance/256.0);
SERIAL_ECHOPGM("advance rate :");
SERIAL_ECHOLN(block->advance_rate/256.0);
*/
ECHO_S(OK);
ECHO_M("advance :");
ECHO_V(block->advance/256.0);
ECHO_M("advance rate :");
ECHO_EV(block->advance_rate/256.0);
*/
#endif // ADVANCE
calculate_trapezoid_for_block(block, block->entry_speed / block->nominal_speed, safe_speed / block->nominal_speed);
......
......@@ -276,39 +276,37 @@ void endstops_hit_on_purpose() {
void checkHitEndstops() {
if (endstop_x_hit || endstop_y_hit || endstop_z_hit || endstop_z_probe_hit || endstop_e_hit) {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_ENDSTOPS_HIT);
ECHO_SM(OK, MSG_ENDSTOPS_HIT);
if(endstop_x_hit) {
SERIAL_ECHOPAIR(" X:", (float)endstops_trigsteps[X_AXIS] / axis_steps_per_unit[X_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "X");
ECHO_MV(MSG_ENDSTOP_X, (float)endstops_trigsteps[X_AXIS] / axis_steps_per_unit[X_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT MSG_ENDSTOP_XS);
}
if(endstop_y_hit) {
SERIAL_ECHOPAIR(" Y:", (float)endstops_trigsteps[Y_AXIS] / axis_steps_per_unit[Y_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "Y");
ECHO_MV(MSG_ENDSTOP_Y, (float)endstops_trigsteps[Y_AXIS] / axis_steps_per_unit[Y_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT MSG_ENDSTOP_YS);
}
if(endstop_z_hit) {
SERIAL_ECHOPAIR(" Z:", (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "Z");
ECHO_MV(MSG_ENDSTOP_Z, (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT MSG_ENDSTOP_ZS);
}
#ifdef Z_PROBE_ENDSTOP
if (endstop_z_probe_hit) {
SERIAL_ECHOPAIR(" Z_PROBE:", (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "ZP");
ECHO_MV(" Z_PROBE:", (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT MSG_ENDSTOP_ZPS);
}
#endif
if(endstop_e_hit) {
SERIAL_ECHOPAIR(" E:", (float)endstops_trigsteps[E_AXIS] / axis_steps_per_unit[E_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "E");
ECHO_MV(MSG_ENDSTOP_E, (float)endstops_trigsteps[E_AXIS] / axis_steps_per_unit[E_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT MSG_ENDSTOP_ES);
}
SERIAL_ECHOLN("");
ECHO_E;
endstops_hit_on_purpose();
#if defined(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) && defined(SDSUPPORT)
if (abort_on_endstop_hit) {
card.sdprinting = false;
card.closefile();
card.closeFile();
quickStop();
setTargetHotend0(0);
setTargetHotend1(0);
......@@ -327,34 +325,33 @@ void endstops_hit_on_purpose() {
void checkHitEndstops() {
if (endstop_x_hit || endstop_y_hit || endstop_z_hit || endstop_z_probe_hit) {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_ENDSTOPS_HIT);
ECHO_SM(OK, MSG_ENDSTOPS_HIT);
if (endstop_x_hit) {
SERIAL_ECHOPAIR(" X:", (float)endstops_trigsteps[X_AXIS] / axis_steps_per_unit[X_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "X");
ECHO_MV(MSG_ENDSTOP_X, (float)endstops_trigsteps[X_AXIS] / axis_steps_per_unit[X_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT MSG_ENDSTOP_XS);
}
if (endstop_y_hit) {
SERIAL_ECHOPAIR(" Y:", (float)endstops_trigsteps[Y_AXIS] / axis_steps_per_unit[Y_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "Y");
ECHO_MV(MSG_ENDSTOP_Y, (float)endstops_trigsteps[Y_AXIS] / axis_steps_per_unit[Y_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT MSG_ENDSTOP_YS);
}
if (endstop_z_hit) {
SERIAL_ECHOPAIR(" Z:", (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "Z");
ECHO_MV(MSG_ENDSTOP_Z, (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT MSG_ENDSTOP_ZS);
}
#ifdef Z_PROBE_ENDSTOP
if (endstop_z_probe_hit) {
SERIAL_ECHOPAIR(" Z_PROBE:", (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT "ZP");
ECHO_MV(MSG_ENDSTOP_ZPS, (float)endstops_trigsteps[Z_AXIS] / axis_steps_per_unit[Z_AXIS]);
LCD_MESSAGEPGM(MSG_ENDSTOPS_HIT MSG_ENDSTOP_ZPS);
}
#endif
SERIAL_EOL;
ECHO_E;
endstops_hit_on_purpose();
#if defined(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) && defined(SDSUPPORT)
if (abort_on_endstop_hit) {
card.sdprinting = false;
card.closefile();
card.closeFile();
quickStop();
setTargetHotend0(0);
setTargetHotend1(0);
......@@ -443,16 +440,6 @@ FORCE_INLINE void trapezoid_generator_reset() {
acc_step_rate = current_block->initial_rate;
acceleration_time = calc_timer(acc_step_rate);
OCR1A = acceleration_time;
// SERIAL_ECHO_START;
// SERIAL_ECHOPGM("advance :");
// SERIAL_ECHO(current_block->advance/256.0);
// SERIAL_ECHOPGM("advance rate :");
// SERIAL_ECHO(current_block->advance_rate/256.0);
// SERIAL_ECHOPGM("initial advance :");
// SERIAL_ECHO(current_block->initial_advance/256.0);
// SERIAL_ECHOPGM("final advance :");
// SERIAL_ECHOLN(current_block->final_advance/256.0);
}
// "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.
......@@ -633,8 +620,6 @@ ISR(TIMER1_COMPA_vect) {
{
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
endstop_z_probe_hit = true;
// if (z_probe_endstop && old_z_probe_endstop) SERIAL_ECHOLN("z_probe_endstop = true");
}
old_z_probe_endstop = z_probe_endstop;
#endif
......@@ -668,9 +653,6 @@ ISR(TIMER1_COMPA_vect) {
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
endstop_z_hit = true;
// if (z_max_both) SERIAL_ECHOLN("z_max_endstop = true");
// if (z2_max_both) SERIAL_ECHOLN("z2_max_endstop = true");
if (!performing_homing || (performing_homing && z_max_both && z2_max_both)) //if not performing home or if both endstops were trigged during homing...
step_events_completed = current_block->step_event_count;
}
......@@ -1419,23 +1401,23 @@ void microstep_mode(uint8_t driver, uint8_t stepping_mode) {
}
void microstep_readings() {
SERIAL_PROTOCOLPGM("MS1,MS2 Pins\n");
SERIAL_PROTOCOLPGM("X: ");
SERIAL_PROTOCOL(digitalRead(X_MS1_PIN));
SERIAL_PROTOCOLLN(digitalRead(X_MS2_PIN));
SERIAL_PROTOCOLPGM("Y: ");
SERIAL_PROTOCOL(digitalRead(Y_MS1_PIN));
SERIAL_PROTOCOLLN(digitalRead(Y_MS2_PIN));
SERIAL_PROTOCOLPGM("Z: ");
SERIAL_PROTOCOL(digitalRead(Z_MS1_PIN));
SERIAL_PROTOCOLLN(digitalRead(Z_MS2_PIN));
SERIAL_PROTOCOLPGM("E0: ");
SERIAL_PROTOCOL(digitalRead(E0_MS1_PIN));
SERIAL_PROTOCOLLN(digitalRead(E0_MS2_PIN));
ECHO_SM(OK, MSG_MICROSTEP_MS1_MS2);
ECHO_M(MSG_MICROSTEP_X);
ECHO_V(digitalRead(X_MS1_PIN));
ECHO_EV(digitalRead(X_MS2_PIN));
ECHO_SM(OK, MSG_MICROSTEP_Y);
ECHO_V(digitalRead(Y_MS1_PIN));
ECHO_EV(digitalRead(Y_MS2_PIN));
ECHO_SM(OK, MSG_MICROSTEP_Z);
ECHO_V(digitalRead(Z_MS1_PIN));
ECHO_EV(digitalRead(Z_MS2_PIN));
ECHO_SM(OK, MSG_MICROSTEP_E0);
ECHO_V(digitalRead(E0_MS1_PIN));
ECHO_EV(digitalRead(E0_MS2_PIN));
#if HAS_MICROSTEPS_E1
SERIAL_PROTOCOLPGM("E1: ");
SERIAL_PROTOCOL(digitalRead(E1_MS1_PIN));
SERIAL_PROTOCOLLN(digitalRead(E1_MS2_PIN));
ECHO_SM(OK, MSG_MICROSTEP_E1);
ECHO_V(digitalRead(E1_MS1_PIN));
ECHO_EV(digitalRead(E1_MS2_PIN));
#endif
}
......
......@@ -204,11 +204,11 @@ void PID_autotune(float temp, int hotend, int ncycles)
|| hotend < 0
#endif
) {
SERIAL_ECHOLN(MSG_PID_BAD_EXTRUDER_NUM);
ECHO_LM(ER, MSG_PID_BAD_EXTRUDER_NUM);
return;
}
SERIAL_ECHOLN(MSG_PID_AUTOTUNE_START);
ECHO_LM(OK, MSG_PID_AUTOTUNE_START);
disable_all_heaters(); // switch off all heaters.
......@@ -260,39 +260,44 @@ void PID_autotune(float temp, int hotend, int ncycles)
bias = constrain(bias, 20, max_pow - 20);
d = (bias > max_pow / 2) ? max_pow - 1 - bias : bias;
SERIAL_PROTOCOLPGM(MSG_BIAS); SERIAL_PROTOCOL(bias);
SERIAL_PROTOCOLPGM(MSG_D); SERIAL_PROTOCOL(d);
SERIAL_PROTOCOLPGM(MSG_T_MIN); SERIAL_PROTOCOL(min);
SERIAL_PROTOCOLPGM(MSG_T_MAX); SERIAL_PROTOCOLLN(max);
ECHO_SMV(OK, MSG_BIAS, bias);
ECHO_MV(MSG_D, d);
ECHO_MV(MSG_T_MIN, min);
ECHO_MV(MSG_T_MAX, max);
if (cycles > 2) {
Ku = (4.0 * d) / (3.14159265 * (max - min) / 2.0);
Tu = ((float)(t_low + t_high) / 1000.0);
SERIAL_PROTOCOLPGM(MSG_KU); SERIAL_PROTOCOL(Ku);
SERIAL_PROTOCOLPGM(MSG_TU); SERIAL_PROTOCOLLN(Tu);
ECHO_MV(MSG_KU, Ku);
ECHO_MV(MSG_TU, Tu);
Kp_temp = 0.6 * Ku;
Ki_temp = 2 * Kp_temp / Tu;
Kd_temp = Kp_temp * Tu / 8;
SERIAL_PROTOCOLLNPGM(MSG_CLASSIC_PID);
SERIAL_PROTOCOLPGM(MSG_KP); SERIAL_PROTOCOLLN(Kp_temp);
SERIAL_PROTOCOLPGM(MSG_KI); SERIAL_PROTOCOLLN(Ki_temp);
SERIAL_PROTOCOLPGM(MSG_KD); SERIAL_PROTOCOLLN(Kd_temp);
ECHO_M(MSG_CLASSIC_PID);
ECHO_MV(MSG_KP, Kp_temp);
ECHO_MV(MSG_KI, Ki_temp);
ECHO_EMV(MSG_KD, Kd_temp);
/*
Kp = 0.33*Ku;
Ki = Kp_temp / Tu;
Kd = Kp_temp * Tu / 3;
SERIAL_PROTOCOLLNPGM(" Some overshoot ");
SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(Kp_temp);
SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(Ki_temp);
SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(Kd_temp);
ECHO_SMV(DB," Some overshoot ");
ECHO_MV(" Kp: ", Kp_temp);
ECHO_MV(" Ki: ", Ki_temp);
ECHO_MV(" Kd: ", Kd_temp);
Kp = 0.2 * Ku;
Ki = 2 * Kp_temp / Tu;
Kd = Kp_temp * Tu / 3;
SERIAL_PROTOCOLLNPGM(" No overshoot ");
SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(Kp_temp);
SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(Ki_temp);
SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(Kd_temp);
ECHO_M(" No overshoot ");
ECHO_MV(" Kp: ", Kp_temp);
ECHO_MV(" Ki: ", Ki_temp);
ECHO_EMV(" Kd: ", Kd_temp);
*/
}
else {
ECHO_E;
}
}
if (hotend < 0)
soft_pwm_bed = (bias + d) >> 1;
......@@ -304,7 +309,7 @@ void PID_autotune(float temp, int hotend, int ncycles)
}
}
if (input > temp + 20) {
SERIAL_PROTOCOLLNPGM(MSG_PID_TEMP_TOO_HIGH);
ECHO_LM(ER, MSG_PID_TEMP_TOO_HIGH);
return;
}
// Every 2 seconds...
......@@ -312,26 +317,24 @@ void PID_autotune(float temp, int hotend, int ncycles)
int p;
if (hotend < 0) {
p = soft_pwm_bed;
SERIAL_PROTOCOLPGM(MSG_OK_B);
ECHO_SMV(OK, MSG_B, input);
ECHO_EMV(MSG_AT, p);
}
else {
p = soft_pwm[hotend];
SERIAL_PROTOCOLPGM(MSG_OK_T);
ECHO_SMV(OK, MSG_T, input);
ECHO_EMV(MSG_AT, p);
}
SERIAL_PROTOCOL(input);
SERIAL_PROTOCOLPGM(MSG_AT);
SERIAL_PROTOCOLLN(p);
temp_ms = ms;
} // every 2 seconds
// Over 2 minutes?
if (((ms - t1) + (ms - t2)) > (10L*60L*1000L*2L)) {
SERIAL_PROTOCOLLNPGM(MSG_PID_TIMEOUT);
ECHO_LM(ER, MSG_PID_TIMEOUT);
return;
}
if (cycles > ncycles) {
SERIAL_PROTOCOLLNPGM(MSG_PID_AUTOTUNE_FINISHED);
ECHO_LM(OK, MSG_PID_AUTOTUNE_FINISHED);
#ifdef PIDTEMP
PID_PARAM(Kp, hotend) = Kp_temp;
PID_PARAM(Ki, hotend) = scalePID_i(Ki_temp);
......@@ -440,10 +443,11 @@ void checkExtruderAutoFans()
//
inline void _temp_error(int e, const char *msg1, const char *msg2) {
if (IsRunning()) {
SERIAL_ERROR_START;
if (e >= 0) SERIAL_ERRORLN((int)e);
serialprintPGM(msg1);
MYSERIAL.write('\n');
ECHO_S(ER);
if (e >= 0) ECHO_EV(e);
else ECHO_EV(MSG_TEMP_BED);
PS_PGM(msg1);
ECHO_E;
#ifdef ULTRA_LCD
lcd_setalertstatuspgm(msg2);
#endif
......@@ -508,19 +512,12 @@ float get_pid_output(int e) {
#endif //PID_OPENLOOP
#ifdef PID_DEBUG
SERIAL_ECHO_START;
SERIAL_ECHO(MSG_PID_DEBUG);
SERIAL_ECHO(e);
SERIAL_ECHO(MSG_PID_DEBUG_INPUT);
SERIAL_ECHO(current_temperature[e]);
SERIAL_ECHO(MSG_PID_DEBUG_OUTPUT);
SERIAL_ECHO(pid_output);
SERIAL_ECHO(MSG_PID_DEBUG_PTERM);
SERIAL_ECHO(pTerm[e]);
SERIAL_ECHO(MSG_PID_DEBUG_ITERM);
SERIAL_ECHO(iTerm[e]);
SERIAL_ECHO(MSG_PID_DEBUG_DTERM);
SERIAL_ECHOLN(dTerm[e]);
ECHO_SMV(DB, " PID_DEBUG ", e);
ECHO_MV(": Input ", current_temperature[e]);
ECHO_MV(" Output ", pid_output);
ECHO_MV(" pTerm ", pTerm[e]);
ECHO_MV(" iTerm ", iTerm[e]);
ECHO_EMV(" dTerm ", dTerm[e]);
#endif //PID_DEBUG
#else /* PID off */
......@@ -557,18 +554,12 @@ float get_pid_output(int e) {
#endif // PID_OPENLOOP
#ifdef PID_BED_DEBUG
SERIAL_ECHO_START;
SERIAL_ECHO(" PID_BED_DEBUG ");
SERIAL_ECHO(": Input ");
SERIAL_ECHO(current_temperature_bed);
SERIAL_ECHO(" Output ");
SERIAL_ECHO(pid_output);
SERIAL_ECHO(" pTerm ");
SERIAL_ECHO(pTerm_bed);
SERIAL_ECHO(" iTerm ");
SERIAL_ECHO(iTerm_bed);
SERIAL_ECHO(" dTerm ");
SERIAL_ECHOLN(dTerm_bed);
ECHO_SM(DB ," PID_BED_DEBUG ");
ECHO_MV(": Input ", current_temperature_bed);
ECHO_MV(" Output ", pid_output);
ECHO_MV(" pTerm ", pTerm_bed);
ECHO_MV(" iTerm ", iTerm_bed);
ECHO_EMV(" dTerm ", dTerm_bed);
#endif //PID_BED_DEBUG
return pid_output;
......@@ -615,9 +606,8 @@ void manage_heater() {
if (watchmillis[e] && ms > watchmillis[e] + WATCH_TEMP_PERIOD) {
if (degHotend(e) < watch_start_temp[e] + WATCH_TEMP_INCREASE) {
setTargetHotend(0, e);
ECHO_LM(ER, MSG_HEATING_FAILED);
LCD_MESSAGEPGM(MSG_HEATING_FAILED_LCD);
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_HEATING_FAILED);
}
else {
watchmillis[e] = 0;
......@@ -707,9 +697,7 @@ static float analog2temp(int raw, uint8_t e) {
if (e >= EXTRUDERS)
#endif
{
SERIAL_ERROR_START;
SERIAL_ERROR((int)e);
SERIAL_ERRORLNPGM(MSG_INVALID_EXTRUDER_NUM);
ECHO_LVM(ER, e, MSG_INVALID_EXTRUDER_NUM);
kill();
return 0.0;
}
......@@ -781,6 +769,9 @@ static float analog2tempBed(int raw) {
/* Called to get the raw values into the the actual temperatures. The raw values are created in interrupt context,
and this function is called from normal context as it is too slow to run in interrupts and will block the stepper routine otherwise */
static void updateTemperaturesFromRawValues() {
static millis_t last_update = millis();
millis_t temp_last_update = millis();
millis_t from_last_update = temp_last_update - last_update;
#ifdef HEATER_0_USES_MAX6675
current_temperature_raw[0] = read_max6675();
#endif
......@@ -796,17 +787,22 @@ static void updateTemperaturesFromRawValues() {
#endif
#if HAS_POWER_CONSUMPTION_SENSOR
static float watt_overflow = 0.0;
static millis_t last_power_update = millis();
millis_t temp_last_power_update = millis();
power_consumption_meas = analog2power();
//MYSERIAL.println(analog2current(),3);
watt_overflow += (power_consumption_meas * (temp_last_power_update - last_power_update)) / 3600000.0;
watt_overflow += (power_consumption_meas * from_last_update) / 3600000.0;
if (watt_overflow >= 1.0) {
power_consumption_hour++;
watt_overflow--;
}
last_power_update = temp_last_power_update;
#endif
static unsigned int second_overflow = 0;
second_overflow += from_last_update;
if(second_overflow >= 1000) {
printer_usage_seconds++;
second_overflow -= 1000;
}
last_update = temp_last_update;
//Reset the watchdog after we know we have a temperature measurement.
watchdog_reset();
......@@ -1050,18 +1046,12 @@ void setWatch() {
static float tr_target_temperature[EXTRUDERS+1] = { 0.0 };
/*
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Thermal Thermal Runaway Running. Heater ID: ");
if (heater_id < 0) SERIAL_ECHOPGM("bed"); else SERIAL_ECHOPGM(heater_id);
SERIAL_ECHOPGM(" ; State:");
SERIAL_ECHOPGM(*state);
SERIAL_ECHOPGM(" ; Timer:");
SERIAL_ECHOPGM(*timer);
SERIAL_ECHOPGM(" ; Temperature:");
SERIAL_ECHOPGM(temperature);
SERIAL_ECHOPGM(" ; Target Temp:");
SERIAL_ECHOPGM(target_temperature);
SERIAL_EOL;
ECHO_SM(DB, "Thermal Thermal Runaway Running. Heater ID: ");
if (heater_id < 0) ECHO_M("bed"); else ECHO_V(heater_id);
ECHO_MV(" ; State:", *state);
ECHO_MV(" ; Timer:", *timer);
ECHO_MV(" ; Temperature:", temperature);
ECHO_EMV(" ; Target Temp:", target_temperature);
*/
int heater_index = heater_id >= 0 ? heater_id : EXTRUDERS;
......@@ -1096,9 +1086,8 @@ void setWatch() {
*state = TRRunaway;
break;
case TRRunaway:
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_THERMAL_RUNAWAY_STOP);
if (heater_id < 0) SERIAL_ERRORLNPGM("bed"); else SERIAL_ERRORLN(heater_id);
ECHO_S(ER, MSG_THERMAL_RUNAWAY_STOP);
if (heater_id < 0) ECHO_EM(MSG_THERMAL_RUNAWAY_BED); else ECHO_EV(heater_id);
LCD_ALERTMESSAGEPGM(MSG_THERMAL_RUNAWAY);
disable_all_heaters();
disable_all_steppers();
......@@ -1578,10 +1567,9 @@ ISR(TIMER0_COMPB_vect) {
temp_state = PrepareTemp_0;
break;
// default:
// SERIAL_ERROR_START;
// SERIAL_ERRORLNPGM("Temp measurement error!");
// break;
default:
ECHO_LM(ER, MSG_TEMP_READ_ERROR);
break;
} // switch(temp_state)
if (temp_count >= OVERSAMPLENR) { // 14 * 16 * 1/(16000000/64/256)
......
......@@ -311,12 +311,12 @@ static void lcd_status_screen() {
#if HAS_LCD_FILAMENT_SENSOR || HAS_LCD_POWER_SENSOR
#if HAS_LCD_FILAMENT_SENSOR && HAS_LCD_POWER_SENSOR
if (millis() > message_millis + 15000)
if (millis() > previous_lcd_status_ms + 15000)
#else
if (millis() > message_millis + 10000)
if (millis() > previous_lcd_status_ms + 10000)
#endif
{
message_millis = millis();
previous_lcd_status_ms = millis();
}
#endif
......@@ -389,7 +389,7 @@ static void lcd_sdcard_resume() { card.startFileprint(); }
static void lcd_sdcard_stop() {
quickStop();
card.sdprinting = false;
card.closefile();
card.closeFile();
autotempShutdown();
cancel_heatup = true;
lcd_setstatus(MSG_PRINT_ABORTED, true);
......@@ -675,7 +675,7 @@ void config_lcd_level_bed()
{
setTargetHotend(0,0);
SERIAL_ECHOLN("Leveling...");
ECHO_EM("Leveling...");
currentMenu = lcd_level_bed;
enqueuecommands_P(PSTR("G28 M"));
pageShowInfo = 0;
......@@ -1104,8 +1104,8 @@ static void lcd_control_motion_menu() {
MENU_ITEM_EDIT(bool, MSG_ENDSTOP_ABORT, &abort_on_endstop_hit);
#endif
#ifdef SCARA
MENU_ITEM_EDIT(float74, MSG_XSCALE, &axis_scaling[X_AXIS],0.5,2);
MENU_ITEM_EDIT(float74, MSG_YSCALE, &axis_scaling[Y_AXIS],0.5,2);
MENU_ITEM_EDIT(float52, MSG_XSCALE, &axis_scaling[X_AXIS],0.5,2);
MENU_ITEM_EDIT(float52, MSG_YSCALE, &axis_scaling[Y_AXIS],0.5,2);
#endif
END_MENU();
}
......@@ -1493,16 +1493,11 @@ void lcd_update() {
else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10;
#ifdef ENCODER_RATE_MULTIPLIER_DEBUG
SERIAL_ECHO_START;
SERIAL_ECHO("Enc Step Rate: ");
SERIAL_ECHO(encoderStepRate);
SERIAL_ECHO(" Multiplier: ");
SERIAL_ECHO(encoderMultiplier);
SERIAL_ECHO(" ENCODER_10X_STEPS_PER_SEC: ");
SERIAL_ECHO(ENCODER_10X_STEPS_PER_SEC);
SERIAL_ECHO(" ENCODER_100X_STEPS_PER_SEC: ");
SERIAL_ECHOLN(ENCODER_100X_STEPS_PER_SEC);
#endif //ENCODER_RATE_MULTIPLIER_DEBUG
ECHO_SMV(DB, "Enc Step Rate: ", encoderStepRate);
ECHO_MV(" Multiplier: ", encoderMultiplier);
ECHO_MV(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC);
ECHO_EMV(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC);
#endif
}
lastEncoderMovementMillis = ms;
......
......@@ -60,14 +60,10 @@ void vector_3::apply_rotation(matrix_3x3 matrix) {
}
void vector_3::debug(const char title[]) {
SERIAL_PROTOCOL(title);
SERIAL_PROTOCOLPGM(" x: ");
SERIAL_PROTOCOL_F(x, 6);
SERIAL_PROTOCOLPGM(" y: ");
SERIAL_PROTOCOL_F(y, 6);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL_F(z, 6);
SERIAL_EOL;
ECHO_SV(DB, title);
ECHO_MV(" x: ", x, 6);
ECHO_MV(" y: ", y, 6);
ECHO_EMV(" z: ", z, 6);
}
void apply_rotation_xyz(matrix_3x3 matrix, float &x, float& y, float& z) {
......@@ -121,16 +117,16 @@ matrix_3x3 matrix_3x3::transpose(matrix_3x3 original) {
}
void matrix_3x3::debug(const char title[]) {
SERIAL_PROTOCOLLN(title);
ECHO_SV(DB, title);
int count = 0;
for(int i=0; i<3; i++) {
for(int j=0; j<3; j++) {
if (matrix[count] >= 0.0) SERIAL_PROTOCOLCHAR('+');
SERIAL_PROTOCOL_F(matrix[count], 6);
SERIAL_PROTOCOLCHAR(' ');
if (matrix[count] >= 0.0) ECHO_C('+');
ECHO_V(matrix[count], 6);
ECHO_C(' ');
count++;
}
SERIAL_EOL;
ECHO_E;
}
}
......
......@@ -43,11 +43,10 @@ void watchdog_reset()
#ifdef WATCHDOG_RESET_MANUAL
ISR(WDT_vect)
{
ECHO_LM(MSG_WATCHDOG_RESET);
//TODO: This message gets overwritten by the kill() call
LCD_ALERTMESSAGEPGM("ERR:Please Reset");//16 characters so it fits on a 16x2 display
lcd_update();
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Something is wrong, please turn off the printer.");
kill(); //kill blocks
while(1); //wait for user or serial reset
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment