Commit 59733b03 authored by MagoKimbra's avatar MagoKimbra

Update

parent 002b9fbd
...@@ -16,8 +16,6 @@ ...@@ -16,8 +16,6 @@
Bed Probe and Delta geometry Autocalibration G30 A Bed Probe and Delta geometry Autocalibration G30 A
* G31 - Dock Z Probe sled (if enabled) * G31 - Dock Z Probe sled (if enabled)
* G32 - Undock Z Probe sled (if enabled) * G32 - Undock Z Probe sled (if enabled)
* G60 - Store in memory the actual position
* G61 - Move X Y Z to position in memory
* G90 - Use Absolute Coordinates * G90 - Use Absolute Coordinates
* G91 - Use Relative Coordinates * G91 - Use Relative Coordinates
* G92 - Set current position to cordinates given * G92 - Set current position to cordinates given
...@@ -91,6 +89,12 @@ ...@@ -91,6 +89,12 @@
* M302 - Allow cold extrudes * M302 - Allow cold extrudes
* M303 - PID relay autotune S[temperature] sets the target temperature. (default target temperature = 150C) * M303 - PID relay autotune S[temperature] sets the target temperature. (default target temperature = 150C)
* M304 - Set bed PID parameters P I and D * M304 - Set bed PID parameters P I and D
* M331 - Save current position coordinates (all axes, for active extruder).
* S<SLOT> - specifies memory slot # (0-based) to save into (default 0).
* M332 - Apply/restore saved coordinates to the active extruder.
* X Y Z E - Value to add at stored coordinates.
* F<speed> - Set Feedrate.
* S<SLOT> - specifies memory slot # (0-based) to restore from (default 0).
* M350 - Set microstepping mode. * M350 - Set microstepping mode.
* M351 - Toggle MS1 MS2 pins directly. * M351 - Toggle MS1 MS2 pins directly.
* M400 - Finish all moves * M400 - Finish all moves
......
...@@ -6,6 +6,16 @@ ...@@ -6,6 +6,16 @@
* Add Acceleration retraction for extruder. * Add Acceleration retraction for extruder.
* Add EJerk for extruder * Add EJerk for extruder
* Remove limit for virtual extruder to 4. Now width MKR4 or NPr2 is possible have infinite extruder... * Remove limit for virtual extruder to 4. Now width MKR4 or NPr2 is possible have infinite extruder...
* Add M92 T* E (Set step per unit for any extruder)
* Add M203 T* E (Set max feedrate for any extruder)
* Add M204 T* R (Set acc retraction for any extruder)
* Add M205 T* E (Set E Jerk for any extruder)
* Add M331 Save current position coordinates (all axes, for active extruder).
S<SLOT> - specifies memory slot # (0-based) to save into (default 0).
* Add M332 Apply/restore saved coordinates to the active extruder.
X Y Z E - Value to add at stored coordinates.
F<speed> - Set Feedrate.
S<SLOT> - specifies memory slot # (0-based) to save into (default 0).
### Version 4.1.2 ### Version 4.1.2
* Serial message function standardized for a better code style * Serial message function standardized for a better code style
......
...@@ -381,6 +381,10 @@ ...@@ -381,6 +381,10 @@
#define MM_PER_ARC_SEGMENT 1 #define MM_PER_ARC_SEGMENT 1
#define N_ARC_CORRECTION 25 #define N_ARC_CORRECTION 25
// Defines the number of memory slots for saving/restoring position (M331/M332)
// The values should not be less than 1
#define NUM_POSITON_SLOTS 2
const unsigned int dropsegments = 5; // everything with less than this number of steps will be ignored as move and joined with the next movement const unsigned int dropsegments = 5; // everything with less than this number of steps will be ignored as move and joined with the next movement
// Control heater 0 and heater 1 in parallel. // Control heater 0 and heater 1 in parallel.
......
...@@ -262,7 +262,6 @@ extern float home_offset[3]; ...@@ -262,7 +262,6 @@ extern float home_offset[3];
extern float min_pos[3]; extern float min_pos[3];
extern float max_pos[3]; extern float max_pos[3];
extern bool axis_known_position[3]; extern bool axis_known_position[3];
extern float lastpos[4];
extern float zprobe_zoffset; extern float zprobe_zoffset;
// Lifetime stats // Lifetime stats
......
...@@ -92,8 +92,6 @@ ...@@ -92,8 +92,6 @@
* G30 - Single Z Probe, probes bed at current XY location. - Bed Probe and Delta geometry Autocalibration * G30 - Single Z Probe, probes bed at current XY location. - Bed Probe and Delta geometry Autocalibration
* G31 - Dock sled (Z_PROBE_SLED only) * G31 - Dock sled (Z_PROBE_SLED only)
* G32 - Undock sled (Z_PROBE_SLED only) * G32 - Undock sled (Z_PROBE_SLED only)
* G60 - Store in memory actual position
* G61 - Move X Y Z to position in memory
* G90 - Use Absolute Coordinates * G90 - Use Absolute Coordinates
* G91 - Use Relative Coordinates * G91 - Use Relative Coordinates
* G92 - Set current position to coordinates given * G92 - Set current position to coordinates given
...@@ -181,6 +179,12 @@ ...@@ -181,6 +179,12 @@
* M302 - Allow cold extrudes, or set the minimum extrude S<temperature>. * M302 - Allow cold extrudes, or set the minimum extrude S<temperature>.
* M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C) * M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
* M304 - Set bed PID parameters P I and D * M304 - Set bed PID parameters P I and D
* M331 - Save current position coordinates (all axes, for active extruder).
* S<SLOT> - specifies memory slot # (0-based) to save into (default 0).
* M332 - Apply/restore saved coordinates to the active extruder.
* X Y Z E - Value to add at stored coordinates.
* F<speed> - Set Feedrate.
* S<SLOT> - specifies memory slot # (0-based) to restore from (default 0).
* M350 - Set microstepping mode. * M350 - Set microstepping mode.
* M351 - Toggle MS1 MS2 pins directly. * M351 - Toggle MS1 MS2 pins directly.
* M380 - Activate solenoid on active extruder * M380 - Activate solenoid on active extruder
...@@ -235,9 +239,11 @@ uint8_t debugLevel = DEBUG_INFO|DEBUG_ERRORS; ...@@ -235,9 +239,11 @@ uint8_t debugLevel = DEBUG_INFO|DEBUG_ERRORS;
static float feedrate = 1500.0, saved_feedrate; static float feedrate = 1500.0, saved_feedrate;
float current_position[NUM_AXIS] = { 0.0 }; float current_position[NUM_AXIS] = { 0.0 };
float destination[NUM_AXIS] = { 0.0 }; float destination[NUM_AXIS] = { 0.0 };
float lastpos[NUM_AXIS] = { 0.0 };
bool axis_known_position[3] = { false }; bool axis_known_position[3] = { false };
bool pos_saved = false;
float stored_position[NUM_POSITON_SLOTS][NUM_AXIS];
static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0; static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0;
static char *current_command, *current_command_args; static char *current_command, *current_command_args;
...@@ -562,7 +568,7 @@ bool enqueuecommand(const char *cmd) { ...@@ -562,7 +568,7 @@ bool enqueuecommand(const char *cmd) {
SET_OUTPUT(EXP_VOLTAGE_LEVEL_PIN); SET_OUTPUT(EXP_VOLTAGE_LEVEL_PIN);
WRITE(EXP_VOLTAGE_LEVEL_PIN,UI_VOLTAGE_LEVEL); WRITE(EXP_VOLTAGE_LEVEL_PIN,UI_VOLTAGE_LEVEL);
ExternalDac::begin(); //initialize ExternalDac ExternalDac::begin(); //initialize ExternalDac
lcd_buzz(10,10); buzz(10,10);
} }
#endif #endif
...@@ -3639,38 +3645,6 @@ inline void gcode_G28() { ...@@ -3639,38 +3645,6 @@ inline void gcode_G28() {
} }
#endif // DELTA && Z_PROBE_ENDSTOP #endif // DELTA && Z_PROBE_ENDSTOP
// G60: Store in memory actual position
inline void gcode_G60() {
memcpy(lastpos, current_position, sizeof(lastpos));
//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
inline void gcode_G61() {
for(int8_t i = 0; i < NUM_AXIS; i++) {
if(code_seen(axis_codes[i])) {
destination[i] = (float)code_value() + lastpos[i];
}
else {
destination[i] = current_position[i];
}
}
//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')) {
float next_feedrate = code_value();
if(next_feedrate > 0.0) feedrate = next_feedrate;
}
//finish moves
prepare_move();
}
/** /**
* G92: Set current position to given X Y Z E * G92: Set current position to given X Y Z E
*/ */
...@@ -5091,7 +5065,7 @@ inline void gcode_M226() { ...@@ -5091,7 +5065,7 @@ inline void gcode_M226() {
} }
#endif // NUM_SERVOS > 0 #endif // NUM_SERVOS > 0
#if HAS_LCD_BUZZ #if HAS_BUZZER
/** /**
* M300: Play beep sound S<frequency Hz> P<duration ms> * M300: Play beep sound S<frequency Hz> P<duration ms>
...@@ -5100,10 +5074,10 @@ inline void gcode_M226() { ...@@ -5100,10 +5074,10 @@ inline void gcode_M226() {
uint16_t beepS = code_seen('S') ? code_value_short() : 100; uint16_t beepS = code_seen('S') ? code_value_short() : 100;
uint32_t beepP = code_seen('P') ? code_value_long() : 1000; uint32_t beepP = code_seen('P') ? code_value_long() : 1000;
if (beepP > 5000) beepP = 5000; // limit to 5 seconds if (beepP > 5000) beepP = 5000; // limit to 5 seconds
lcd_buzz(beepP, beepS); buzz(beepP, beepS);
} }
#endif // HAS_LCD_BUZZ #endif // HAS_BUZZER
#ifdef PIDTEMP #ifdef PIDTEMP
...@@ -5175,6 +5149,73 @@ inline void gcode_M226() { ...@@ -5175,6 +5149,73 @@ inline void gcode_M226() {
} }
#endif // PIDTEMPBED #endif // PIDTEMPBED
/**
* M331: save current position
* S<slot> specifies memory slot # (0-based) to save into (default 0)
*/
inline void gcode_M331() {
int slot = 0;
if (code_seen('S')) slot = code_value();
if (slot < 0 || slot >= NUM_POSITON_SLOTS) {
ECHO_LMV(ER, MSG_INVALID_POS_SLOT, (int)NUM_POSITON_SLOTS);
return;
}
memcpy(stored_position[slot], current_position, sizeof(*stored_position));
pos_saved = true;
ECHO_SM(DB, MSG_SAVED_POS);
ECHO_MV(" S", slot);
ECHO_MV("<-X:", stored_position[slot][X_AXIS]);
ECHO_MV(" Y:", stored_position[slot][Y_AXIS]);
ECHO_MV(" Z:", stored_position[slot][Z_AXIS]);
ECHO_EMV(" E:", stored_position[slot][E_AXIS]);
}
/**
* M332: Apply/restore saved coordinates to the active extruder.
* X Y Z E - Value to add at stored coordinates.
* F<speed> - Set Feedrate.
* S<slot> specifies memory slot # (0-based) to save into (default 0).
*/
inline void gcode_M332() {
if (!pos_saved) return;
bool make_move = false;
int slot = 0;
if (code_seen('S')) slot = code_value();
if (slot < 0 || slot >= NUM_POSITON_SLOTS) {
ECHO_LMV(ER, MSG_INVALID_POS_SLOT, (int)NUM_POSITON_SLOTS);
return;
}
ECHO_SM(DB, MSG_RESTORING_POS);
ECHO_MV(" S", slot);
ECHO_M("->");
if (code_seen('F')) {
float next_feedrate = code_value();
if (next_feedrate > 0.0) feedrate = next_feedrate;
}
for(int8_t i = 0; i < NUM_AXIS; i++) {
if(code_seen(axis_codes[i])) {
destination[i] = (float)code_value() + stored_position[slot][i];
}
else {
destination[i] = current_position[i];
}
ECHO_MV(" ", axis_codes[i]);
ECHO_MV(":", destination[i]);
}
ECHO_E;
//finish moves
prepare_move();
st_synchronize();
}
#if HAS_MICROSTEPS #if HAS_MICROSTEPS
// M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
inline void gcode_M350() { inline void gcode_M350() {
...@@ -5450,7 +5491,7 @@ inline void gcode_M428() { ...@@ -5450,7 +5491,7 @@ inline void gcode_M428() {
else { else {
ECHO_LM(ER, MSG_ERR_M428_TOO_FAR); ECHO_LM(ER, MSG_ERR_M428_TOO_FAR);
LCD_ALERTMESSAGEPGM("Err: Too far!"); LCD_ALERTMESSAGEPGM("Err: Too far!");
#if HAS_LCD_BUZZ #if HAS_BUZZER
enqueuecommands_P(PSTR("M300 S40 P200")); enqueuecommands_P(PSTR("M300 S40 P200"));
#endif #endif
err = true; err = true;
...@@ -5469,7 +5510,7 @@ inline void gcode_M428() { ...@@ -5469,7 +5510,7 @@ inline void gcode_M428() {
#endif #endif
ECHO_LM(DB, "Offset applied."); ECHO_LM(DB, "Offset applied.");
LCD_ALERTMESSAGEPGM("Offset applied."); LCD_ALERTMESSAGEPGM("Offset applied.");
#if HAS_LCD_BUZZ #if HAS_BUZZER
enqueuecommands_P(PSTR("M300 S659 P200\nM300 S698 P200")); enqueuecommands_P(PSTR("M300 S659 P200\nM300 S698 P200"));
#endif #endif
} }
...@@ -5528,7 +5569,7 @@ inline void gcode_M503() { ...@@ -5528,7 +5569,7 @@ inline void gcode_M503() {
* *
*/ */
inline void gcode_M600() { inline void gcode_M600() {
float target[NUM_AXIS], fr60 = feedrate / 60; float lastpos[NUM_AXIS], target[NUM_AXIS], fr60 = feedrate / 60;
filament_changing = true; filament_changing = true;
for (int i = 0; i < NUM_AXIS; i++) for (int i = 0; i < NUM_AXIS; i++)
target[i] = lastpos[i] = current_position[i]; target[i] = lastpos[i] = current_position[i];
...@@ -5605,7 +5646,7 @@ inline void gcode_M503() { ...@@ -5605,7 +5646,7 @@ inline void gcode_M503() {
LCD_ALERTMESSAGEPGM("Zzzz Zzzz Zzzz"); LCD_ALERTMESSAGEPGM("Zzzz Zzzz Zzzz");
} }
if (beep) { if (beep) {
for(int8_t i = 0; i < 3; i++) lcd_buzz(100, 1000); for(int8_t i = 0; i < 3; i++) buzz(100, 1000);
last_set = millis(); last_set = millis();
beep = false; beep = false;
++cnt; ++cnt;
...@@ -6215,9 +6256,9 @@ void process_next_command() { ...@@ -6215,9 +6256,9 @@ void process_next_command() {
#endif // DELTA && Z_PROBE_ENDSTOP #endif // DELTA && Z_PROBE_ENDSTOP
case 60: // G60 Store in memory actual position case 60: // G60 Store in memory actual position
gcode_G60(); break; gcode_M331(); break;
case 61: // G61 move to X Y Z in memory case 61: // G61 move to X Y Z in memory
gcode_G61(); break; gcode_M332(); break;
case 90: // G90 case 90: // G90
relative_mode = false; break; relative_mode = false; break;
case 91: // G91 case 91: // G91
...@@ -6436,10 +6477,10 @@ void process_next_command() { ...@@ -6436,10 +6477,10 @@ void process_next_command() {
gcode_M280(); break; gcode_M280(); break;
#endif // NUM_SERVOS > 0 #endif // NUM_SERVOS > 0
#if HAS_LCD_BUZZ #if HAS_BUZZER
case 300: // M300 - Play beep tone case 300: // M300 - Play beep tone
gcode_M300(); break; gcode_M300(); break;
#endif // HAS_LCD_BUZZ #endif // HAS_BUZZER
#ifdef PIDTEMP #ifdef PIDTEMP
case 301: // M301 case 301: // M301
...@@ -6461,13 +6502,16 @@ void process_next_command() { ...@@ -6461,13 +6502,16 @@ void process_next_command() {
gcode_M304(); break; gcode_M304(); break;
#endif // PIDTEMPBED #endif // PIDTEMPBED
case 331: // M331 Saved Coordinated
gcode_M331(); break;
case 332: // M332 Restored Coordinates
gcode_M332(); break;
#if HAS_MICROSTEPS #if HAS_MICROSTEPS
case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
gcode_M350(); gcode_M350(); break;
break;
case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low. case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
gcode_M351(); gcode_M351(); break;
break;
#endif // HAS_MICROSTEPS #endif // HAS_MICROSTEPS
#ifdef SCARA #ifdef SCARA
......
This diff is collapsed.
...@@ -77,9 +77,9 @@ ...@@ -77,9 +77,9 @@
#define MSG_PID_P "PID-P" #define MSG_PID_P "PID-P"
#define MSG_PID_I "PID-I" #define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D" #define MSG_PID_D "PID-D"
#define MSG_E2 " E2" #define MSG_H1 " H1"
#define MSG_E3 " E3" #define MSG_H2 " H2"
#define MSG_E4 " E4" #define MSG_H3 " H3"
#define MSG_ACC "Accel" #define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk" #define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VZ_JERK "Vz-jerk" #define MSG_VZ_JERK "Vz-jerk"
...@@ -176,13 +176,18 @@ ...@@ -176,13 +176,18 @@
#define MSG_YSCALE "Y Scale" #define MSG_YSCALE "Y Scale"
#endif #endif
// Extra
#define MSG_LASER "Laser Preset" #define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configuration" #define MSG_CONFIG "Configuration"
#define MSG_E_BOWDEN_LENGTH "Extrude " STRINGIFY(BOWDEN_LENGTH) "mm" #define MSG_E_BOWDEN_LENGTH "Extrude " STRINGIFY(BOWDEN_LENGTH) "mm"
#define MSG_R_BOWDEN_LENGTH "Retract " STRINGIFY(BOWDEN_LENGTH) "mm" #define MSG_R_BOWDEN_LENGTH "Retract " STRINGIFY(BOWDEN_LENGTH) "mm"
#define MSG_PURGE_XMM "Purge " STRINGIFY(LCD_PURGE_LENGTH) "mm" #define MSG_PURGE_XMM "Purge " STRINGIFY(LCD_PURGE_LENGTH) "mm"
#define MSG_RETRACT_XMM "Retract " STRINGIFY(LCD_RETRACT_LENGTH) "mm" #define MSG_RETRACT_XMM "Retract " STRINGIFY(LCD_RETRACT_LENGTH) "mm"
#define MSG_SAVED_POS "Saved position"
#define MSG_RESTORING_POS "Restoring position"
#define MSG_INVALID_POS_SLOT "Invalid slot, total slots: "
// Firmware Test
#ifdef FIRMWARE_TEST #ifdef FIRMWARE_TEST
#define MSG_FWTEST_YES "Put the Y command to go next" #define MSG_FWTEST_YES "Put the Y command to go next"
#define MSG_FWTEST_NO "Put the N command to go next" #define MSG_FWTEST_NO "Put the N command to go next"
......
...@@ -77,9 +77,9 @@ ...@@ -77,9 +77,9 @@
#define MSG_PID_P "PID-P" #define MSG_PID_P "PID-P"
#define MSG_PID_I "PID-I" #define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D" #define MSG_PID_D "PID-D"
#define MSG_E2 " E2" #define MSG_H1 " H1"
#define MSG_E3 " E3" #define MSG_H2 " H2"
#define MSG_E4 " E4" #define MSG_H3 " H3"
#define MSG_ACC "Accel" #define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk" #define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VZ_JERK "Vz-jerk" #define MSG_VZ_JERK "Vz-jerk"
...@@ -176,13 +176,18 @@ ...@@ -176,13 +176,18 @@
#define MSG_YSCALE "Y Scale" #define MSG_YSCALE "Y Scale"
#endif #endif
// Extra
#define MSG_LASER "Laser Preset" #define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configurazione" #define MSG_CONFIG "Configurazione"
#define MSG_E_BOWDEN_LENGTH "Extrude " STRINGIFY(BOWDEN_LENGTH) "mm" #define MSG_E_BOWDEN_LENGTH "Extrude " STRINGIFY(BOWDEN_LENGTH) "mm"
#define MSG_R_BOWDEN_LENGTH "Retract " STRINGIFY(BOWDEN_LENGTH) "mm" #define MSG_R_BOWDEN_LENGTH "Retract " STRINGIFY(BOWDEN_LENGTH) "mm"
#define MSG_PURGE_XMM "Purge " STRINGIFY(LCD_PURGE_LENGTH) "mm" #define MSG_PURGE_XMM "Purge " STRINGIFY(LCD_PURGE_LENGTH) "mm"
#define MSG_RETRACT_XMM "Retract " STRINGIFY(LCD_RETRACT_LENGTH) "mm" #define MSG_RETRACT_XMM "Retract " STRINGIFY(LCD_RETRACT_LENGTH) "mm"
#define MSG_SAVED_POS "Posizione Salvata"
#define MSG_RESTORING_POS "Restoring position"
#define MSG_INVALID_POS_SLOT "Invalid slot, total slots: "
// Firmware Test
#ifdef FIRMWARE_TEST #ifdef FIRMWARE_TEST
#define MSG_FWTEST_YES "Dai il comando Y per andare avanti" #define MSG_FWTEST_YES "Dai il comando Y per andare avanti"
#define MSG_FWTEST_NO "Dai il comando N per andare avanti" #define MSG_FWTEST_NO "Dai il comando N per andare avanti"
......
...@@ -36,7 +36,6 @@ ...@@ -36,7 +36,6 @@
#if defined(PIDTEMPBED) || defined(PIDTEMP) #if defined(PIDTEMPBED) || defined(PIDTEMP)
#define PID_dT ((OVERSAMPLENR * 14.0)/(F_CPU / 64.0 / 256.0)) #define PID_dT ((OVERSAMPLENR * 14.0)/(F_CPU / 64.0 / 256.0))
#define RECI_PID_dT ( 1 / PID_dT )
#endif #endif
//=========================================================================== //===========================================================================
...@@ -375,17 +374,14 @@ int getHeaterPower(int heater) { ...@@ -375,17 +374,14 @@ int getHeaterPower(int heater) {
#if HAS_AUTO_FAN #if HAS_AUTO_FAN
void setExtruderAutoFanState(int pin, bool state) void setExtruderAutoFanState(int pin, bool state) {
{
unsigned char newFanSpeed = (state != 0) ? EXTRUDER_AUTO_FAN_SPEED : 0; unsigned char newFanSpeed = (state != 0) ? EXTRUDER_AUTO_FAN_SPEED : 0;
// this idiom allows both digital and PWM fan outputs (see M42 handling). // this idiom allows both digital and PWM fan outputs (see M42 handling).
pinMode(pin, OUTPUT);
digitalWrite(pin, newFanSpeed); digitalWrite(pin, newFanSpeed);
analogWrite(pin, newFanSpeed); analogWrite(pin, newFanSpeed);
} }
void checkExtruderAutoFans() void checkExtruderAutoFans() {
{
uint8_t fanState = 0; uint8_t fanState = 0;
// which fan pins need to be turned on? // which fan pins need to be turned on?
...@@ -448,7 +444,7 @@ void checkExtruderAutoFans() ...@@ -448,7 +444,7 @@ void checkExtruderAutoFans()
#endif #endif
} }
#endif // any extruder auto fan pins set #endif // HAS_AUTO_FAN
// //
// Temperature Error Handlers // Temperature Error Handlers
...@@ -740,7 +736,7 @@ static float analog2temp(int raw, uint8_t e) { ...@@ -740,7 +736,7 @@ static float analog2temp(int raw, uint8_t e) {
return celsius; return celsius;
} }
return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET; return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
} }
// Derived from RepRap FiveD extruder::getTemperature() // Derived from RepRap FiveD extruder::getTemperature()
...@@ -765,7 +761,7 @@ static float analog2tempBed(int raw) { ...@@ -765,7 +761,7 @@ static float analog2tempBed(int raw) {
return celsius; return celsius;
#elif defined BED_USES_AD595 #elif defined BED_USES_AD595
return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET; return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
#else #else
return 0; return 0;
#endif #endif
...@@ -944,6 +940,20 @@ void tp_init() { ...@@ -944,6 +940,20 @@ void tp_init() {
#if HAS_FILAMENT_SENSOR #if HAS_FILAMENT_SENSOR
ANALOG_SELECT(FILWIDTH_PIN); ANALOG_SELECT(FILWIDTH_PIN);
#endif #endif
#if HAS_AUTO_FAN_0
pinMode(EXTRUDER_0_AUTO_FAN_PIN, OUTPUT);
#endif
#if HAS_AUTO_FAN_1 && (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN)
pinMode(EXTRUDER_1_AUTO_FAN_PIN, OUTPUT);
#endif
#if HAS_AUTO_FAN_2 && (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) && (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN)
pinMode(EXTRUDER_2_AUTO_FAN_PIN, OUTPUT);
#endif
#if HAS_AUTO_FAN_3 && (EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) && (EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN) && (EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_2_AUTO_FAN_PIN)
pinMode(EXTRUDER_3_AUTO_FAN_PIN, OUTPUT);
#endif
#if HAS_POWER_CONSUMPTION_SENSOR #if HAS_POWER_CONSUMPTION_SENSOR
ANALOG_SELECT(POWER_CONSUMPTION_PIN); ANALOG_SELECT(POWER_CONSUMPTION_PIN);
#endif #endif
...@@ -979,7 +989,6 @@ void tp_init() { ...@@ -979,7 +989,6 @@ void tp_init() {
#ifdef HEATER_0_MAXTEMP #ifdef HEATER_0_MAXTEMP
TEMP_MAX_ROUTINE(0); TEMP_MAX_ROUTINE(0);
#endif #endif
#if HOTENDS > 1 #if HOTENDS > 1
#ifdef HEATER_1_MINTEMP #ifdef HEATER_1_MINTEMP
TEMP_MIN_ROUTINE(1); TEMP_MIN_ROUTINE(1);
......
This diff is collapsed.
...@@ -59,8 +59,6 @@ ...@@ -59,8 +59,6 @@
#if HAS_LCD_FILAMENT_SENSOR || HAS_LCD_POWER_SENSOR #if HAS_LCD_FILAMENT_SENSOR || HAS_LCD_POWER_SENSOR
extern millis_t previous_lcd_status_ms; extern millis_t previous_lcd_status_ms;
#endif #endif
void lcd_buzz(long duration,uint16_t freq);
void lcd_quick_feedback(); // Audible feedback for a button click - could also be visual void lcd_quick_feedback(); // Audible feedback for a button click - could also be visual
bool lcd_clicked(); bool lcd_clicked();
...@@ -117,7 +115,6 @@ ...@@ -117,7 +115,6 @@
FORCE_INLINE void lcd_setstatuspgm(const char* message, const uint8_t level=0) {} FORCE_INLINE void lcd_setstatuspgm(const char* message, const uint8_t level=0) {}
FORCE_INLINE void lcd_buttons_update() {} FORCE_INLINE void lcd_buttons_update() {}
FORCE_INLINE void lcd_reset_alert_level() {} FORCE_INLINE void lcd_reset_alert_level() {}
FORCE_INLINE void lcd_buzz(long duration, uint16_t freq) {}
FORCE_INLINE bool lcd_detected(void) { return true; } FORCE_INLINE bool lcd_detected(void) { return true; }
#define LCD_MESSAGEPGM(x) do{}while(0) #define LCD_MESSAGEPGM(x) do{}while(0)
...@@ -125,6 +122,10 @@ ...@@ -125,6 +122,10 @@
#endif //ULTRA_LCD #endif //ULTRA_LCD
#if HAS_BUZZER
void buzz(long duration,uint16_t freq);
#endif
char *itostr2(const uint8_t &x); char *itostr2(const uint8_t &x);
char *itostr31(const int &xx); char *itostr31(const int &xx);
char *itostr3(const int &xx); char *itostr3(const int &xx);
......
...@@ -546,31 +546,46 @@ static void lcd_implementation_status_screen() { ...@@ -546,31 +546,46 @@ static void lcd_implementation_status_screen() {
#if HOTENDS > 1 && TEMP_SENSOR_BED != 0 #if HOTENDS > 1 && TEMP_SENSOR_BED != 0
// If we both have a 2nd extruder and a heated bed, // If we both have a 2nd hotend and a heated bed,
// show the heated bed temp on the left, // show the heated bed temp on the left,
// since the first line is filled with extruder temps // since the first line is filled with hotend temps
LCD_TEMP(degBed(), degTargetBed(), LCD_STR_BEDTEMP[0]); LCD_TEMP(degBed(), degTargetBed(), LCD_STR_BEDTEMP[0]);
#else #else
lcd.print('X');
if (axis_known_position[X_AXIS])
#ifdef DELTA
lcd.print(ftostr30(current_position[X_AXIS]));
#else
lcd.print(ftostr3(current_position[X_AXIS]));
#endif
else
lcd_printPGM(PSTR("---"));
#ifdef DELTA #ifdef DELTA
lcd.print('X');
lcd.print(ftostr30(current_position[X_AXIS]));
lcd_printPGM(PSTR(" Y")); lcd_printPGM(PSTR(" Y"));
lcd.print(ftostr30(current_position[Y_AXIS])); if (axis_known_position[Y_AXIS])
lcd.print(ftostr30(current_position[Y_AXIS]));
else
#else #else
lcd.print('X');
lcd.print(ftostr3(current_position[X_AXIS]));
lcd_printPGM(PSTR(" Y")); lcd_printPGM(PSTR(" Y"));
lcd.print(ftostr3(current_position[Y_AXIS])); if (axis_known_position[Y_AXIS])
lcd.print(ftostr3(current_position[Y_AXIS]));
else
#endif // DELTA #endif // DELTA
lcd_printPGM(PSTR("---"));
#endif // HOTENDS > 1 || TEMP_SENSOR_BED != 0 #endif // HOTENDS > 1 || TEMP_SENSOR_BED != 0
#endif // LCD_WIDTH >= 20 #endif // LCD_WIDTH >= 20
lcd.setCursor(LCD_WIDTH - 8, 1); lcd.setCursor(LCD_WIDTH - 8, 1);
lcd.print('Z'); lcd.print('Z');
lcd.print(ftostr32sp(current_position[Z_AXIS] + 0.00001)); if (axis_known_position[Z_AXIS])
lcd.print(ftostr32sp(current_position[Z_AXIS] + 0.00001));
else
lcd_printPGM(PSTR("---.--"));
#endif // LCD_HEIGHT > 2 #endif // LCD_HEIGHT > 2
......
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