Commit 3bc2a24a authored by MagoKimbra's avatar MagoKimbra

Update 4.0.7

parent 987e10cd
......@@ -2,7 +2,6 @@
* Conditionals.h
* Defines that depend on configuration but are not editable.
*/
#ifndef CONDITIONALS_H
#ifndef CONFIGURATION_LCD // Get the LCD defines which are needed first
......@@ -413,16 +412,5 @@
#define WRITE_FAN(v) WRITE(FAN_PIN, v)
#endif
/**
* Sampling period of the temperature routine
* This override comes originally from temperature.cpp
* The Configuration.h option is basically ignored.
*/
#ifdef PID_dT
#undef PID_dT
#endif
#define PID_dT ((OVERSAMPLENR * 14.0)/(F_CPU / 64.0 / 256.0))
#endif //CONFIGURATION_LCD
#endif //CONDITIONALS_H
......@@ -20,7 +20,7 @@
// 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.0.6"
#define STRING_VERSION " 4.0.7"
#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.
......@@ -438,7 +438,7 @@ your extruder heater takes 2 minutes to hit the target on heating.
//========================= Bowden Filament management ======================
//#define EASY_LOAD
#ifdef EASY_LOAD
#define BOWDEN_LENGTH 560 // mm
#define BOWDEN_LENGTH 250 // mm
#define LCD_PURGE_LENGTH 3 // mm
#define LCD_RETRACT_LENGTH 3 // mm
#define LCD_PURGE_FEEDRATE 3 // mm/s
......
......@@ -131,9 +131,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the log
#define Z_MIN_POS 0
#define E_MIN_POS 0
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
//// MOVEMENT SETTINGS
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
......@@ -150,6 +147,12 @@ const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the log
#define DEFAULT_RETRACT_ACCELERATION 2500 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
// For the other hotends it is their distance from the extruder 0 hotend.
//#define HOTEND_OFFSET_X {0.0, 5.00, 0.0, 0.0} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00, 0.0, 0.0} // (in mm) for each extruder, offset of the hotend on the Y axis
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20 // (mm/sec)
#define DEFAULT_ZJERK 20 // (mm/sec)
......
......@@ -112,6 +112,31 @@
// On a RAMPS (or other 5 driver) motherboard, using this feature will limit you to using 1 extruder.
//#define Z_DUAL_STEPPER_DRIVERS
#ifdef Z_DUAL_STEPPER_DRIVERS
// Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
// That way the machine is capable to align the bed during home, since both Z steppers are homed.
// There is also an implementation of M666 (software endstops adjustment) to this feature.
// After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
// One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
// If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
// Play a little bit with small adjustments (0.5mm) and check the behaviour.
// The M119 (endstops report) will start reporting the Z2 Endstop as well.
#define Z_DUAL_ENDSTOPS
#ifdef Z_DUAL_ENDSTOPS
#define Z2_STEP_PIN E2_STEP_PIN // Stepper to be used to Z2 axis.
#define Z2_DIR_PIN E2_DIR_PIN
#define Z2_ENABLE_PIN E2_ENABLE_PIN
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
const bool Z2_MAX_ENDSTOP_INVERTING = false;
#define DISABLE_XMAX_ENDSTOP //Better to disable the XMAX to avoid conflict. Just rename "XMAX_ENDSTOP" by the endstop you are using for Z2 axis.
#endif
#endif
// Same again but for Y Axis.
//#define Y_DUAL_STEPPER_DRIVERS
......
......@@ -176,7 +176,7 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#define disable_e() {disable_e0(); disable_e1(); disable_e2(); disable_e3();}
#ifdef COREXY
enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5};
enum AxisEnum {X_AXIS=0, Y_AXIS=1, A_AXIS=0, B_AXIS=1, Z_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5};
//X_HEAD and Y_HEAD is used for systems that don't have a 1:1 relationship between X_AXIS and X Head movement, like CoreXY bots.
#else
enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3};
......@@ -224,7 +224,7 @@ void clamp_to_software_endstops(float target[3]);
void refresh_cmd_timeout(void);
#ifdef FAST_PWM_FAN
void setPwmFrequency(uint8_t pin, int val);
void setPwmFrequency(uint8_t pin, int val);
#endif
#ifndef CRITICAL_SECTION_START
......@@ -330,9 +330,8 @@ extern uint8_t active_driver;
// Debug with repetier
extern uint8_t debugLevel;
extern inline bool debugDryrun()
{
return ((debugLevel & 8)!=0);
extern inline bool debugDryrun() {
return ((debugLevel & 8) != 0);
}
#ifdef FIRMWARE_TEST
......
This source diff could not be displayed because it is too large. You can view the blob instead.
......@@ -14,7 +14,7 @@
#ifndef DOGM_LCD_IMPLEMENTATION_H
#define DOGM_LCD_IMPLEMENTATION_H
#define MARLIN_VERSION " 4.0.6"
#define MARLIN_VERSION " 4.0.7"
/**
* Implementation of the LCD display routines for a DOGM128 graphic display. These are common LCD 128x64 pixel graphic displays.
......
......@@ -115,6 +115,7 @@
#define MSG_Y_MAX "y_max: "
#define MSG_Z_MIN "z_min: "
#define MSG_Z_MAX "z_max: "
#define MSG_Z2_MAX "z2_max: "
#define MSG_E_MIN "e_min: "
#define MSG_PAUSE_PIN "pause pin: "
#define MSG_M119_REPORT "Reporting endstop status"
......@@ -226,8 +227,6 @@
#define STR_h3 "\263"
#define STR_Deg "\337"
#define STR_THERMOMETER "\002"
#elif defined(ULTRA_LCD)
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN for your LCD controller.
#endif
#endif
/*
......
......@@ -56,9 +56,9 @@
#define MSG_FAN_SPEED "Lüftergeschw."
#define MSG_FLOW "Fluss"
#define MSG_CONTROL "Einstellungen"
#define MSG_MIN "\002 Min"
#define MSG_MAX "\002 Max"
#define MSG_FACTOR "\002 Faktor"
#define MSG_MIN STR_THERMOMETER " Min"
#define MSG_MAX STR_THERMOMETER " Max"
#define MSG_FACTOR STR_THERMOMETER " Faktor"
#define MSG_AUTOTEMP "AutoTemp"
#define MSG_ON "Ein"
#define MSG_OFF "Aus"
......@@ -76,7 +76,7 @@
#define MSG_E "e"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
#define MSG_AMAX "A max"
#define MSG_A_RETRACT "A-Retract"
#define MSG_A_TRAVEL "A-travel"
#define MSG_XSTEPS "X steps/mm"
......@@ -89,7 +89,7 @@
#define MSG_TEMPERATURE "Temperatur"
#define MSG_MOTION "Bewegung"
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#define MSG_VOLUMETRIC_ENABLED "E in mm" STR_h3
#define MSG_FILAMENT_SIZE_EXTRUDER "Fil. Dia."
#define MSG_CONTRAST "LCD contrast"
#define MSG_STORE_EPROM "EPROM speichern"
......
......@@ -49,6 +49,12 @@ block_t *current_block; // A pointer to the block currently being traced
static unsigned char out_bits; // The next stepping-bits to be output
static unsigned int cleaning_buffer_counter;
#ifdef Z_DUAL_ENDSTOPS
static bool performing_homing = false,
locked_z_motor = false,
locked_z2_motor = false;
#endif
// Counter variables for the bresenham line tracer
static long counter_x, counter_y, counter_z, counter_e;
volatile static unsigned long step_events_completed; // The number of step events executed in the current block
......@@ -73,8 +79,8 @@ static volatile bool endstop_y_hit = false;
static volatile bool endstop_z_hit = false;
#ifdef NPR2
static volatile bool endstop_e_hit=false;
static bool old_e_min_endstop=false;
static volatile bool endstop_e_hit = false;
static bool old_e_min_endstop = false;
#endif
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
......@@ -89,7 +95,13 @@ static bool old_x_min_endstop = false,
old_y_min_endstop = false,
old_y_max_endstop = false,
old_z_min_endstop = false,
#ifndef Z_DUAL_ENDSTOPS
old_z_max_endstop = false;
#else
old_z_max_endstop = false,
old_z2_min_endstop = false,
old_z2_max_endstop = false;
#endif
static bool check_endstops = true;
......@@ -133,7 +145,23 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
#ifdef Z_DUAL_STEPPER_DRIVERS
#define Z_APPLY_DIR(v,Q) { Z_DIR_WRITE(v); Z2_DIR_WRITE(v); }
#define Z_APPLY_STEP(v,Q) { Z_STEP_WRITE(v); Z2_STEP_WRITE(v); }
#ifdef Z_DUAL_ENDSTOPS
#define Z_APPLY_STEP(v,Q) \
if (performing_homing) { \
if (Z_HOME_DIR > 0) {\
if (!(old_z_max_endstop && (count_direction[Z_AXIS] > 0)) && !locked_z_motor) Z_STEP_WRITE(v); \
if (!(old_z2_max_endstop && (count_direction[Z_AXIS] > 0)) && !locked_z2_motor) Z2_STEP_WRITE(v); \
} else {\
if (!(old_z_min_endstop && (count_direction[Z_AXIS] < 0)) && !locked_z_motor) Z_STEP_WRITE(v); \
if (!(old_z2_min_endstop && (count_direction[Z_AXIS] < 0)) && !locked_z2_motor) Z2_STEP_WRITE(v); \
} \
} else { \
Z_STEP_WRITE(v); \
Z2_STEP_WRITE(v); \
}
#else
#define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v), Z2_STEP_WRITE(v)
#endif
#else
#define Z_APPLY_DIR(v,Q) Z_DIR_WRITE(v)
#define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v)
......@@ -518,28 +546,66 @@ ISR(TIMER1_COMPA_vect) {
}
if (TEST(out_bits, Z_AXIS)) { // -direction
Z_DIR_WRITE(INVERT_Z_DIR);
#ifdef Z_DUAL_STEPPER_DRIVERS
Z2_DIR_WRITE(INVERT_Z_DIR);
#endif
Z_APPLY_DIR(INVERT_Z_DIR,0);
count_direction[Z_AXIS] = -1;
if (check_endstops) {
#if defined(Z_MIN_PIN) && Z_MIN_PIN >= 0
if (check_endstops)
{
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
#ifndef Z_DUAL_ENDSTOPS
UPDATE_ENDSTOP(z, Z, min, MIN);
#else
bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
#if defined(Z2_MIN_PIN) && Z2_MIN_PIN > -1
bool z2_min_endstop=(READ(Z2_MIN_PIN) != Z2_MIN_ENDSTOP_INVERTING);
#else
bool z2_min_endstop=z_min_endstop;
#endif
if(((z_min_endstop && old_z_min_endstop) || (z2_min_endstop && old_z2_min_endstop)) && (current_block->steps[Z_AXIS] > 0))
{
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
endstop_z_hit=true;
if (!(performing_homing) || ((performing_homing)&&(z_min_endstop && old_z_min_endstop)&&(z2_min_endstop && old_z2_min_endstop))) //if not performing home or if both endstops were trigged during homing...
{
step_events_completed = current_block->step_event_count;
}
}
else { // +direction
Z_DIR_WRITE(!INVERT_Z_DIR);
#ifdef Z_DUAL_STEPPER_DRIVERS
Z2_DIR_WRITE(!INVERT_Z_DIR);
old_z_min_endstop = z_min_endstop;
old_z2_min_endstop = z2_min_endstop;
#endif
#endif
}
}
else { // +direction
Z_APPLY_DIR(!INVERT_Z_DIR,0);
count_direction[Z_AXIS] = 1;
if (check_endstops) {
#if defined(Z_MAX_PIN) && Z_MAX_PIN >= 0
#ifndef Z_DUAL_ENDSTOPS
UPDATE_ENDSTOP(z, Z, max, MAX);
#else
bool z_max_endstop=(READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
#if defined(Z2_MAX_PIN) && Z2_MAX_PIN > -1
bool z2_max_endstop=(READ(Z2_MAX_PIN) != Z2_MAX_ENDSTOP_INVERTING);
#else
bool z2_max_endstop=z_max_endstop;
#endif
if(((z_max_endstop && old_z_max_endstop) || (z2_max_endstop && old_z2_max_endstop)) && (current_block->steps[Z_AXIS] > 0))
{
endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
endstop_z_hit=true;
// if (z_max_endstop && old_z_max_endstop) SERIAL_ECHOLN("z_max_endstop = true");
// if (z2_max_endstop && old_z2_max_endstop) SERIAL_ECHOLN("z2_max_endstop = true");
if (!(performing_homing) || ((performing_homing)&&(z_max_endstop && old_z_max_endstop)&&(z2_max_endstop && old_z2_max_endstop))) //if not performing home or if both endstops were trigged during homing...
{
step_events_completed = current_block->step_event_count;
}
}
old_z_max_endstop = z_max_endstop;
old_z2_max_endstop = z2_max_endstop;
#endif
#endif
}
}
......@@ -554,7 +620,7 @@ ISR(TIMER1_COMPA_vect) {
bool e_min_endstop=(READ(E_MIN_PIN) != E_MIN_ENDSTOP_INVERTING);
if (e_min_endstop && old_e_min_endstop && (current_block->steps[E_AXIS] > 0)) {
endstops_trigsteps[E_AXIS] = count_position[E_AXIS];
endstop_e_hit=true;
endstop_e_hit = true;
step_events_completed = current_block->step_event_count;
}
old_e_min_endstop = e_min_endstop;
......@@ -929,6 +995,13 @@ void st_init() {
#endif
#endif
#if defined(Z2_MAX_PIN) && Z2_MAX_PIN >= 0
SET_INPUT(Z2_MAX_PIN);
#ifdef ENDSTOPPULLUP_ZMAX
WRITE(Z2_MAX_PIN,HIGH);
#endif
#endif
#define AXIS_INIT(axis, AXIS, PIN) \
AXIS ##_STEP_INIT; \
AXIS ##_STEP_WRITE(INVERT_## PIN ##_STEP_PIN); \
......@@ -1273,3 +1346,9 @@ void microstep_readings() {
SERIAL_PROTOCOLLN(digitalRead(E1_MS2_PIN));
#endif
}
#ifdef Z_DUAL_ENDSTOPS
void In_Homing_Process(bool state) { performing_homing = state; }
void Lock_z_motor(bool state) { locked_z_motor = state; }
void Lock_z2_motor(bool state) { locked_z2_motor = state; }
#endif
......@@ -97,6 +97,12 @@ void digipot_current(uint8_t driver, int current);
void microstep_init();
void microstep_readings();
#ifdef Z_DUAL_ENDSTOPS
void In_Homing_Process(bool state);
void Lock_z_motor(bool state);
void Lock_z2_motor(bool state);
#endif
#ifdef BABYSTEPPING
void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention
#endif //BABYSTEPPING
......
......@@ -45,6 +45,10 @@
#define K2 (1.0 - K1)
#endif
#if defined(PIDTEMPBED) || defined(PIDTEMP)
#define PID_dT ((OVERSAMPLENR * 14.0)/(F_CPU / 64.0 / 256.0))
#endif
//===========================================================================
//============================= public variables ============================
//===========================================================================
......@@ -82,6 +86,7 @@ unsigned char soft_pwm_bed;
#if HAS_POWER_CONSUMPTION_SENSOR
int current_raw_powconsumption = 0; //Holds measured power consumption
static unsigned long raw_powconsumption_value = 0;
#endif
//===========================================================================
......@@ -568,6 +573,12 @@ void manage_heater() {
updateTemperaturesFromRawValues();
#ifdef HEATER_0_USES_MAX6675
float ct = current_temperature[0];
if (ct > min(HEATER_0_MAXTEMP, 1023)) max_temp_error(0);
if (ct < max(HEATER_0_MINTEMP, 0.01)) min_temp_error(0);
#endif //HEATER_0_USES_MAX6675
unsigned long ms = millis();
// Loop through all hotends
......@@ -599,7 +610,7 @@ void manage_heater() {
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
if (fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) {
disable_heater();
_temp_error(-1, MSG_EXTRUDER_SWITCHED_OFF, MSG_ERR_REDUNDANT_TEMP);
_temp_error(0, PSTR(MSG_EXTRUDER_SWITCHED_OFF), PSTR(MSG_ERR_REDUNDANT_TEMP));
}
#endif //TEMP_SENSOR_1_AS_REDUNDANT
......@@ -1181,20 +1192,45 @@ enum TempState {
StartupDelay // Startup, delay initial temp reading a tiny bit so the hardware can settle
};
//
// Timer 0 is shared with millies
//
ISR(TIMER0_COMPB_vect) {
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
#define TEMP_SENSOR_COUNT 2
#else
#else
#define TEMP_SENSOR_COUNT HOTENDS
#endif
static unsigned long raw_temp_value[TEMP_SENSOR_COUNT] = { 0 };
static unsigned long raw_temp_bed_value = 0;
static void set_current_temp_raw() {
#ifndef HEATER_0_USES_MAX6675
current_temperature_raw[0] = raw_temp_value[0];
#endif
#if HOTENDS > 1
current_temperature_raw[1] = raw_temp_value[1];
#if HOTENDS > 2
current_temperature_raw[2] = raw_temp_value[2];
#if HOTENDS > 3
current_temperature_raw[3] = raw_temp_value[3];
#endif
#endif
#endif
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
redundant_temperature_raw = raw_temp_value[1];
#endif
current_temperature_bed_raw = raw_temp_bed_value;
#if HAS_POWER_CONSUMPTION_SENSOR
float power_zero_raw = (POWER_ZERO * 1023 * OVERSAMPLENR) / 5.0;
current_raw_powconsumption = (raw_powconsumption_value < power_zero_raw) ? (2 * power_zero_raw - raw_powconsumption_value) : (raw_powconsumption_value);
#endif
}
//
// Timer 0 is shared with millies
//
ISR(TIMER0_COMPB_vect) {
//these variables are only accessible from the ISR, but static, so they don't lose their value
static unsigned char temp_count = 0;
static unsigned long raw_temp_value[TEMP_SENSOR_COUNT] = { 0 };
static unsigned long raw_temp_bed_value = 0;
static TempState temp_state = StartupDelay;
static unsigned char pwm_count = BIT(SOFT_PWM_SCALE);
......@@ -1229,10 +1265,6 @@ ISR(TIMER0_COMPB_vect) {
static unsigned long raw_filwidth_value = 0;
#endif
#if HAS_POWER_CONSUMPTION_SENSOR
static unsigned long raw_powconsumption_value = 0;
#endif
#ifndef SLOW_PWM_HEATERS
/**
* standard PWM modulation
......@@ -1517,36 +1549,14 @@ ISR(TIMER0_COMPB_vect) {
// break;
} // switch(temp_state)
if (temp_count >= OVERSAMPLENR) { // 14 * 16 * 1/(16000000/64/256) = 229ms.
if (temp_count >= OVERSAMPLENR) { // 14 * 16 * 1/(16000000/64/256)
if (!temp_meas_ready) { //Only update the raw values if they have been read. Else we could be updating them during reading.
#ifndef HEATER_0_USES_MAX6675
current_temperature_raw[0] = raw_temp_value[0];
#endif
#if HOTENDS > 1
current_temperature_raw[1] = raw_temp_value[1];
#if HOTENDS > 2
current_temperature_raw[2] = raw_temp_value[2];
#if HOTENDS > 3
current_temperature_raw[3] = raw_temp_value[3];
#endif
#endif
#endif
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
redundant_temperature_raw = raw_temp_value[1];
#endif
#if HAS_POWER_CONSUMPTION_SENSOR
float power_zero_raw = (POWER_ZERO * 1023 * OVERSAMPLENR) / 5.0;
current_raw_powconsumption = (raw_powconsumption_value < power_zero_raw) ? (2 * power_zero_raw - raw_powconsumption_value) : (raw_powconsumption_value);
#endif
current_temperature_bed_raw = raw_temp_bed_value;
set_current_temp_raw();
} //!temp_meas_ready
// Filament Sensor - can be read any time since IIR filtering is used
#if HAS_FILAMENT_SENSOR
current_raw_filwidth = raw_filwidth_value >> 10; // Divide to get to 0-16368 range since we used 1/128 IIR filter approach
current_raw_filwidth = raw_filwidth_value >> 10; // Divide to get to 0-16384 range since we used 1/128 IIR filter approach
#endif
temp_meas_ready = true;
......@@ -1558,11 +1568,7 @@ ISR(TIMER0_COMPB_vect) {
raw_powconsumption_value = 0;
#endif
#ifdef HEATER_0_USES_MAX6675
float ct = current_temperature[0];
if (ct > min(HEATER_0_MAXTEMP, 1023)) max_temp_error(0);
if (ct < max(HEATER_0_MINTEMP, 0.01)) min_temp_error(0);
#else
#ifndef HEATER_0_USES_MAX6675
#if HEATER_0_RAW_LO_TEMP > HEATER_0_RAW_HI_TEMP
#define GE0 <=
#else
......
......@@ -52,10 +52,10 @@ char lcd_status_message[LCD_WIDTH+1] = WELCOME_MSG;
#ifdef DOGLCD
#include "dogm_lcd_implementation.h"
#define LCD u8g
#define LCD_Printpos(x, y) u8g.setPrintPos(x, y)
#else
#include "ultralcd_implementation_hitachi_HD44780.h"
#define LCD lcd
#define LCD_Printpos(x, y) lcd.setCursor(x, y)
#endif
/* Different menus */
......@@ -310,17 +310,6 @@ static void lcd_status_screen()
lcd_status_update_delay = 10; /* redraw the main screen every second. This is easier then trying keep track of all things that change on the screen */
}
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY) || (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY) && (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
if (millis() > message_millis + 15000)
#else
if (millis() > message_millis + 10000)
#endif
{
message_millis = millis();
}
#endif
#ifdef ULTIPANEL
bool current_click = LCD_CLICKED;
......@@ -349,6 +338,16 @@ static void lcd_status_screen()
currentMenu == lcd_status_screen
#endif
);
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY) || (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
#if (defined(FILAMENT_SENSOR) && defined(FILWIDTH_PIN) && FILWIDTH_PIN >= 0) && defined(FILAMENT_LCD_DISPLAY) && (defined(POWER_CONSUMPTION) && defined(POWER_CONSUMPTION_PIN) && POWER_CONSUMPTION_PIN >= 0) && defined(POWER_CONSUMPTION_LCD_DISPLAY)
if (millis() > message_millis + 15000)
#else
if (millis() > message_millis + 10000)
#endif
{
message_millis = millis();
}
#endif
}
#ifdef ULTIPANEL_FEEDMULTIPLY
......@@ -698,7 +697,7 @@ void lcd_level_bed()
switch(pageShowInfo) {
case 0:
{
LCD.setCursor(0, 1);
LCD_Printpos(0, 1);
lcd_printPGM(PSTR(MSG_LP_INTRO));
currentMenu = lcd_level_bed;
ChangeScreen=false;
......@@ -706,7 +705,7 @@ void lcd_level_bed()
break;
case 1:
{
LCD.setCursor(0, 1);
LCD_Printpos(0, 1);
lcd_printPGM(PSTR(MSG_LP_1));
currentMenu = lcd_level_bed;
ChangeScreen=false;
......@@ -714,7 +713,7 @@ void lcd_level_bed()
break;
case 2:
{
LCD.setCursor(0, 1);
LCD_Printpos(0, 1);
lcd_printPGM(PSTR(MSG_LP_2));
currentMenu = lcd_level_bed;
ChangeScreen=false;
......@@ -722,7 +721,7 @@ void lcd_level_bed()
break;
case 3:
{
LCD.setCursor(0, 1);
LCD_Printpos(0, 1);
lcd_printPGM(PSTR(MSG_LP_3));
currentMenu = lcd_level_bed;
ChangeScreen=false;
......@@ -730,7 +729,7 @@ void lcd_level_bed()
break;
case 4:
{
LCD.setCursor(0, 1);
LCD_Printpos(0, 1);
lcd_printPGM(PSTR(MSG_LP_4));
currentMenu = lcd_level_bed;
ChangeScreen=false;
......@@ -738,7 +737,7 @@ void lcd_level_bed()
break;
case 5:
{
LCD.setCursor(0, 1);
LCD_Printpos(0, 1);
lcd_printPGM(PSTR(MSG_LP_5));
currentMenu = lcd_level_bed;
ChangeScreen=false;
......@@ -746,7 +745,7 @@ void lcd_level_bed()
break;
case 6:
{
LCD.setCursor(2, 2);
LCD_Printpos(2, 2);
lcd_printPGM(PSTR(MSG_LP_6));
ChangeScreen=false;
delay(1200);
......
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