Merged updates from Marlin_v1.
This commit is contained in:
commit
3b2e5027e5
84 changed files with 2037 additions and 3806 deletions
|
@ -43,7 +43,7 @@
|
||||||
// 70 = Megatronics
|
// 70 = Megatronics
|
||||||
// 90 = Alpha OMCA board
|
// 90 = Alpha OMCA board
|
||||||
// 91 = Final OMCA board
|
// 91 = Final OMCA board
|
||||||
// Rambo = 301
|
// 301 = Rambo
|
||||||
|
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD 33
|
#define MOTHERBOARD 33
|
||||||
|
@ -145,9 +145,11 @@
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#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 PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
|
#define PID_FUNCTIONAL_RANGE 10 // 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_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
|
#define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
|
||||||
#define K1 0.95 //smoothing factor withing the PID
|
#define K1 0.95 //smoothing factor withing the PID
|
||||||
#define PID_dT ((16.0 * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the
|
#define PID_dT ((16.0 * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
|
||||||
|
|
||||||
// If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it
|
// If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it
|
||||||
// Ultimaker
|
// Ultimaker
|
||||||
|
@ -290,8 +292,8 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
|
||||||
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
||||||
|
|
||||||
// The position of the homing switches
|
// The position of the homing switches
|
||||||
#define MANUAL_HOME_POSITIONS // If defined, manualy programed locations will be used
|
define MANUAL_HOME_POSITIONS // If defined, MANUAL_*_HOME_POS below will be used
|
||||||
//#define BED_CENTER_AT_0_0 // If defined the center of the bed is defined as (0,0)
|
//#define BED_CENTER_AT_0_0 // If defined, the center of the bed is at (X=0, Y=0)
|
||||||
|
|
||||||
// Manual homing switch locations:
|
// Manual homing switch locations:
|
||||||
// For deltabots this means top and center of the cartesian print volume.
|
// For deltabots this means top and center of the cartesian print volume.
|
||||||
|
|
|
@ -78,7 +78,7 @@
|
||||||
|
|
||||||
//// AUTOSET LOCATIONS OF LIMIT SWITCHES
|
//// AUTOSET LOCATIONS OF LIMIT SWITCHES
|
||||||
//// Added by ZetaPhoenix 09-15-2012
|
//// Added by ZetaPhoenix 09-15-2012
|
||||||
#ifdef MANUAL_HOME_POSITIONS //Use manual limit switch locations
|
#ifdef MANUAL_HOME_POSITIONS // Use manual limit switch locations
|
||||||
#define X_HOME_POS MANUAL_X_HOME_POS
|
#define X_HOME_POS MANUAL_X_HOME_POS
|
||||||
#define Y_HOME_POS MANUAL_Y_HOME_POS
|
#define Y_HOME_POS MANUAL_Y_HOME_POS
|
||||||
#define Z_HOME_POS MANUAL_Z_HOME_POS
|
#define Z_HOME_POS MANUAL_Z_HOME_POS
|
||||||
|
|
|
@ -125,13 +125,13 @@ MCU ?= atmega1280
|
||||||
|
|
||||||
#Teensylu
|
#Teensylu
|
||||||
else ifeq ($(HARDWARE_MOTHERBOARD),8)
|
else ifeq ($(HARDWARE_MOTHERBOARD),8)
|
||||||
HARDWARE_VARIANT ?= Teensyduino
|
HARDWARE_VARIANT ?= Teensy
|
||||||
MCU ?= at90usb1286
|
MCU ?= at90usb1286
|
||||||
else ifeq ($(HARDWARE_MOTHERBOARD),81)
|
else ifeq ($(HARDWARE_MOTHERBOARD),81)
|
||||||
HARDWARE_VARIANT ?= Teensyduino
|
HARDWARE_VARIANT ?= Teensy
|
||||||
MCU ?= at90usb1286
|
MCU ?= at90usb1286
|
||||||
else ifeq ($(HARDWARE_MOTHERBOARD),82)
|
else ifeq ($(HARDWARE_MOTHERBOARD),82)
|
||||||
HARDWARE_VARIANT ?= Teensyduino
|
HARDWARE_VARIANT ?= Teensy
|
||||||
MCU ?= at90usb646
|
MCU ?= at90usb646
|
||||||
|
|
||||||
#Gen3+
|
#Gen3+
|
||||||
|
@ -173,8 +173,13 @@ F_CPU ?= 16000000
|
||||||
ifeq ($(HARDWARE_VARIANT), arduino)
|
ifeq ($(HARDWARE_VARIANT), arduino)
|
||||||
HARDWARE_SRC = $(ARDUINO_INSTALL_DIR)/hardware/arduino/cores/arduino
|
HARDWARE_SRC = $(ARDUINO_INSTALL_DIR)/hardware/arduino/cores/arduino
|
||||||
else
|
else
|
||||||
HARDWARE_SRC = $(HARDWARE_VARIANT)/cores/arduino
|
ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true)
|
||||||
|
HARDWARE_SRC = ../ArduinoAddons/Arduino_1.x.x/$(HARDWARE_VARIANT)/cores/arduino
|
||||||
|
else
|
||||||
|
HARDWARE_SRC = ../ArduinoAddons/Arduino_0.xx/$(HARDWARE_VARIANT)/cores/arduino
|
||||||
endif
|
endif
|
||||||
|
endif
|
||||||
|
|
||||||
|
|
||||||
TARGET = $(notdir $(CURDIR))
|
TARGET = $(notdir $(CURDIR))
|
||||||
|
|
||||||
|
@ -223,9 +228,27 @@ OPT = s
|
||||||
|
|
||||||
DEFINES ?=
|
DEFINES ?=
|
||||||
|
|
||||||
|
# Program settings
|
||||||
|
CC = $(AVR_TOOLS_PATH)avr-gcc
|
||||||
|
CXX = $(AVR_TOOLS_PATH)avr-g++
|
||||||
|
OBJCOPY = $(AVR_TOOLS_PATH)avr-objcopy
|
||||||
|
OBJDUMP = $(AVR_TOOLS_PATH)avr-objdump
|
||||||
|
AR = $(AVR_TOOLS_PATH)avr-ar
|
||||||
|
SIZE = $(AVR_TOOLS_PATH)avr-size
|
||||||
|
NM = $(AVR_TOOLS_PATH)avr-nm
|
||||||
|
AVRDUDE = avrdude
|
||||||
|
REMOVE = rm -f
|
||||||
|
MV = mv -f
|
||||||
|
|
||||||
# Place -D or -U options here
|
# Place -D or -U options here
|
||||||
CDEFS = -DF_CPU=$(F_CPU) ${addprefix -D , $(DEFINES)}
|
CDEFS = -DF_CPU=$(F_CPU) ${addprefix -D , $(DEFINES)}
|
||||||
CXXDEFS = -DF_CPU=$(F_CPU) ${addprefix -D , $(DEFINES)}
|
CXXDEFS = $(CDEFS)
|
||||||
|
|
||||||
|
ifeq ($(HARDWARE_VARIANT), Teensy)
|
||||||
|
CDEFS += -DUSB_SERIAL
|
||||||
|
SRC += usb.c pins_teensy.c
|
||||||
|
CXXSRC += usb_api.cpp
|
||||||
|
endif
|
||||||
|
|
||||||
# Add all the source directories as include directories too
|
# Add all the source directories as include directories too
|
||||||
CINCS = ${addprefix -I ,${VPATH}}
|
CINCS = ${addprefix -I ,${VPATH}}
|
||||||
|
@ -247,8 +270,8 @@ CTUNING += -DMOTHERBOARD=${HARDWARE_MOTHERBOARD}
|
||||||
endif
|
endif
|
||||||
#CEXTRA = -Wa,-adhlns=$(<:.c=.lst)
|
#CEXTRA = -Wa,-adhlns=$(<:.c=.lst)
|
||||||
|
|
||||||
CFLAGS = $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CEXTRA) $(CTUNING)
|
CFLAGS := $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CEXTRA) $(CTUNING)
|
||||||
CXXFLAGS = $(CDEFS) $(CINCS) -O$(OPT) -Wall $(CEXTRA) $(CTUNING)
|
CXXFLAGS := $(CDEFS) $(CINCS) -O$(OPT) -Wall $(CEXTRA) $(CTUNING)
|
||||||
#ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs
|
#ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs
|
||||||
LDFLAGS = -lm
|
LDFLAGS = -lm
|
||||||
|
|
||||||
|
@ -260,18 +283,6 @@ AVRDUDE_FLAGS = -D -C $(ARDUINO_INSTALL_DIR)/hardware/tools/avrdude.conf \
|
||||||
-p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) \
|
-p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) \
|
||||||
-b $(UPLOAD_RATE)
|
-b $(UPLOAD_RATE)
|
||||||
|
|
||||||
# Program settings
|
|
||||||
CC = $(AVR_TOOLS_PATH)avr-gcc
|
|
||||||
CXX = $(AVR_TOOLS_PATH)avr-g++
|
|
||||||
OBJCOPY = $(AVR_TOOLS_PATH)avr-objcopy
|
|
||||||
OBJDUMP = $(AVR_TOOLS_PATH)avr-objdump
|
|
||||||
AR = $(AVR_TOOLS_PATH)avr-ar
|
|
||||||
SIZE = $(AVR_TOOLS_PATH)avr-size
|
|
||||||
NM = $(AVR_TOOLS_PATH)avr-nm
|
|
||||||
AVRDUDE = avrdude
|
|
||||||
REMOVE = rm -f
|
|
||||||
MV = mv -f
|
|
||||||
|
|
||||||
# Define all object files.
|
# Define all object files.
|
||||||
OBJ = ${patsubst %.c, $(BUILD_DIR)/%.o, ${SRC}}
|
OBJ = ${patsubst %.c, $(BUILD_DIR)/%.o, ${SRC}}
|
||||||
OBJ += ${patsubst %.cpp, $(BUILD_DIR)/%.o, ${CXXSRC}}
|
OBJ += ${patsubst %.cpp, $(BUILD_DIR)/%.o, ${CXXSRC}}
|
||||||
|
|
|
@ -26,14 +26,12 @@
|
||||||
#define HardwareSerial_h // trick to disable the standard HWserial
|
#define HardwareSerial_h // trick to disable the standard HWserial
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ARDUINO >= 100
|
#if (ARDUINO >= 100) && !defined(__AVR_ATmega644P__)
|
||||||
#if defined(__AVR_ATmega644P__)
|
# include "Arduino.h"
|
||||||
#include "WProgram.h"
|
|
||||||
#else
|
|
||||||
#include "Arduino.h"
|
|
||||||
#endif
|
|
||||||
#else
|
#else
|
||||||
#include "WProgram.h"
|
# include "WProgram.h"
|
||||||
|
//Arduino < 1.0.0 does not define this, so we need to do it ourselfs
|
||||||
|
# define analogInputToDigitalPin(p) ((p) + A0)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "MarlinSerial.h"
|
#include "MarlinSerial.h"
|
||||||
|
@ -183,7 +181,6 @@ void setPwmFrequency(uint8_t pin, int val);
|
||||||
extern float homing_feedrate[];
|
extern float homing_feedrate[];
|
||||||
extern bool axis_relative_modes[];
|
extern bool axis_relative_modes[];
|
||||||
extern int feedmultiply;
|
extern int feedmultiply;
|
||||||
extern bool feedmultiplychanged;
|
|
||||||
extern int extrudemultiply; // Sets extrude multiply factor (in percent)
|
extern int extrudemultiply; // Sets extrude multiply factor (in percent)
|
||||||
extern float current_position[NUM_AXIS] ;
|
extern float current_position[NUM_AXIS] ;
|
||||||
extern float add_homeing[3];
|
extern float add_homeing[3];
|
||||||
|
|
|
@ -147,7 +147,6 @@ CardReader card;
|
||||||
float homing_feedrate[] = HOMING_FEEDRATE;
|
float homing_feedrate[] = HOMING_FEEDRATE;
|
||||||
bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
|
bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
|
||||||
int feedmultiply=100; //100->1 200->2
|
int feedmultiply=100; //100->1 200->2
|
||||||
bool feedmultiplychanged;
|
|
||||||
int saved_feedmultiply;
|
int saved_feedmultiply;
|
||||||
int extrudemultiply=100; //100->1 200->2
|
int extrudemultiply=100; //100->1 200->2
|
||||||
float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
|
float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
|
||||||
|
@ -826,7 +825,7 @@ void process_commands()
|
||||||
{
|
{
|
||||||
switch( (int)code_value() )
|
switch( (int)code_value() )
|
||||||
{
|
{
|
||||||
#ifdef ULTRA_LCD
|
#ifdef ULTIPANEL
|
||||||
case 0: // M0 - Unconditional stop - Wait for user button press on LCD
|
case 0: // M0 - Unconditional stop - Wait for user button press on LCD
|
||||||
case 1: // M1 - Conditional stop - Wait for user button press on LCD
|
case 1: // M1 - Conditional stop - Wait for user button press on LCD
|
||||||
{
|
{
|
||||||
|
@ -947,25 +946,23 @@ void process_commands()
|
||||||
if (code_seen('S'))
|
if (code_seen('S'))
|
||||||
{
|
{
|
||||||
int pin_status = code_value();
|
int pin_status = code_value();
|
||||||
|
int pin_number = LED_PIN;
|
||||||
if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
|
if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
|
||||||
|
pin_number = code_value();
|
||||||
|
for(int8_t i = 0; i < (int8_t)sizeof(sensitive_pins); i++)
|
||||||
{
|
{
|
||||||
int pin_number = code_value();
|
if (sensitive_pins[i] == pin_number)
|
||||||
for(int8_t i = 0; i < (int8_t)sizeof(sensitive_pins); i++)
|
|
||||||
{
|
{
|
||||||
if (sensitive_pins[i] == pin_number)
|
pin_number = -1;
|
||||||
{
|
break;
|
||||||
pin_number = -1;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (pin_number > -1)
|
|
||||||
{
|
|
||||||
pinMode(pin_number, OUTPUT);
|
|
||||||
digitalWrite(pin_number, pin_status);
|
|
||||||
analogWrite(pin_number, pin_status);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
if (pin_number > -1)
|
||||||
|
{
|
||||||
|
pinMode(pin_number, OUTPUT);
|
||||||
|
digitalWrite(pin_number, pin_status);
|
||||||
|
analogWrite(pin_number, pin_status);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 104: // M104
|
case 104: // M104
|
||||||
|
@ -1211,7 +1208,10 @@ void process_commands()
|
||||||
SERIAL_PROTOCOLPGM(MSG_M115_REPORT);
|
SERIAL_PROTOCOLPGM(MSG_M115_REPORT);
|
||||||
break;
|
break;
|
||||||
case 117: // M117 display message
|
case 117: // M117 display message
|
||||||
lcd_setstatus(cmdbuffer[bufindr]+5);
|
starpos = (strchr(strchr_pointer + 5,'*'));
|
||||||
|
if(starpos!=NULL)
|
||||||
|
*(starpos-1)='\0';
|
||||||
|
lcd_setstatus(strchr_pointer + 5);
|
||||||
break;
|
break;
|
||||||
case 114: // M114
|
case 114: // M114
|
||||||
SERIAL_PROTOCOLPGM("X:");
|
SERIAL_PROTOCOLPGM("X:");
|
||||||
|
@ -1362,7 +1362,6 @@ void process_commands()
|
||||||
if(code_seen('S'))
|
if(code_seen('S'))
|
||||||
{
|
{
|
||||||
feedmultiply = code_value() ;
|
feedmultiply = code_value() ;
|
||||||
feedmultiplychanged = true;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -1465,27 +1464,27 @@ void process_commands()
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 500: // Store settings in EEPROM
|
case 500: // M500 Store settings in EEPROM
|
||||||
{
|
{
|
||||||
Config_StoreSettings();
|
Config_StoreSettings();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 501: // Read settings from EEPROM
|
case 501: // M501 Read settings from EEPROM
|
||||||
{
|
{
|
||||||
Config_RetrieveSettings();
|
Config_RetrieveSettings();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 502: // Revert to default settings
|
case 502: // M502 Revert to default settings
|
||||||
{
|
{
|
||||||
Config_ResetDefault();
|
Config_ResetDefault();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 503: // print settings currently in memory
|
case 503: // M503 print settings currently in memory
|
||||||
{
|
{
|
||||||
Config_PrintSettings();
|
Config_PrintSettings();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 907: // Set digital trimpot motor current using axis codes.
|
case 907: // M907 Set digital trimpot motor current using axis codes.
|
||||||
{
|
{
|
||||||
#if DIGIPOTSS_PIN > -1
|
#if DIGIPOTSS_PIN > -1
|
||||||
for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_current(i,code_value());
|
for(int i=0;i<=NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_current(i,code_value());
|
||||||
|
@ -1493,7 +1492,7 @@ void process_commands()
|
||||||
if(code_seen('S')) for(int i=0;i<=4;i++) digipot_current(i,code_value());
|
if(code_seen('S')) for(int i=0;i<=4;i++) digipot_current(i,code_value());
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
case 908: // Control digital trimpot directly.
|
case 908: // M908 Control digital trimpot directly.
|
||||||
{
|
{
|
||||||
#if DIGIPOTSS_PIN > -1
|
#if DIGIPOTSS_PIN > -1
|
||||||
uint8_t channel,current;
|
uint8_t channel,current;
|
||||||
|
@ -1503,7 +1502,7 @@ void process_commands()
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 350: // 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.
|
||||||
{
|
{
|
||||||
#if X_MS1_PIN > -1
|
#if X_MS1_PIN > -1
|
||||||
if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value());
|
if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value());
|
||||||
|
@ -1513,7 +1512,7 @@ void process_commands()
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 351: // 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.
|
||||||
{
|
{
|
||||||
#if X_MS1_PIN > -1
|
#if X_MS1_PIN > -1
|
||||||
if(code_seen('S')) switch((int)code_value())
|
if(code_seen('S')) switch((int)code_value())
|
||||||
|
@ -1531,8 +1530,9 @@ void process_commands()
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 999: // Restart after being stopped
|
case 999: // M999: Restart after being stopped
|
||||||
Stopped = false;
|
Stopped = false;
|
||||||
|
lcd_reset_alert_level();
|
||||||
gcode_LastN = Stopped_gcode_LastN;
|
gcode_LastN = Stopped_gcode_LastN;
|
||||||
FlushSerialRequestResend();
|
FlushSerialRequestResend();
|
||||||
break;
|
break;
|
||||||
|
@ -1880,7 +1880,7 @@ void setPwmFrequency(uint8_t pin, int val)
|
||||||
#if defined(TCCR0A)
|
#if defined(TCCR0A)
|
||||||
case TIMER0A:
|
case TIMER0A:
|
||||||
case TIMER0B:
|
case TIMER0B:
|
||||||
// TCCR0B &= ~(CS00 | CS01 | CS02);
|
// TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02));
|
||||||
// TCCR0B |= val;
|
// TCCR0B |= val;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1888,7 +1888,7 @@ void setPwmFrequency(uint8_t pin, int val)
|
||||||
#if defined(TCCR1A)
|
#if defined(TCCR1A)
|
||||||
case TIMER1A:
|
case TIMER1A:
|
||||||
case TIMER1B:
|
case TIMER1B:
|
||||||
// TCCR1B &= ~(CS10 | CS11 | CS12);
|
// TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
|
||||||
// TCCR1B |= val;
|
// TCCR1B |= val;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1896,7 +1896,7 @@ void setPwmFrequency(uint8_t pin, int val)
|
||||||
#if defined(TCCR2)
|
#if defined(TCCR2)
|
||||||
case TIMER2:
|
case TIMER2:
|
||||||
case TIMER2:
|
case TIMER2:
|
||||||
TCCR2 &= ~(CS10 | CS11 | CS12);
|
TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12));
|
||||||
TCCR2 |= val;
|
TCCR2 |= val;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1904,7 +1904,7 @@ void setPwmFrequency(uint8_t pin, int val)
|
||||||
#if defined(TCCR2A)
|
#if defined(TCCR2A)
|
||||||
case TIMER2A:
|
case TIMER2A:
|
||||||
case TIMER2B:
|
case TIMER2B:
|
||||||
TCCR2B &= ~(CS20 | CS21 | CS22);
|
TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22));
|
||||||
TCCR2B |= val;
|
TCCR2B |= val;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1913,7 +1913,7 @@ void setPwmFrequency(uint8_t pin, int val)
|
||||||
case TIMER3A:
|
case TIMER3A:
|
||||||
case TIMER3B:
|
case TIMER3B:
|
||||||
case TIMER3C:
|
case TIMER3C:
|
||||||
TCCR3B &= ~(CS30 | CS31 | CS32);
|
TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32));
|
||||||
TCCR3B |= val;
|
TCCR3B |= val;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1922,7 +1922,7 @@ void setPwmFrequency(uint8_t pin, int val)
|
||||||
case TIMER4A:
|
case TIMER4A:
|
||||||
case TIMER4B:
|
case TIMER4B:
|
||||||
case TIMER4C:
|
case TIMER4C:
|
||||||
TCCR4B &= ~(CS40 | CS41 | CS42);
|
TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42));
|
||||||
TCCR4B |= val;
|
TCCR4B |= val;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -1931,7 +1931,7 @@ void setPwmFrequency(uint8_t pin, int val)
|
||||||
case TIMER5A:
|
case TIMER5A:
|
||||||
case TIMER5B:
|
case TIMER5B:
|
||||||
case TIMER5C:
|
case TIMER5C:
|
||||||
TCCR5B &= ~(CS50 | CS51 | CS52);
|
TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52));
|
||||||
TCCR5B |= val;
|
TCCR5B |= val;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -527,14 +527,15 @@ void CardReader::updir()
|
||||||
|
|
||||||
void CardReader::printingHasFinished()
|
void CardReader::printingHasFinished()
|
||||||
{
|
{
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
quickStop();
|
quickStop();
|
||||||
sdprinting = false;
|
file.close();
|
||||||
if(SD_FINISHED_STEPPERRELEASE)
|
sdprinting = false;
|
||||||
{
|
if(SD_FINISHED_STEPPERRELEASE)
|
||||||
//finishAndDisableSteppers();
|
{
|
||||||
enquecommand_P(PSTR(SD_FINISHED_RELEASECOMMAND));
|
//finishAndDisableSteppers();
|
||||||
}
|
enquecommand_P(PSTR(SD_FINISHED_RELEASECOMMAND));
|
||||||
autotempShutdown();
|
}
|
||||||
|
autotempShutdown();
|
||||||
}
|
}
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
|
|
|
@ -35,10 +35,11 @@ public:
|
||||||
void setroot();
|
void setroot();
|
||||||
|
|
||||||
|
|
||||||
|
FORCE_INLINE bool isFileOpen() { return file.isOpen(); }
|
||||||
FORCE_INLINE bool eof() { return sdpos>=filesize ;};
|
FORCE_INLINE bool eof() { return sdpos>=filesize ;};
|
||||||
FORCE_INLINE int16_t get() { sdpos = file.curPosition();return (int16_t)file.read();};
|
FORCE_INLINE int16_t get() { sdpos = file.curPosition();return (int16_t)file.read();};
|
||||||
FORCE_INLINE void setIndex(long index) {sdpos = index;file.seekSet(index);};
|
FORCE_INLINE void setIndex(long index) {sdpos = index;file.seekSet(index);};
|
||||||
FORCE_INLINE uint8_t percentDone(){if(!sdprinting) return 0; if(filesize) return sdpos/((filesize+99)/100); else return 0;};
|
FORCE_INLINE uint8_t percentDone(){if(!isFileOpen()) return 0; if(filesize) return sdpos/((filesize+99)/100); else return 0;};
|
||||||
FORCE_INLINE char* getWorkDirName(){workDir.getFilename(filename);return filename;};
|
FORCE_INLINE char* getWorkDirName(){workDir.getFilename(filename);return filename;};
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -16,7 +16,9 @@
|
||||||
// 7 Italian
|
// 7 Italian
|
||||||
// 8 Portuguese
|
// 8 Portuguese
|
||||||
|
|
||||||
|
#ifndef LANGUAGE_CHOICE
|
||||||
#define LANGUAGE_CHOICE 1 // Pick your language from the list above
|
#define LANGUAGE_CHOICE 1 // Pick your language from the list above
|
||||||
|
#endif
|
||||||
|
|
||||||
#define PROTOCOL_VERSION "1.0"
|
#define PROTOCOL_VERSION "1.0"
|
||||||
|
|
||||||
|
@ -37,88 +39,78 @@
|
||||||
#define WELCOME_MSG MACHINE_NAME " Ready."
|
#define WELCOME_MSG MACHINE_NAME " Ready."
|
||||||
#define MSG_SD_INSERTED "Card inserted"
|
#define MSG_SD_INSERTED "Card inserted"
|
||||||
#define MSG_SD_REMOVED "Card removed"
|
#define MSG_SD_REMOVED "Card removed"
|
||||||
#define MSG_MAIN " Main \003"
|
#define MSG_MAIN "Main"
|
||||||
#define MSG_AUTOSTART " Autostart"
|
#define MSG_AUTOSTART "Autostart"
|
||||||
#define MSG_DISABLE_STEPPERS " Disable Steppers"
|
#define MSG_DISABLE_STEPPERS "Disable Steppers"
|
||||||
#define MSG_AUTO_HOME " Auto Home"
|
#define MSG_AUTO_HOME "Auto Home"
|
||||||
#define MSG_SET_ORIGIN " Set Origin"
|
#define MSG_SET_ORIGIN "Set Origin"
|
||||||
#define MSG_PREHEAT_PLA " Preheat PLA"
|
#define MSG_PREHEAT_PLA "Preheat PLA"
|
||||||
#define MSG_PREHEAT_PLA_SETTINGS " Preheat PLA Setting"
|
#define MSG_PREHEAT_PLA_SETTINGS "Preheat PLA Conf"
|
||||||
#define MSG_PREHEAT_ABS " Preheat ABS"
|
#define MSG_PREHEAT_ABS "Preheat ABS"
|
||||||
#define MSG_PREHEAT_ABS_SETTINGS " Preheat ABS Setting"
|
#define MSG_PREHEAT_ABS_SETTINGS "Preheat ABS Conf"
|
||||||
#define MSG_COOLDOWN " Cooldown"
|
#define MSG_COOLDOWN "Cooldown"
|
||||||
#define MSG_EXTRUDE " Extrude"
|
#define MSG_EXTRUDE "Extrude"
|
||||||
#define MSG_RETRACT " Retract"
|
#define MSG_RETRACT "Retract"
|
||||||
#define MSG_PREHEAT_PLA " Preheat PLA"
|
#define MSG_MOVE_AXIS "Move Axis"
|
||||||
#define MSG_PREHEAT_ABS " Preheat ABS"
|
#define MSG_SPEED "Speed"
|
||||||
#define MSG_MOVE_AXIS " Move Axis \x7E"
|
#define MSG_NOZZLE "Nozzle"
|
||||||
#define MSG_SPEED " Speed:"
|
#define MSG_NOZZLE1 "Nozzle2"
|
||||||
#define MSG_NOZZLE " \002Nozzle:"
|
#define MSG_NOZZLE2 "Nozzle3"
|
||||||
#define MSG_NOZZLE1 " \002Nozzle2:"
|
#define MSG_BED "Bed"
|
||||||
#define MSG_NOZZLE2 " \002Nozzle3:"
|
#define MSG_FAN_SPEED "Fan speed"
|
||||||
#define MSG_BED " \002Bed:"
|
#define MSG_FLOW "Flow"
|
||||||
#define MSG_FAN_SPEED " Fan speed:"
|
#define MSG_CONTROL "Control"
|
||||||
#define MSG_FLOW " Flow:"
|
#define MSG_MIN " \002 Min"
|
||||||
#define MSG_CONTROL " Control \003"
|
#define MSG_MAX " \002 Max"
|
||||||
#define MSG_MIN " \002 Min:"
|
#define MSG_FACTOR " \002 Fact"
|
||||||
#define MSG_MAX " \002 Max:"
|
#define MSG_AUTOTEMP "Autotemp"
|
||||||
#define MSG_FACTOR " \002 Fact:"
|
|
||||||
#define MSG_AUTOTEMP " Autotemp:"
|
|
||||||
#define MSG_ON "On "
|
#define MSG_ON "On "
|
||||||
#define MSG_OFF "Off"
|
#define MSG_OFF "Off"
|
||||||
#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_PID_C " PID-C: "
|
#define MSG_PID_C "PID-C"
|
||||||
#define MSG_ACC " Acc:"
|
#define MSG_ACC "Accel"
|
||||||
#define MSG_VXY_JERK " Vxy-jerk: "
|
#define MSG_VXY_JERK "Vxy-jerk"
|
||||||
#define MSG_VMAX " Vmax "
|
#define MSG_VMAX "Vmax "
|
||||||
#define MSG_X "x:"
|
#define MSG_X "x"
|
||||||
#define MSG_Y "y:"
|
#define MSG_Y "y"
|
||||||
#define MSG_Z "z:"
|
#define MSG_Z "z"
|
||||||
#define MSG_E "e:"
|
#define MSG_E "e"
|
||||||
#define MSG_VMIN " Vmin:"
|
#define MSG_VMIN "Vmin"
|
||||||
#define MSG_VTRAV_MIN " VTrav min:"
|
#define MSG_VTRAV_MIN "VTrav min"
|
||||||
#define MSG_AMAX " Amax "
|
#define MSG_AMAX "Amax "
|
||||||
#define MSG_A_RETRACT " A-retract:"
|
#define MSG_A_RETRACT "A-retract"
|
||||||
#define MSG_XSTEPS " Xsteps/mm:"
|
#define MSG_XSTEPS "Xsteps/mm"
|
||||||
#define MSG_YSTEPS " Ysteps/mm:"
|
#define MSG_YSTEPS "Ysteps/mm"
|
||||||
#define MSG_ZSTEPS " Zsteps/mm:"
|
#define MSG_ZSTEPS "Zsteps/mm"
|
||||||
#define MSG_ESTEPS " Esteps/mm:"
|
#define MSG_ESTEPS "Esteps/mm"
|
||||||
#define MSG_MAIN_WIDE " Main \003"
|
#define MSG_RECTRACT "Rectract"
|
||||||
#define MSG_RECTRACT_WIDE " Rectract \x7E"
|
#define MSG_TEMPERATURE "Temperature"
|
||||||
#define MSG_TEMPERATURE_WIDE " Temperature \x7E"
|
#define MSG_MOTION "Motion"
|
||||||
#define MSG_TEMPERATURE_RTN " Temperature \003"
|
#define MSG_STORE_EPROM "Store memory"
|
||||||
#define MSG_MOTION_WIDE " Motion \x7E"
|
#define MSG_LOAD_EPROM "Load memory"
|
||||||
#define MSG_STORE_EPROM " Store memory"
|
#define MSG_RESTORE_FAILSAFE "Restore Failsafe"
|
||||||
#define MSG_LOAD_EPROM " Load memory"
|
#define MSG_REFRESH "Refresh"
|
||||||
#define MSG_RESTORE_FAILSAFE " Restore Failsafe"
|
#define MSG_WATCH "Watch"
|
||||||
#define MSG_REFRESH "\004Refresh"
|
#define MSG_PREPARE "Prepare"
|
||||||
#define MSG_WATCH " Watch \003"
|
#define MSG_TUNE "Tune"
|
||||||
#define MSG_PREPARE " Prepare \x7E"
|
#define MSG_PAUSE_PRINT "Pause Print"
|
||||||
#define MSG_PREPARE_ALT " Prepare \003"
|
#define MSG_RESUME_PRINT "Resume Print"
|
||||||
#define MSG_CONTROL_ARROW " Control \x7E"
|
#define MSG_STOP_PRINT "Stop Print"
|
||||||
#define MSG_RETRACT_ARROW " Retract \x7E"
|
#define MSG_CARD_MENU "Card Menu"
|
||||||
#define MSG_TUNE " Tune \x7E"
|
#define MSG_NO_CARD "No Card"
|
||||||
#define MSG_PAUSE_PRINT " Pause Print \x7E"
|
|
||||||
#define MSG_RESUME_PRINT " Resume Print \x7E"
|
|
||||||
#define MSG_STOP_PRINT " Stop Print \x7E"
|
|
||||||
#define MSG_CARD_MENU " Card Menu \x7E"
|
|
||||||
#define MSG_NO_CARD " No Card"
|
|
||||||
#define MSG_DWELL "Sleep..."
|
#define MSG_DWELL "Sleep..."
|
||||||
#define MSG_USERWAIT "Wait for user..."
|
#define MSG_USERWAIT "Wait for user..."
|
||||||
#define MSG_NO_MOVE "No move."
|
#define MSG_NO_MOVE "No move."
|
||||||
#define MSG_PART_RELEASE "Partial Release"
|
|
||||||
#define MSG_KILLED "KILLED. "
|
#define MSG_KILLED "KILLED. "
|
||||||
#define MSG_STOPPED "STOPPED. "
|
#define MSG_STOPPED "STOPPED. "
|
||||||
#define MSG_STEPPER_RELEASED "Released."
|
#define MSG_CONTROL_RETRACT "Retract mm"
|
||||||
#define MSG_CONTROL_RETRACT " Retract mm:"
|
#define MSG_CONTROL_RETRACTF "Retract F"
|
||||||
#define MSG_CONTROL_RETRACTF " Retract F:"
|
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
|
||||||
#define MSG_CONTROL_RETRACT_ZLIFT " Hop mm:"
|
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVER " UnRet +mm:"
|
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet F"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVERF " UnRet F:"
|
#define MSG_AUTORETRACT "AutoRetr."
|
||||||
#define MSG_AUTORETRACT " AutoRetr.:"
|
|
||||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Something is wrong in the MenuStructure."
|
|
||||||
|
|
||||||
// Serial Console Messages
|
// Serial Console Messages
|
||||||
|
|
||||||
|
@ -198,72 +190,68 @@
|
||||||
#define WELCOME_MSG MACHINE_NAME " Gotowe."
|
#define WELCOME_MSG MACHINE_NAME " Gotowe."
|
||||||
#define MSG_SD_INSERTED "Karta wlozona"
|
#define MSG_SD_INSERTED "Karta wlozona"
|
||||||
#define MSG_SD_REMOVED "Karta usunieta"
|
#define MSG_SD_REMOVED "Karta usunieta"
|
||||||
#define MSG_MAIN " Menu \003"
|
#define MSG_MAIN "Main"
|
||||||
#define MSG_AUTOSTART " Autostart"
|
#define MSG_AUTOSTART "Autostart"
|
||||||
#define MSG_DISABLE_STEPPERS " Wylacz silniki"
|
#define MSG_DISABLE_STEPPERS "Wylacz silniki"
|
||||||
#define MSG_AUTO_HOME " Auto. poz. zerowa"
|
#define MSG_AUTO_HOME "Auto. poz. zerowa"
|
||||||
#define MSG_SET_ORIGIN " Ustaw punkt zerowy"
|
#define MSG_SET_ORIGIN "Ustaw punkt zerowy"
|
||||||
#define MSG_PREHEAT_PLA " Rozgrzej PLA"
|
#define MSG_PREHEAT_PLA "Rozgrzej PLA"
|
||||||
#define MSG_PREHEAT_PLA_SETTINGS " Ustawienia roz. PLA"
|
#define MSG_PREHEAT_PLA_SETTINGS "Ustawienia roz. PLA"
|
||||||
#define MSG_PREHEAT_ABS " Rozgrzej ABS"
|
#define MSG_PREHEAT_ABS "Rozgrzej ABS"
|
||||||
#define MSG_PREHEAT_ABS_SETTINGS " Ustawienia roz. ABS"
|
#define MSG_PREHEAT_ABS_SETTINGS "Ustawienia roz. ABS"
|
||||||
#define MSG_COOLDOWN " Chlodzenie"
|
#define MSG_COOLDOWN "Chlodzenie"
|
||||||
#define MSG_EXTRUDE " Ekstruzja"
|
#define MSG_EXTRUDE "Ekstruzja"
|
||||||
#define MSG_RETRACT " Cofanie"
|
#define MSG_RETRACT "Cofanie"
|
||||||
#define MSG_MOVE_AXIS " Ruch osi \x7E"
|
#define MSG_MOVE_AXIS "Ruch osi"
|
||||||
#define MSG_SPEED " Predkosc:"
|
#define MSG_SPEED "Predkosc"
|
||||||
#define MSG_NOZZLE " \002Dysza:"
|
#define MSG_NOZZLE "Dysza"
|
||||||
#define MSG_NOZZLE1 " \002Dysza2:"
|
#define MSG_NOZZLE1 "Dysza2"
|
||||||
#define MSG_NOZZLE2 " \002Dysza3:"
|
#define MSG_NOZZLE2 "Dysza3"
|
||||||
#define MSG_BED " \002Loze:"
|
#define MSG_BED "Loze"
|
||||||
#define MSG_FAN_SPEED " Obroty wiatraka:"
|
#define MSG_FAN_SPEED "Obroty wiatraka"
|
||||||
#define MSG_FLOW " Przeplyw:"
|
#define MSG_FLOW "Przeplyw"
|
||||||
#define MSG_CONTROL " Kontrola \003"
|
#define MSG_CONTROL "Kontrola"
|
||||||
#define MSG_MIN " \002 Min:"
|
#define MSG_MIN " \002 Min"
|
||||||
#define MSG_MAX " \002 Max:"
|
#define MSG_MAX " \002 Max"
|
||||||
#define MSG_FACTOR " \002 Mnoznik:"
|
#define MSG_FACTOR " \002 Mnoznik"
|
||||||
#define MSG_AUTOTEMP " Auto. temp.:"
|
#define MSG_AUTOTEMP "Auto. temp."
|
||||||
#define MSG_ON "Wl. "
|
#define MSG_ON "Wl. "
|
||||||
#define MSG_OFF "Wyl."
|
#define MSG_OFF "Wyl."
|
||||||
#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_PID_C " PID-C: "
|
#define MSG_PID_C "PID-C"
|
||||||
#define MSG_ACC " Acc:"
|
#define MSG_ACC "Acc"
|
||||||
#define MSG_VXY_JERK " Zryw Vxy: "
|
#define MSG_VXY_JERK "Zryw Vxy"
|
||||||
#define MSG_VMAX " Vmax "
|
#define MSG_VMAX "Vmax"
|
||||||
#define MSG_X "x:"
|
#define MSG_X "x"
|
||||||
#define MSG_Y "y:"
|
#define MSG_Y "y"
|
||||||
#define MSG_Z "z:"
|
#define MSG_Z "z"
|
||||||
#define MSG_E "e:"
|
#define MSG_E "e"
|
||||||
#define MSG_VMIN " Vmin:"
|
#define MSG_VMIN "Vmin"
|
||||||
#define MSG_VTRAV_MIN " Vskok min:"
|
#define MSG_VTRAV_MIN "Vskok min"
|
||||||
#define MSG_AMAX " Amax "
|
#define MSG_AMAX "Amax"
|
||||||
#define MSG_A_RETRACT " A-wycofanie:"
|
#define MSG_A_RETRACT "A-wycofanie"
|
||||||
#define MSG_XSTEPS " krokiX/mm:"
|
#define MSG_XSTEPS "krokiX/mm"
|
||||||
#define MSG_YSTEPS " krokiY/mm:"
|
#define MSG_YSTEPS "krokiY/mm"
|
||||||
#define MSG_ZSTEPS " krokiZ/mm:"
|
#define MSG_ZSTEPS "krokiZ/mm"
|
||||||
#define MSG_ESTEPS " krokiE/mm:"
|
#define MSG_ESTEPS "krokiE/mm"
|
||||||
#define MSG_MAIN_WIDE " Menu \003"
|
#define MSG_RECTRACT "Wycofanie"
|
||||||
#define MSG_RECTRACT_WIDE " Wycofanie \x7E"
|
#define MSG_TEMPERATURE "Temperatura"
|
||||||
#define MSG_TEMPERATURE_WIDE " Temperatura \x7E"
|
#define MSG_MOTION "Ruch"
|
||||||
#define MSG_TEMPERATURE_RTN " Temperatura \003"
|
#define MSG_STORE_EPROM "Zapisz w pamieci"
|
||||||
#define MSG_MOTION_WIDE " Ruch \x7E"
|
#define MSG_LOAD_EPROM "Wczytaj z pamieci"
|
||||||
#define MSG_STORE_EPROM " Zapisz w pamieci"
|
|
||||||
#define MSG_LOAD_EPROM " Wczytaj z pamieci"
|
|
||||||
#define MSG_RESTORE_FAILSAFE " Ustawienia fabryczne"
|
#define MSG_RESTORE_FAILSAFE " Ustawienia fabryczne"
|
||||||
#define MSG_REFRESH "\004Odswiez"
|
#define MSG_REFRESH "\004Odswiez"
|
||||||
#define MSG_WATCH " Obserwuj \003"
|
#define MSG_WATCH "Obserwuj"
|
||||||
#define MSG_PREPARE " Przygotuj \x7E"
|
#define MSG_PREPARE "Przygotuj"
|
||||||
#define MSG_PREPARE_ALT " Przygotuj \003"
|
#define MSG_CONTROL "Kontroluj"
|
||||||
#define MSG_CONTROL_ARROW " Kontroluj \x7E"
|
#define MSG_TUNE "Strojenie"
|
||||||
#define MSG_RETRACT_ARROW " Wycofaj \x7E"
|
#define MSG_PAUSE_PRINT "Pauza"
|
||||||
#define MSG_TUNE "Strojenie\x7E"
|
#define MSG_RESUME_PRINT "Wznowienie"
|
||||||
#define MSG_PAUSE_PRINT " Pauza \x7E"
|
#define MSG_STOP_PRINT "Stop"
|
||||||
#define MSG_RESUME_PRINT " Wznowienie \x7E"
|
#define MSG_CARD_MENU "Menu SDCard"
|
||||||
#define MSG_STOP_PRINT " Stop \x7E"
|
#define MSG_NO_CARD "Brak karty"
|
||||||
#define MSG_CARD_MENU " Menu SDCard \x7E"
|
|
||||||
#define MSG_NO_CARD " Brak karty"
|
|
||||||
#define MSG_DWELL "Uspij..."
|
#define MSG_DWELL "Uspij..."
|
||||||
#define MSG_USERWAIT "Czekaj na uzytkownika..."
|
#define MSG_USERWAIT "Czekaj na uzytkownika..."
|
||||||
#define MSG_NO_MOVE "Brak ruchu."
|
#define MSG_NO_MOVE "Brak ruchu."
|
||||||
|
@ -271,13 +259,12 @@
|
||||||
#define MSG_KILLED "Ubity. "
|
#define MSG_KILLED "Ubity. "
|
||||||
#define MSG_STOPPED "Zatrzymany. "
|
#define MSG_STOPPED "Zatrzymany. "
|
||||||
#define MSG_STEPPER_RELEASED "Zwolniony."
|
#define MSG_STEPPER_RELEASED "Zwolniony."
|
||||||
#define MSG_CONTROL_RETRACT " Wycofaj mm:"
|
#define MSG_CONTROL_RETRACT "Wycofaj mm"
|
||||||
#define MSG_CONTROL_RETRACTF " Wycofaj F:"
|
#define MSG_CONTROL_RETRACTF "Wycofaj F"
|
||||||
#define MSG_CONTROL_RETRACT_ZLIFT " Skok Z mm:"
|
#define MSG_CONTROL_RETRACT_ZLIFT "Skok Z mm:"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVER " Cof. wycof. +mm:"
|
#define MSG_CONTROL_RETRACT_RECOVER "Cof. wycof. +mm"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVERF " Cof. wycof. F:"
|
#define MSG_CONTROL_RETRACT_RECOVERF "Cof. wycof. F"
|
||||||
#define MSG_AUTORETRACT " Auto. wycofanie:"
|
#define MSG_AUTORETRACT "Auto. wycofanie"
|
||||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Cos jest nie tak ze struktura menu."
|
|
||||||
|
|
||||||
// Serial Console Messages
|
// Serial Console Messages
|
||||||
|
|
||||||
|
@ -437,7 +424,6 @@
|
||||||
#define MSG_CONTROL_RETRACT_RECOVER " UnRet +mm:"
|
#define MSG_CONTROL_RETRACT_RECOVER " UnRet +mm:"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVERF " UnRet F:"
|
#define MSG_CONTROL_RETRACT_RECOVERF " UnRet F:"
|
||||||
#define MSG_AUTORETRACT " Retract. Auto.:"
|
#define MSG_AUTORETRACT " Retract. Auto.:"
|
||||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Erreur avec MenuStructure."
|
|
||||||
|
|
||||||
// Serial Console Messages
|
// Serial Console Messages
|
||||||
|
|
||||||
|
@ -519,71 +505,68 @@
|
||||||
|
|
||||||
#define MSG_SD_INSERTED "SDKarte erkannt"
|
#define MSG_SD_INSERTED "SDKarte erkannt"
|
||||||
#define MSG_SD_REMOVED "SDKarte entfernt"
|
#define MSG_SD_REMOVED "SDKarte entfernt"
|
||||||
#define MSG_MAIN " Hauptmneü \003"
|
#define MSG_MAIN "Hauptmneü"
|
||||||
#define MSG_AUTOSTART " Autostart"
|
#define MSG_AUTOSTART "Autostart"
|
||||||
#define MSG_DISABLE_STEPPERS " Stepper abschalten"
|
#define MSG_DISABLE_STEPPERS "Stepper abschalten"
|
||||||
#define MSG_AUTO_HOME " Auto Nullpunkt"
|
#define MSG_AUTO_HOME "Auto Nullpunkt"
|
||||||
#define MSG_SET_ORIGIN " Setze Nullpunkt"
|
#define MSG_SET_ORIGIN "Setze Nullpunkt"
|
||||||
#define MSG_PREHEAT_PLA " Vorwärmen PLA"
|
#define MSG_PREHEAT_PLA "Vorwärmen PLA"
|
||||||
#define MSG_PREHEAT_PLA_SETTINGS " Vorwärmen PLA Einstellungen"
|
#define MSG_PREHEAT_PLA_SETTINGS "Vorwärmen PLA Einstellungen"
|
||||||
#define MSG_PREHEAT_ABS " Vorwärmen ABS"
|
#define MSG_PREHEAT_ABS "Vorwärmen ABS"
|
||||||
#define MSG_PREHEAT_ABS_SETTINGS " Vorwärmen ABS Einstellungen"
|
#define MSG_PREHEAT_ABS_SETTINGS "Vorwärmen ABS Einstellungen"
|
||||||
#define MSG_COOLDOWN " Abkühlen"
|
#define MSG_COOLDOWN "Abkühlen"
|
||||||
#define MSG_EXTRUDE " Extrude"
|
#define MSG_EXTRUDE "Extrude"
|
||||||
#define MSG_RETRACT " Retract"
|
#define MSG_RETRACT "Retract"
|
||||||
#define MSG_MOVE_AXIS " Achsen bewegen\x7E"
|
#define MSG_MOVE_AXIS "Achsen bewegen"
|
||||||
#define MSG_SPEED " Geschw:"
|
#define MSG_SPEED "Geschw"
|
||||||
#define MSG_NOZZLE " \002Düse:"
|
#define MSG_NOZZLE "Düse"
|
||||||
#define MSG_NOZZLE1 " \002Düse2:"
|
#define MSG_NOZZLE1 "Düse2"
|
||||||
#define MSG_NOZZLE2 " \002Düse3:"
|
#define MSG_NOZZLE2 "Düse3"
|
||||||
#define MSG_BED " \002Bett:"
|
#define MSG_BED "Bett"
|
||||||
#define MSG_FAN_SPEED " Lüftergeschw.:"
|
#define MSG_FAN_SPEED "Lüftergeschw."
|
||||||
#define MSG_FLOW " Fluß:"
|
#define MSG_FLOW "Fluß"
|
||||||
#define MSG_CONTROL " Einstellungen \003"
|
#define MSG_CONTROL "Einstellungen"
|
||||||
#define MSG_MIN " \002 Min:"
|
#define MSG_MIN "\002 Min"
|
||||||
#define MSG_MAX " \002 Max:"
|
#define MSG_MAX "\002 Max"
|
||||||
#define MSG_FACTOR " \002 Faktor:"
|
#define MSG_FACTOR "\002 Faktor"
|
||||||
#define MSG_AUTOTEMP " AutoTemp:"
|
#define MSG_AUTOTEMP "AutoTemp"
|
||||||
#define MSG_ON "Ein "
|
#define MSG_ON "Ein"
|
||||||
#define MSG_OFF "Aus "
|
#define MSG_OFF "Aus"
|
||||||
#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_PID_C " PID-C: "
|
#define MSG_PID_C "PID-C"
|
||||||
#define MSG_ACC " Acc:"
|
#define MSG_ACC "Acc"
|
||||||
#define MSG_VXY_JERK " Vxy-jerk: "
|
#define MSG_VXY_JERK "Vxy-jerk"
|
||||||
#define MSG_VMAX " Vmax "
|
#define MSG_VMAX "Vmax "
|
||||||
#define MSG_X "x:"
|
#define MSG_X "x"
|
||||||
#define MSG_Y "y:"
|
#define MSG_Y "y"
|
||||||
#define MSG_Z "z:"
|
#define MSG_Z "z"
|
||||||
#define MSG_E "e:"
|
#define MSG_E "e"
|
||||||
#define MSG_VMIN " Vmin:"
|
#define MSG_VMIN "Vmin"
|
||||||
#define MSG_VTRAV_MIN " VTrav min:"
|
#define MSG_VTRAV_MIN "VTrav min"
|
||||||
#define MSG_AMAX " Amax "
|
#define MSG_AMAX "Amax "
|
||||||
#define MSG_A_RETRACT " A-Retract:"
|
#define MSG_A_RETRACT "A-Retract"
|
||||||
#define MSG_XSTEPS " Xsteps/mm:"
|
#define MSG_XSTEPS "Xsteps/mm"
|
||||||
#define MSG_YSTEPS " Ysteps/mm:"
|
#define MSG_YSTEPS "Ysteps/mm"
|
||||||
#define MSG_ZSTEPS " Zsteps/mm:"
|
#define MSG_ZSTEPS "Zsteps/mm"
|
||||||
#define MSG_ESTEPS " Esteps/mm:"
|
#define MSG_ESTEPS "Esteps/mm"
|
||||||
#define MSG_MAIN_WIDE " Hauptmenü \003"
|
#define MSG_RECTRACT_WIDE "Rectract"
|
||||||
#define MSG_RECTRACT_WIDE " Rectract \x7E"
|
#define MSG_WATCH "Beobachten"
|
||||||
#define MSG_WATCH " Beobachten \003"
|
#define MSG_TEMPERATURE "Temperatur"
|
||||||
#define MSG_TEMPERATURE_WIDE " Temperatur \x7E"
|
#define MSG_MOTION "Bewegung"
|
||||||
#define MSG_TEMPERATURE_RTN " Temperatur \003"
|
#define MSG_STORE_EPROM "EPROM speichern"
|
||||||
#define MSG_MOTION_WIDE " Bewegung \x7E"
|
#define MSG_LOAD_EPROM "EPROM laden"
|
||||||
#define MSG_STORE_EPROM " EPROM speichern"
|
#define MSG_RESTORE_FAILSAFE "Standardkonfig."
|
||||||
#define MSG_LOAD_EPROM " EPROM laden"
|
#define MSG_REFRESH "Aktualisieren"
|
||||||
#define MSG_RESTORE_FAILSAFE " Standardkonfig."
|
#define MSG_PREPARE "Vorbereitung"
|
||||||
#define MSG_REFRESH "\004Aktualisieren"
|
#define MSG_CONTROL "Einstellungen"
|
||||||
#define MSG_PREPARE " Vorbereitung \x7E"
|
#define MSG_TUNE "Justierung"
|
||||||
#define MSG_PREPARE_ALT " Vorbereitung \003"
|
#define MSG_PAUSE_PRINT "Druck anhalten"
|
||||||
#define MSG_CONTROL_ARROW " Einstellungen \x7E"
|
#define MSG_RESUME_PRINT "Druck fortsetz"
|
||||||
#define MSG_TUNE " Justierung \x7E"
|
#define MSG_STOP_PRINT "Druck stoppen"
|
||||||
#define MSG_PAUSE_PRINT " Druck anhalten\x7E"
|
#define MSG_CARD_MENU "SDKarten Menü"
|
||||||
#define MSG_RESUME_PRINT " Druck fortsetz\x7E"
|
#define MSG_NO_CARD "Keine SDKarte"
|
||||||
#define MSG_STOP_PRINT " Druck stoppen \x7E"
|
|
||||||
#define MSG_CARD_MENU " SDKarten Menü \x7E"
|
|
||||||
#define MSG_NO_CARD " Keine SDKarte"
|
|
||||||
#define MSG_DWELL "Warten..."
|
#define MSG_DWELL "Warten..."
|
||||||
#define MSG_USERWAIT "Warte auf Nutzer..."
|
#define MSG_USERWAIT "Warte auf Nutzer..."
|
||||||
#define MSG_NO_MOVE "Kein Zug."
|
#define MSG_NO_MOVE "Kein Zug."
|
||||||
|
@ -591,13 +574,12 @@
|
||||||
#define MSG_KILLED "KILLED"
|
#define MSG_KILLED "KILLED"
|
||||||
#define MSG_STOPPED "GESTOPPT"
|
#define MSG_STOPPED "GESTOPPT"
|
||||||
#define MSG_STEPPER_RELEASED "Stepper frei"
|
#define MSG_STEPPER_RELEASED "Stepper frei"
|
||||||
#define MSG_CONTROL_RETRACT " Retract mm:"
|
#define MSG_CONTROL_RETRACT "Retract mm"
|
||||||
#define MSG_CONTROL_RETRACTF " Retract F:"
|
#define MSG_CONTROL_RETRACTF "Retract F"
|
||||||
#define MSG_CONTROL_RETRACT_ZLIFT " Hop mm:"
|
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVER " UnRet +mm:"
|
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVERF " UnRet F:"
|
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet F"
|
||||||
#define MSG_AUTORETRACT " AutoRetr.:"
|
#define MSG_AUTORETRACT "AutoRetr."
|
||||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Fehler in Menüstruktur."
|
|
||||||
|
|
||||||
// Serial Console Messages
|
// Serial Console Messages
|
||||||
|
|
||||||
|
@ -756,7 +738,6 @@
|
||||||
#define MSG_CONTROL_RETRACT_RECOVER " DesRet +mm:"
|
#define MSG_CONTROL_RETRACT_RECOVER " DesRet +mm:"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVERF " DesRet F:"
|
#define MSG_CONTROL_RETRACT_RECOVERF " DesRet F:"
|
||||||
#define MSG_AUTORETRACT " AutoRetr.:"
|
#define MSG_AUTORETRACT " AutoRetr.:"
|
||||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Hay un error en la estructura del menu"
|
|
||||||
|
|
||||||
// Serial Console Messages
|
// Serial Console Messages
|
||||||
|
|
||||||
|
@ -831,7 +812,7 @@
|
||||||
#if LANGUAGE_CHOICE == 6
|
#if LANGUAGE_CHOICE == 6
|
||||||
|
|
||||||
// LCD Menu Messages
|
// LCD Menu Messages
|
||||||
#define WELCOME_MSG MACHINE_NAME " Готов."
|
#define WELCOME_MSG MACHINE_NAME " Готов"
|
||||||
#define MSG_SD_INSERTED "Карта вставлена"
|
#define MSG_SD_INSERTED "Карта вставлена"
|
||||||
#define MSG_SD_REMOVED "Карта извлечена"
|
#define MSG_SD_REMOVED "Карта извлечена"
|
||||||
#define MSG_MAIN " Меню \003"
|
#define MSG_MAIN " Меню \003"
|
||||||
|
@ -880,21 +861,16 @@
|
||||||
#define MSG_YSTEPS " Y шаг/mm:"
|
#define MSG_YSTEPS " Y шаг/mm:"
|
||||||
#define MSG_ZSTEPS " Z шаг/mm:"
|
#define MSG_ZSTEPS " Z шаг/mm:"
|
||||||
#define MSG_ESTEPS " E шаг/mm:"
|
#define MSG_ESTEPS " E шаг/mm:"
|
||||||
#define MSG_MAIN_WIDE " Меню \003"
|
#define MSG_RECTRACT " Откат подачи \x7E"
|
||||||
#define MSG_RECTRACT_WIDE " Откат подачи \x7E"
|
#define MSG_TEMPERATURE " Температура \x7E"
|
||||||
#define MSG_TEMPERATURE_WIDE " Температура \x7E"
|
#define MSG_MOTION " Скорости \x7E"
|
||||||
#define MSG_TEMPERATURE_RTN " Температура \003"
|
|
||||||
#define MSG_MOTION_WIDE " Скорости \x7E"
|
|
||||||
#define MSG_STORE_EPROM " Сохранить настройки"
|
#define MSG_STORE_EPROM " Сохранить настройки"
|
||||||
#define MSG_LOAD_EPROM " Загрузить настройки"
|
#define MSG_LOAD_EPROM " Загрузить настройки"
|
||||||
#define MSG_RESTORE_FAILSAFE " Сброс настроек "
|
#define MSG_RESTORE_FAILSAFE " Сброс настроек "
|
||||||
#define MSG_REFRESH "\004Обновить "
|
#define MSG_REFRESH "\004Обновить "
|
||||||
#define MSG_WATCH " Обзор \003"
|
#define MSG_WATCH " Обзор \003"
|
||||||
#define MSG_PREPARE " Действия \x7E"
|
#define MSG_PREPARE " Действия \x7E"
|
||||||
#define MSG_PREPARE_ALT " Действия \003"
|
#define MSG_TUNE " Настройки \x7E"
|
||||||
#define MSG_CONTROL_ARROW " Настройки \x7E"
|
|
||||||
#define MSG_RETRACT_ARROW " Настройки отката \x7E"
|
|
||||||
#define MSG_TUNE " Tune \x7E"
|
|
||||||
#define MSG_PAUSE_PRINT " Пауза печати \x7E"
|
#define MSG_PAUSE_PRINT " Пауза печати \x7E"
|
||||||
#define MSG_RESUME_PRINT " Продолжить печать \x7E"
|
#define MSG_RESUME_PRINT " Продолжить печать \x7E"
|
||||||
#define MSG_STOP_PRINT " Остановить печать \x7E"
|
#define MSG_STOP_PRINT " Остановить печать \x7E"
|
||||||
|
@ -906,14 +882,12 @@
|
||||||
#define MSG_PART_RELEASE " Извлечение принта "
|
#define MSG_PART_RELEASE " Извлечение принта "
|
||||||
#define MSG_KILLED "УБИТО. "
|
#define MSG_KILLED "УБИТО. "
|
||||||
#define MSG_STOPPED "ОСТАНОВЛЕНО. "
|
#define MSG_STOPPED "ОСТАНОВЛЕНО. "
|
||||||
#define MSG_STEPPER_RELEASED "Двигатели отключены."
|
|
||||||
#define MSG_CONTROL_RETRACT " Откат mm:"
|
#define MSG_CONTROL_RETRACT " Откат mm:"
|
||||||
#define MSG_CONTROL_RETRACTF " Откат F:"
|
#define MSG_CONTROL_RETRACTF " Откат F:"
|
||||||
#define MSG_CONTROL_RETRACT_ZLIFT " Прыжок mm:"
|
#define MSG_CONTROL_RETRACT_ZLIFT " Прыжок mm:"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVER " Возврат +mm:"
|
#define MSG_CONTROL_RETRACT_RECOVER " Возврат +mm:"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVERF " Возврат F:"
|
#define MSG_CONTROL_RETRACT_RECOVERF " Возврат F:"
|
||||||
#define MSG_AUTORETRACT " АвтоОткат:"
|
#define MSG_AUTORETRACT " АвтоОткат:"
|
||||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Ошибка в структуре меню."
|
|
||||||
|
|
||||||
// Serial Console Messages
|
// Serial Console Messages
|
||||||
|
|
||||||
|
@ -959,7 +933,9 @@
|
||||||
#define MSG_Y_MAX "y_max:"
|
#define MSG_Y_MAX "y_max:"
|
||||||
#define MSG_Z_MIN "z_min:"
|
#define MSG_Z_MIN "z_min:"
|
||||||
#define MSG_Z_MAX "z_max:"
|
#define MSG_Z_MAX "z_max:"
|
||||||
|
#define MSG_M119_REPORT "Статус концевиков"
|
||||||
|
#define MSG_ENDSTOP_HIT "Срабатывание концевика"
|
||||||
|
#define MSG_ENDSTOP_OPEN "Концевик освобожден"
|
||||||
#define MSG_SD_CANT_OPEN_SUBDIR "Не открыть папку"
|
#define MSG_SD_CANT_OPEN_SUBDIR "Не открыть папку"
|
||||||
#define MSG_SD_INIT_FAIL "Ошибка инициализации SD"
|
#define MSG_SD_INIT_FAIL "Ошибка инициализации SD"
|
||||||
#define MSG_SD_VOL_INIT_FAIL "Ошибка инициализации раздела"
|
#define MSG_SD_VOL_INIT_FAIL "Ошибка инициализации раздела"
|
||||||
|
@ -975,14 +951,10 @@
|
||||||
#define MSG_SD_NOT_PRINTING "нет SD печати"
|
#define MSG_SD_NOT_PRINTING "нет SD печати"
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "ошибка записи в файл"
|
#define MSG_SD_ERR_WRITE_TO_FILE "ошибка записи в файл"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Не зайти в папку:"
|
#define MSG_SD_CANT_ENTER_SUBDIR "Не зайти в папку:"
|
||||||
|
|
||||||
#define MSG_STEPPER_TO_HIGH "Частота шагов очень высока : "
|
#define MSG_STEPPER_TO_HIGH "Частота шагов очень высока : "
|
||||||
#define MSG_ENDSTOPS_HIT "концевик сработал: "
|
#define MSG_ENDSTOPS_HIT "концевик сработал: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " защита холодной экструзии"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " защита холодной экструзии"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " защита превышения длинны экструзии"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " защита превышения длинны экструзии"
|
||||||
#define MSG_M119_REPORT "Статус концевиков"
|
|
||||||
#define MSG_ENDSTOP_HIT "Срабатывание концевика"
|
|
||||||
#define MSG_ENDSTOP_OPEN "Концевик освобожден"
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
177
Marlin/pins.h
177
Marlin/pins.h
|
@ -19,20 +19,17 @@
|
||||||
#define X_STEP_PIN 2
|
#define X_STEP_PIN 2
|
||||||
#define X_DIR_PIN 3
|
#define X_DIR_PIN 3
|
||||||
#define X_ENABLE_PIN -1
|
#define X_ENABLE_PIN -1
|
||||||
#define X_MIN_PIN -1
|
#define X_STOP_PIN 16
|
||||||
#define X_MAX_PIN 16
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 5
|
#define Y_STEP_PIN 5
|
||||||
#define Y_DIR_PIN 6
|
#define Y_DIR_PIN 6
|
||||||
#define Y_ENABLE_PIN -1
|
#define Y_ENABLE_PIN -1
|
||||||
#define Y_MIN_PIN 67
|
#define Y_STOP_PIN 67
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 62
|
#define Z_STEP_PIN 62
|
||||||
#define Z_DIR_PIN 63
|
#define Z_DIR_PIN 63
|
||||||
#define Z_ENABLE_PIN -1
|
#define Z_ENABLE_PIN -1
|
||||||
#define Z_MIN_PIN 59
|
#define Z_STOP_PIN 59
|
||||||
#define Z_MAX_PIN -1
|
|
||||||
|
|
||||||
#define E0_STEP_PIN 65
|
#define E0_STEP_PIN 65
|
||||||
#define E0_DIR_PIN 66
|
#define E0_DIR_PIN 66
|
||||||
|
@ -83,15 +80,13 @@
|
||||||
#define X_STEP_PIN 19
|
#define X_STEP_PIN 19
|
||||||
#define X_DIR_PIN 18
|
#define X_DIR_PIN 18
|
||||||
#define X_ENABLE_PIN 24
|
#define X_ENABLE_PIN 24
|
||||||
#define X_MIN_PIN 7
|
#define X_STOP_PIN 7
|
||||||
#define X_MAX_PIN -1
|
|
||||||
|
|
||||||
//y axis pins
|
//y axis pins
|
||||||
#define Y_STEP_PIN 23
|
#define Y_STEP_PIN 23
|
||||||
#define Y_DIR_PIN 22
|
#define Y_DIR_PIN 22
|
||||||
#define Y_ENABLE_PIN 24
|
#define Y_ENABLE_PIN 24
|
||||||
#define Y_MIN_PIN 5
|
#define Y_STOP_PIN 5
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
//z axis pins
|
//z axis pins
|
||||||
#define Z_STEP_PIN 26
|
#define Z_STEP_PIN 26
|
||||||
|
@ -167,22 +162,19 @@
|
||||||
#define X_STEP_PIN 29
|
#define X_STEP_PIN 29
|
||||||
#define X_DIR_PIN 28
|
#define X_DIR_PIN 28
|
||||||
#define X_ENABLE_PIN 25
|
#define X_ENABLE_PIN 25
|
||||||
#define X_MIN_PIN 0
|
#define X_STOP_PIN 0
|
||||||
#define X_MAX_PIN -1
|
|
||||||
|
|
||||||
//y axis pins
|
//y axis pins
|
||||||
#define Y_STEP_PIN 27
|
#define Y_STEP_PIN 27
|
||||||
#define Y_DIR_PIN 26
|
#define Y_DIR_PIN 26
|
||||||
#define Y_ENABLE_PIN 25
|
#define Y_ENABLE_PIN 25
|
||||||
#define Y_MIN_PIN 1
|
#define Y_STOP_PIN 1
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
//z axis pins
|
//z axis pins
|
||||||
#define Z_STEP_PIN 23
|
#define Z_STEP_PIN 23
|
||||||
#define Z_DIR_PIN 22
|
#define Z_DIR_PIN 22
|
||||||
#define Z_ENABLE_PIN 25
|
#define Z_ENABLE_PIN 25
|
||||||
#define Z_MIN_PIN 2
|
#define Z_STOP_PIN 2
|
||||||
#define Z_MAX_PIN -1
|
|
||||||
|
|
||||||
//extruder pins
|
//extruder pins
|
||||||
#define E0_STEP_PIN 19
|
#define E0_STEP_PIN 19
|
||||||
|
@ -238,22 +230,19 @@
|
||||||
#define X_STEP_PIN 21 //different from stanard GEN7
|
#define X_STEP_PIN 21 //different from stanard GEN7
|
||||||
#define X_DIR_PIN 20 //different from stanard GEN7
|
#define X_DIR_PIN 20 //different from stanard GEN7
|
||||||
#define X_ENABLE_PIN 24
|
#define X_ENABLE_PIN 24
|
||||||
#define X_MIN_PIN 0
|
#define X_STOP_PIN 0
|
||||||
#define X_MAX_PIN -1
|
|
||||||
|
|
||||||
//y axis pins
|
//y axis pins
|
||||||
#define Y_STEP_PIN 23
|
#define Y_STEP_PIN 23
|
||||||
#define Y_DIR_PIN 22
|
#define Y_DIR_PIN 22
|
||||||
#define Y_ENABLE_PIN 24
|
#define Y_ENABLE_PIN 24
|
||||||
#define Y_MIN_PIN 1
|
#define Y_STOP_PIN 1
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
//z axis pins
|
//z axis pins
|
||||||
#define Z_STEP_PIN 26
|
#define Z_STEP_PIN 26
|
||||||
#define Z_DIR_PIN 25
|
#define Z_DIR_PIN 25
|
||||||
#define Z_ENABLE_PIN 24
|
#define Z_ENABLE_PIN 24
|
||||||
#define Z_MIN_PIN 2
|
#define Z_STOP_PIN 2
|
||||||
#define Z_MAX_PIN -1
|
|
||||||
|
|
||||||
//extruder pins
|
//extruder pins
|
||||||
#define E0_STEP_PIN 28
|
#define E0_STEP_PIN 28
|
||||||
|
@ -335,20 +324,17 @@
|
||||||
#define X_STEP_PIN 54
|
#define X_STEP_PIN 54
|
||||||
#define X_DIR_PIN 55
|
#define X_DIR_PIN 55
|
||||||
#define X_ENABLE_PIN 38
|
#define X_ENABLE_PIN 38
|
||||||
#define X_MIN_PIN -1
|
#define X_STOP_PIN 2
|
||||||
#define X_MAX_PIN 2 //2 //Max endstops default to disabled "-1", set to commented value to enable.
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 60
|
#define Y_STEP_PIN 60
|
||||||
#define Y_DIR_PIN 61
|
#define Y_DIR_PIN 61
|
||||||
#define Y_ENABLE_PIN 56
|
#define Y_ENABLE_PIN 56
|
||||||
#define Y_MIN_PIN -1
|
#define Y_STOP_PIN 15
|
||||||
#define Y_MAX_PIN 15 //15
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 46
|
#define Z_STEP_PIN 46
|
||||||
#define Z_DIR_PIN 48
|
#define Z_DIR_PIN 48
|
||||||
#define Z_ENABLE_PIN 62
|
#define Z_ENABLE_PIN 62
|
||||||
#define Z_MIN_PIN -1
|
#define Z_STOP_PIN 19
|
||||||
#define Z_MAX_PIN 19
|
|
||||||
|
|
||||||
#define Z2_STEP_PIN 36
|
#define Z2_STEP_PIN 36
|
||||||
#define Z2_DIR_PIN 34
|
#define Z2_DIR_PIN 34
|
||||||
|
@ -546,20 +532,17 @@
|
||||||
#define X_STEP_PIN 19
|
#define X_STEP_PIN 19
|
||||||
#define X_DIR_PIN 18
|
#define X_DIR_PIN 18
|
||||||
#define X_ENABLE_PIN -1
|
#define X_ENABLE_PIN -1
|
||||||
#define X_MIN_PIN 17
|
#define X_STOP_PIN 17
|
||||||
#define X_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 10
|
#define Y_STEP_PIN 10
|
||||||
#define Y_DIR_PIN 7
|
#define Y_DIR_PIN 7
|
||||||
#define Y_ENABLE_PIN -1
|
#define Y_ENABLE_PIN -1
|
||||||
#define Y_MIN_PIN 8
|
#define Y_STOP_PIN 8
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 13
|
#define Z_STEP_PIN 13
|
||||||
#define Z_DIR_PIN 3
|
#define Z_DIR_PIN 3
|
||||||
#define Z_ENABLE_PIN 2
|
#define Z_ENABLE_PIN 2
|
||||||
#define Z_MIN_PIN 4
|
#define Z_STOP_PIN 4
|
||||||
#define Z_MAX_PIN -1
|
|
||||||
|
|
||||||
#define E0_STEP_PIN 11
|
#define E0_STEP_PIN 11
|
||||||
#define E0_DIR_PIN 12
|
#define E0_DIR_PIN 12
|
||||||
|
@ -600,22 +583,19 @@
|
||||||
#define X_STEP_PIN 15
|
#define X_STEP_PIN 15
|
||||||
#define X_DIR_PIN 18
|
#define X_DIR_PIN 18
|
||||||
#define X_ENABLE_PIN 19
|
#define X_ENABLE_PIN 19
|
||||||
#define X_MIN_PIN 20
|
#define X_STOP_PIN 20
|
||||||
#define X_MAX_PIN -1
|
|
||||||
|
|
||||||
//y axis pins
|
//y axis pins
|
||||||
#define Y_STEP_PIN 23
|
#define Y_STEP_PIN 23
|
||||||
#define Y_DIR_PIN 22
|
#define Y_DIR_PIN 22
|
||||||
#define Y_ENABLE_PIN 24
|
#define Y_ENABLE_PIN 24
|
||||||
#define Y_MIN_PIN 25
|
#define Y_STOP_PIN 25
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
//z axis pins
|
//z axis pins
|
||||||
#define Z_STEP_PIN 27
|
#define Z_STEP_PIN 27
|
||||||
#define Z_DIR_PIN 28
|
#define Z_DIR_PIN 28
|
||||||
#define Z_ENABLE_PIN 29
|
#define Z_ENABLE_PIN 29
|
||||||
#define Z_MIN_PIN 30
|
#define Z_STOP_PIN 30
|
||||||
#define Z_MAX_PIN -1
|
|
||||||
|
|
||||||
//extruder pins
|
//extruder pins
|
||||||
#define E0_STEP_PIN 4 //Edited @ EJE Electronics 20100715
|
#define E0_STEP_PIN 4 //Edited @ EJE Electronics 20100715
|
||||||
|
@ -675,33 +655,15 @@
|
||||||
|
|
||||||
#define X_STEP_PIN 15
|
#define X_STEP_PIN 15
|
||||||
#define X_DIR_PIN 21
|
#define X_DIR_PIN 21
|
||||||
#if X_HOME_DIR < 0
|
#define X_STOP_PIN 18
|
||||||
# define X_MIN_PIN 18
|
|
||||||
# define X_MAX_PIN -1
|
|
||||||
#else
|
|
||||||
# define X_MIN_PIN -1
|
|
||||||
# define X_MAX_PIN 18
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 22
|
#define Y_STEP_PIN 22
|
||||||
#define Y_DIR_PIN 23
|
#define Y_DIR_PIN 23
|
||||||
#if Y_HOME_DIR < 0
|
#define Y_STOP_PIN 19
|
||||||
# define Y_MIN_PIN 19
|
|
||||||
# define Y_MAX_PIN -1
|
|
||||||
#else
|
|
||||||
# define Y_MIN_PIN -1
|
|
||||||
# define Y_MAX_PIN 19
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 3
|
#define Z_STEP_PIN 3
|
||||||
#define Z_DIR_PIN 2
|
#define Z_DIR_PIN 2
|
||||||
#if Z_HOME_DIR < 0
|
#define Z_STOP_PIN 20
|
||||||
# define Z_MIN_PIN 20
|
|
||||||
# define Z_MAX_PIN -1
|
|
||||||
#else
|
|
||||||
# define Z_MIN_PIN -1
|
|
||||||
# define Z_MAX_PIN 20
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define E0_STEP_PIN 1
|
#define E0_STEP_PIN 1
|
||||||
#define E0_DIR_PIN 0
|
#define E0_DIR_PIN 0
|
||||||
|
@ -973,20 +935,14 @@
|
||||||
#define X_STEP_PIN 0
|
#define X_STEP_PIN 0
|
||||||
#define X_DIR_PIN 1
|
#define X_DIR_PIN 1
|
||||||
#define X_ENABLE_PIN 39
|
#define X_ENABLE_PIN 39
|
||||||
#define X_MIN_PIN 13
|
|
||||||
#define X_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 2
|
#define Y_STEP_PIN 2
|
||||||
#define Y_DIR_PIN 3
|
#define Y_DIR_PIN 3
|
||||||
#define Y_ENABLE_PIN 38
|
#define Y_ENABLE_PIN 38
|
||||||
#define Y_MIN_PIN 14
|
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 4
|
#define Z_STEP_PIN 4
|
||||||
#define Z_DIR_PIN 5
|
#define Z_DIR_PIN 5
|
||||||
#define Z_ENABLE_PIN 23
|
#define Z_ENABLE_PIN 23
|
||||||
#define Z_MIN_PIN 15
|
|
||||||
#define Z_MAX_PIN -1
|
|
||||||
|
|
||||||
#define E0_STEP_PIN 6
|
#define E0_STEP_PIN 6
|
||||||
#define E0_DIR_PIN 7
|
#define E0_DIR_PIN 7
|
||||||
|
@ -997,11 +953,19 @@
|
||||||
#define HEATER_2_PIN -1
|
#define HEATER_2_PIN -1
|
||||||
#define HEATER_BED_PIN 20 // Bed
|
#define HEATER_BED_PIN 20 // Bed
|
||||||
#define FAN_PIN 22 // Fan
|
#define FAN_PIN 22 // Fan
|
||||||
|
// You may need to change FAN_PIN to 16 because Marlin isn't using fastio.h
|
||||||
|
// for the fan and Teensyduino uses a different pin mapping.
|
||||||
|
|
||||||
#if MOTHERBOARD == 8
|
#if MOTHERBOARD == 8 // Teensylu
|
||||||
|
#define X_STOP_PIN 13
|
||||||
|
#define Y_STOP_PIN 14
|
||||||
|
#define Z_STOP_PIN 15
|
||||||
#define TEMP_0_PIN 7 // Extruder / Analog pin numbering
|
#define TEMP_0_PIN 7 // Extruder / Analog pin numbering
|
||||||
#define TEMP_BED_PIN 6 // Bed / Analog pin numbering
|
#define TEMP_BED_PIN 6 // Bed / Analog pin numbering
|
||||||
#else
|
#else // Printrboard
|
||||||
|
#define X_STOP_PIN 35
|
||||||
|
#define Y_STOP_PIN 8
|
||||||
|
#define Z_STOP_PIN 36
|
||||||
#define TEMP_0_PIN 1 // Extruder / Analog pin numbering
|
#define TEMP_0_PIN 1 // Extruder / Analog pin numbering
|
||||||
#define TEMP_BED_PIN 0 // Bed / Analog pin numbering
|
#define TEMP_BED_PIN 0 // Bed / Analog pin numbering
|
||||||
#endif
|
#endif
|
||||||
|
@ -1041,22 +1005,20 @@
|
||||||
#define X_STEP_PIN 27
|
#define X_STEP_PIN 27
|
||||||
#define X_DIR_PIN 29
|
#define X_DIR_PIN 29
|
||||||
#define X_ENABLE_PIN 28
|
#define X_ENABLE_PIN 28
|
||||||
#define X_MIN_PIN -1
|
#define X_STOP_PIN 7
|
||||||
#define X_MAX_PIN 7
|
|
||||||
#define X_ATT_PIN 26
|
#define X_ATT_PIN 26
|
||||||
|
|
||||||
#define Y_STEP_PIN 31
|
#define Y_STEP_PIN 31
|
||||||
#define Y_DIR_PIN 33
|
#define Y_DIR_PIN 33
|
||||||
#define Y_ENABLE_PIN 32
|
#define Y_ENABLE_PIN 32
|
||||||
#define Y_MIN_PIN -1
|
#define Y_STOP_PIN 6
|
||||||
#define Y_MAX_PIN 6
|
|
||||||
#define Y_ATT_PIN 30
|
#define Y_ATT_PIN 30
|
||||||
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 17
|
#define Z_STEP_PIN 17
|
||||||
#define Z_DIR_PIN 19
|
#define Z_DIR_PIN 19
|
||||||
#define Z_ENABLE_PIN 18
|
#define Z_ENABLE_PIN 18
|
||||||
#define Z_MIN_PIN -1
|
#define Z_STOP_PIN 5
|
||||||
#define Z_MAX_PIN 5
|
|
||||||
#define Z_ATT_PIN 16
|
#define Z_ATT_PIN 16
|
||||||
|
|
||||||
#define E0_STEP_PIN 21
|
#define E0_STEP_PIN 21
|
||||||
|
@ -1106,18 +1068,15 @@
|
||||||
|
|
||||||
#define X_STEP_PIN 15
|
#define X_STEP_PIN 15
|
||||||
#define X_DIR_PIN 18
|
#define X_DIR_PIN 18
|
||||||
#define X_MIN_PIN 20
|
#define X_STOP_PIN 20
|
||||||
#define X_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 23
|
#define Y_STEP_PIN 23
|
||||||
#define Y_DIR_PIN 22
|
#define Y_DIR_PIN 22
|
||||||
#define Y_MIN_PIN 25
|
#define Y_STOP_PIN 25
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 27
|
#define Z_STEP_PIN 27
|
||||||
#define Z_DIR_PIN 28
|
#define Z_DIR_PIN 28
|
||||||
#define Z_MIN_PIN 30
|
#define Z_STOP_PIN 30
|
||||||
#define Z_MAX_PIN -1
|
|
||||||
|
|
||||||
#define E_STEP_PIN 17
|
#define E_STEP_PIN 17
|
||||||
#define E_DIR_PIN 21
|
#define E_DIR_PIN 21
|
||||||
|
@ -1187,20 +1146,17 @@
|
||||||
#define X_STEP_PIN 21
|
#define X_STEP_PIN 21
|
||||||
#define X_DIR_PIN 20
|
#define X_DIR_PIN 20
|
||||||
#define X_ENABLE_PIN 24
|
#define X_ENABLE_PIN 24
|
||||||
#define X_MIN_PIN 0
|
#define X_STOP_PIN 0
|
||||||
#define X_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 23
|
#define Y_STEP_PIN 23
|
||||||
#define Y_DIR_PIN 22
|
#define Y_DIR_PIN 22
|
||||||
#define Y_ENABLE_PIN 24
|
#define Y_ENABLE_PIN 24
|
||||||
#define Y_MIN_PIN 1
|
#define Y_STOP_PIN 1
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 26
|
#define Z_STEP_PIN 26
|
||||||
#define Z_DIR_PIN 25
|
#define Z_DIR_PIN 25
|
||||||
#define Z_ENABLE_PIN 24
|
#define Z_ENABLE_PIN 24
|
||||||
#define Z_MIN_PIN 2
|
#define Z_STOP_PIN 2
|
||||||
#define Z_MAX_PIN -1
|
|
||||||
|
|
||||||
#define E0_STEP_PIN 28
|
#define E0_STEP_PIN 28
|
||||||
#define E0_DIR_PIN 27
|
#define E0_DIR_PIN 27
|
||||||
|
@ -1244,20 +1200,17 @@
|
||||||
#define X_STEP_PIN 26
|
#define X_STEP_PIN 26
|
||||||
#define X_DIR_PIN 25
|
#define X_DIR_PIN 25
|
||||||
#define X_ENABLE_PIN 10
|
#define X_ENABLE_PIN 10
|
||||||
#define X_MIN_PIN 0
|
#define X_STOP_PIN 0
|
||||||
#define X_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Y_STEP_PIN 28
|
#define Y_STEP_PIN 28
|
||||||
#define Y_DIR_PIN 27
|
#define Y_DIR_PIN 27
|
||||||
#define Y_ENABLE_PIN 10
|
#define Y_ENABLE_PIN 10
|
||||||
#define Y_MIN_PIN 1
|
#define Y_STOP_PIN 1
|
||||||
#define Y_MAX_PIN -1
|
|
||||||
|
|
||||||
#define Z_STEP_PIN 23
|
#define Z_STEP_PIN 23
|
||||||
#define Z_DIR_PIN 22
|
#define Z_DIR_PIN 22
|
||||||
#define Z_ENABLE_PIN 10
|
#define Z_ENABLE_PIN 10
|
||||||
#define Z_MIN_PIN 2
|
#define Z_STOP_PIN 2
|
||||||
#define Z_MAX_PIN -1
|
|
||||||
|
|
||||||
#define E0_STEP_PIN 24
|
#define E0_STEP_PIN 24
|
||||||
#define E0_DIR_PIN 21
|
#define E0_DIR_PIN 21
|
||||||
|
@ -1394,13 +1347,13 @@
|
||||||
#define X_DIR_PIN 28
|
#define X_DIR_PIN 28
|
||||||
#define X_ENABLE_PIN 24
|
#define X_ENABLE_PIN 24
|
||||||
#define X_MIN_PIN 41
|
#define X_MIN_PIN 41
|
||||||
#define X_MAX_PIN 37 //2 //Max endstops default to disabled "-1", set to commented value to enable.
|
#define X_MAX_PIN 37
|
||||||
|
|
||||||
#define Y_STEP_PIN 60 // A6
|
#define Y_STEP_PIN 60 // A6
|
||||||
#define Y_DIR_PIN 61 // A7
|
#define Y_DIR_PIN 61 // A7
|
||||||
#define Y_ENABLE_PIN 22
|
#define Y_ENABLE_PIN 22
|
||||||
#define Y_MIN_PIN 14
|
#define Y_MIN_PIN 14
|
||||||
#define Y_MAX_PIN 15 //15
|
#define Y_MAX_PIN 15
|
||||||
|
|
||||||
#define Z_STEP_PIN 54 // A0
|
#define Z_STEP_PIN 54 // A0
|
||||||
#define Z_DIR_PIN 55 // A1
|
#define Z_DIR_PIN 55 // A1
|
||||||
|
@ -1494,14 +1447,44 @@
|
||||||
#define _E2_PINS
|
#define _E2_PINS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef X_STOP_PIN
|
||||||
|
#if X_HOME_DIR < 0
|
||||||
|
#define X_MIN_PIN X_STOP_PIN
|
||||||
|
#define X_MAX_PIN -1
|
||||||
|
#else
|
||||||
|
#define X_MIN_PIN -1
|
||||||
|
#define X_MAX_PIN X_STOP_PIN
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef Y_STOP_PIN
|
||||||
|
#if Y_HOME_DIR < 0
|
||||||
|
#define Y_MIN_PIN Y_STOP_PIN
|
||||||
|
#define Y_MAX_PIN -1
|
||||||
|
#else
|
||||||
|
#define Y_MIN_PIN -1
|
||||||
|
#define Y_MAX_PIN Y_STOP_PIN
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef Z_STOP_PIN
|
||||||
|
#if Z_HOME_DIR < 0
|
||||||
|
#define Z_MIN_PIN Z_STOP_PIN
|
||||||
|
#define Z_MAX_PIN -1
|
||||||
|
#else
|
||||||
|
#define Z_MIN_PIN -1
|
||||||
|
#define Z_MAX_PIN Z_STOP_PIN
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef DISABLE_MAX_ENDSTOPS
|
#ifdef DISABLE_MAX_ENDSTOPS
|
||||||
#define X_MAX_PIN -1
|
#define X_MAX_PIN -1
|
||||||
#define Y_MAX_PIN -1
|
#define Y_MAX_PIN -1
|
||||||
#define Z_MAX_PIN -1
|
#define Z_MAX_PIN -1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SENSITIVE_PINS {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, LED_PIN, PS_ON_PIN, \
|
#define SENSITIVE_PINS {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, PS_ON_PIN, \
|
||||||
HEATER_BED_PIN, FAN_PIN, \
|
HEATER_BED_PIN, FAN_PIN, \
|
||||||
_E0_PINS _E1_PINS _E2_PINS \
|
_E0_PINS _E1_PINS _E2_PINS \
|
||||||
TEMP_0_PIN, TEMP_1_PIN, TEMP_2_PIN, TEMP_BED_PIN }
|
analogInputToDigitalPin(TEMP_0_PIN), analogInputToDigitalPin(TEMP_1_PIN), analogInputToDigitalPin(TEMP_2_PIN), analogInputToDigitalPin(TEMP_BED_PIN) }
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -824,38 +824,36 @@ void st_init()
|
||||||
#if (X_STEP_PIN > -1)
|
#if (X_STEP_PIN > -1)
|
||||||
SET_OUTPUT(X_STEP_PIN);
|
SET_OUTPUT(X_STEP_PIN);
|
||||||
WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
|
WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
|
||||||
if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
|
disable_x();
|
||||||
#endif
|
#endif
|
||||||
#if (Y_STEP_PIN > -1)
|
#if (Y_STEP_PIN > -1)
|
||||||
SET_OUTPUT(Y_STEP_PIN);
|
SET_OUTPUT(Y_STEP_PIN);
|
||||||
WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
|
WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
|
||||||
if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
|
disable_y();
|
||||||
#endif
|
#endif
|
||||||
#if (Z_STEP_PIN > -1)
|
#if (Z_STEP_PIN > -1)
|
||||||
SET_OUTPUT(Z_STEP_PIN);
|
SET_OUTPUT(Z_STEP_PIN);
|
||||||
WRITE(Z_STEP_PIN,INVERT_Z_STEP_PIN);
|
WRITE(Z_STEP_PIN,INVERT_Z_STEP_PIN);
|
||||||
if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
|
|
||||||
|
|
||||||
#if defined(Z_DUAL_STEPPER_DRIVERS) && (Z2_STEP_PIN > -1)
|
#if defined(Z_DUAL_STEPPER_DRIVERS) && (Z2_STEP_PIN > -1)
|
||||||
SET_OUTPUT(Z2_STEP_PIN);
|
SET_OUTPUT(Z2_STEP_PIN);
|
||||||
WRITE(Z2_STEP_PIN,INVERT_Z_STEP_PIN);
|
WRITE(Z2_STEP_PIN,INVERT_Z_STEP_PIN);
|
||||||
if(!Z_ENABLE_ON) WRITE(Z2_ENABLE_PIN,HIGH);
|
|
||||||
#endif
|
#endif
|
||||||
|
disable_z();
|
||||||
#endif
|
#endif
|
||||||
#if (E0_STEP_PIN > -1)
|
#if (E0_STEP_PIN > -1)
|
||||||
SET_OUTPUT(E0_STEP_PIN);
|
SET_OUTPUT(E0_STEP_PIN);
|
||||||
WRITE(E0_STEP_PIN,INVERT_E_STEP_PIN);
|
WRITE(E0_STEP_PIN,INVERT_E_STEP_PIN);
|
||||||
if(!E_ENABLE_ON) WRITE(E0_ENABLE_PIN,HIGH);
|
disable_e0();
|
||||||
#endif
|
#endif
|
||||||
#if defined(E1_STEP_PIN) && (E1_STEP_PIN > -1)
|
#if defined(E1_STEP_PIN) && (E1_STEP_PIN > -1)
|
||||||
SET_OUTPUT(E1_STEP_PIN);
|
SET_OUTPUT(E1_STEP_PIN);
|
||||||
WRITE(E1_STEP_PIN,INVERT_E_STEP_PIN);
|
WRITE(E1_STEP_PIN,INVERT_E_STEP_PIN);
|
||||||
if(!E_ENABLE_ON) WRITE(E1_ENABLE_PIN,HIGH);
|
disable_e1();
|
||||||
#endif
|
#endif
|
||||||
#if defined(E2_STEP_PIN) && (E2_STEP_PIN > -1)
|
#if defined(E2_STEP_PIN) && (E2_STEP_PIN > -1)
|
||||||
SET_OUTPUT(E2_STEP_PIN);
|
SET_OUTPUT(E2_STEP_PIN);
|
||||||
WRITE(E2_STEP_PIN,INVERT_E_STEP_PIN);
|
WRITE(E2_STEP_PIN,INVERT_E_STEP_PIN);
|
||||||
if(!E_ENABLE_ON) WRITE(E2_ENABLE_PIN,HIGH);
|
disable_e2();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CONTROLLERFAN_PIN
|
#ifdef CONTROLLERFAN_PIN
|
||||||
|
|
|
@ -37,19 +37,14 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================public variables============================
|
//=============================public variables============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
int target_raw[EXTRUDERS] = { 0 };
|
int target_temperature[EXTRUDERS] = { 0 };
|
||||||
int target_raw_bed = 0;
|
int target_temperature_bed = 0;
|
||||||
#ifdef BED_LIMIT_SWITCHING
|
int current_temperature_raw[EXTRUDERS] = { 0 };
|
||||||
int target_bed_low_temp =0;
|
float current_temperature[EXTRUDERS] = { 0 };
|
||||||
int target_bed_high_temp =0;
|
int current_temperature_bed_raw = 0;
|
||||||
#endif
|
float current_temperature_bed = 0;
|
||||||
int current_raw[EXTRUDERS] = { 0 };
|
|
||||||
int current_raw_bed = 0;
|
|
||||||
|
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
// used external
|
|
||||||
float pid_setpoint[EXTRUDERS] = { 0.0 };
|
|
||||||
|
|
||||||
float Kp=DEFAULT_Kp;
|
float Kp=DEFAULT_Kp;
|
||||||
float Ki=(DEFAULT_Ki*PID_dT);
|
float Ki=(DEFAULT_Ki*PID_dT);
|
||||||
float Kd=(DEFAULT_Kd/PID_dT);
|
float Kd=(DEFAULT_Kd/PID_dT);
|
||||||
|
@ -59,9 +54,6 @@ int current_raw_bed = 0;
|
||||||
#endif //PIDTEMP
|
#endif //PIDTEMP
|
||||||
|
|
||||||
#ifdef PIDTEMPBED
|
#ifdef PIDTEMPBED
|
||||||
// used external
|
|
||||||
float pid_setpoint_bed = { 0.0 };
|
|
||||||
|
|
||||||
float bedKp=DEFAULT_bedKp;
|
float bedKp=DEFAULT_bedKp;
|
||||||
float bedKi=(DEFAULT_bedKi*PID_dT);
|
float bedKi=(DEFAULT_bedKi*PID_dT);
|
||||||
float bedKd=(DEFAULT_bedKd/PID_dT);
|
float bedKd=(DEFAULT_bedKd/PID_dT);
|
||||||
|
@ -116,12 +108,20 @@ static volatile bool temp_meas_ready = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Init min and max temp with extreme values to prevent false errors during startup
|
// Init min and max temp with extreme values to prevent false errors during startup
|
||||||
static int minttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0, 0, 0);
|
static int minttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_LO_TEMP , HEATER_1_RAW_LO_TEMP , HEATER_2_RAW_LO_TEMP );
|
||||||
static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(16383, 16383, 16383); // the first value used for all
|
static int maxttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_HI_TEMP , HEATER_1_RAW_HI_TEMP , HEATER_2_RAW_HI_TEMP );
|
||||||
static int bed_minttemp = 0;
|
static int minttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 0, 0, 0 );
|
||||||
static int bed_maxttemp = 16383;
|
static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 16383, 16383, 16383 );
|
||||||
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS((void *)heater_0_temptable, (void *)heater_1_temptable, (void *)heater_2_temptable);
|
//static int bed_minttemp_raw = HEATER_BED_RAW_LO_TEMP; /* No bed mintemp error implemented?!? */
|
||||||
static int heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS(heater_0_temptable_len, heater_1_temptable_len, heater_2_temptable_len);
|
#ifdef BED_MAXTEMP
|
||||||
|
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
|
||||||
|
#endif
|
||||||
|
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
|
||||||
|
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
|
||||||
|
|
||||||
|
static float analog2temp(int raw, uint8_t e);
|
||||||
|
static float analog2tempBed(int raw);
|
||||||
|
static void updateTemperaturesFromRawValues();
|
||||||
|
|
||||||
#ifdef WATCH_TEMP_PERIOD
|
#ifdef WATCH_TEMP_PERIOD
|
||||||
int watch_start_temp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
|
int watch_start_temp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
|
||||||
|
@ -179,13 +179,9 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||||
for(;;) {
|
for(;;) {
|
||||||
|
|
||||||
if(temp_meas_ready == true) { // temp sample ready
|
if(temp_meas_ready == true) { // temp sample ready
|
||||||
//Reset the watchdog after we know we have a temperature measurement.
|
updateTemperaturesFromRawValues();
|
||||||
watchdog_reset();
|
|
||||||
|
|
||||||
CRITICAL_SECTION_START;
|
input = (extruder<0)?current_temperature_bed:current_temperature[extruder];
|
||||||
temp_meas_ready = false;
|
|
||||||
CRITICAL_SECTION_END;
|
|
||||||
input = (extruder<0)?analog2tempBed(current_raw_bed):analog2temp(current_raw[extruder], extruder);
|
|
||||||
|
|
||||||
max=max(max,input);
|
max=max(max,input);
|
||||||
min=min(min,input);
|
min=min(min,input);
|
||||||
|
@ -313,26 +309,21 @@ void manage_heater()
|
||||||
if(temp_meas_ready != true) //better readability
|
if(temp_meas_ready != true) //better readability
|
||||||
return;
|
return;
|
||||||
|
|
||||||
//Reset the watchdog after we know we have a temperature measurement.
|
updateTemperaturesFromRawValues();
|
||||||
watchdog_reset();
|
|
||||||
|
|
||||||
CRITICAL_SECTION_START;
|
|
||||||
temp_meas_ready = false;
|
|
||||||
CRITICAL_SECTION_END;
|
|
||||||
|
|
||||||
for(int e = 0; e < EXTRUDERS; e++)
|
for(int e = 0; e < EXTRUDERS; e++)
|
||||||
{
|
{
|
||||||
|
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
pid_input = analog2temp(current_raw[e], e);
|
pid_input = current_temperature[e];
|
||||||
|
|
||||||
#ifndef PID_OPENLOOP
|
#ifndef PID_OPENLOOP
|
||||||
pid_error[e] = pid_setpoint[e] - pid_input;
|
pid_error[e] = target_temperature[e] - pid_input;
|
||||||
if(pid_error[e] > 10) {
|
if(pid_error[e] > PID_FUNCTIONAL_RANGE) {
|
||||||
pid_output = PID_MAX;
|
pid_output = PID_MAX;
|
||||||
pid_reset[e] = true;
|
pid_reset[e] = true;
|
||||||
}
|
}
|
||||||
else if(pid_error[e] < -10) {
|
else if(pid_error[e] < -PID_FUNCTIONAL_RANGE) {
|
||||||
pid_output = 0;
|
pid_output = 0;
|
||||||
pid_reset[e] = true;
|
pid_reset[e] = true;
|
||||||
}
|
}
|
||||||
|
@ -354,20 +345,31 @@ void manage_heater()
|
||||||
pid_output = constrain(pTerm[e] + iTerm[e] - dTerm[e], 0, PID_MAX);
|
pid_output = constrain(pTerm[e] + iTerm[e] - dTerm[e], 0, PID_MAX);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
pid_output = constrain(pid_setpoint[e], 0, PID_MAX);
|
pid_output = constrain(target_temperature[e], 0, PID_MAX);
|
||||||
#endif //PID_OPENLOOP
|
#endif //PID_OPENLOOP
|
||||||
#ifdef PID_DEBUG
|
#ifdef PID_DEBUG
|
||||||
SERIAL_ECHOLN(" PIDDEBUG "<<e<<": Input "<<pid_input<<" Output "<<pid_output" pTerm "<<pTerm[e]<<" iTerm "<<iTerm[e]<<" dTerm "<<dTerm[e]);
|
SERIAL_ECHO_START(" PIDDEBUG ");
|
||||||
|
SERIAL_ECHO(e);
|
||||||
|
SERIAL_ECHO(": Input ");
|
||||||
|
SERIAL_ECHO(pid_input);
|
||||||
|
SERIAL_ECHO(" Output ");
|
||||||
|
SERIAL_ECHO(pid_output);
|
||||||
|
SERIAL_ECHO(" pTerm ");
|
||||||
|
SERIAL_ECHO(pTerm[e]);
|
||||||
|
SERIAL_ECHO(" iTerm ");
|
||||||
|
SERIAL_ECHO(iTerm[e]);
|
||||||
|
SERIAL_ECHO(" dTerm ");
|
||||||
|
SERIAL_ECHOLN(dTerm[e]);
|
||||||
#endif //PID_DEBUG
|
#endif //PID_DEBUG
|
||||||
#else /* PID off */
|
#else /* PID off */
|
||||||
pid_output = 0;
|
pid_output = 0;
|
||||||
if(current_raw[e] < target_raw[e]) {
|
if(current_temperature[e] < target_temperature[e]) {
|
||||||
pid_output = PID_MAX;
|
pid_output = PID_MAX;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Check if temperature is within the correct range
|
// Check if temperature is within the correct range
|
||||||
if((current_raw[e] > minttemp[e]) && (current_raw[e] < maxttemp[e]))
|
if((current_temperature[e] > minttemp[e]) && (current_temperature[e] < maxttemp[e]))
|
||||||
{
|
{
|
||||||
soft_pwm[e] = (int)pid_output >> 1;
|
soft_pwm[e] = (int)pid_output >> 1;
|
||||||
}
|
}
|
||||||
|
@ -393,19 +395,19 @@ void manage_heater()
|
||||||
} // End extruder for loop
|
} // End extruder for loop
|
||||||
|
|
||||||
|
|
||||||
#ifndef PIDTEMPBED
|
#ifndef PIDTEMPBED
|
||||||
if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
|
if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
|
||||||
return;
|
return;
|
||||||
previous_millis_bed_heater = millis();
|
previous_millis_bed_heater = millis();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_BED_PIN > -1
|
#if TEMP_SENSOR_BED != 0
|
||||||
|
|
||||||
#ifdef PIDTEMPBED
|
#ifdef PIDTEMPBED
|
||||||
pid_input = analog2tempBed(current_raw_bed);
|
pid_input = current_temperature_bed;
|
||||||
|
|
||||||
#ifndef PID_OPENLOOP
|
#ifndef PID_OPENLOOP
|
||||||
pid_error_bed = pid_setpoint_bed - pid_input;
|
pid_error_bed = target_temperature_bed - pid_input;
|
||||||
pTerm_bed = bedKp * pid_error_bed;
|
pTerm_bed = bedKp * pid_error_bed;
|
||||||
temp_iState_bed += pid_error_bed;
|
temp_iState_bed += pid_error_bed;
|
||||||
temp_iState_bed = constrain(temp_iState_bed, temp_iState_min_bed, temp_iState_max_bed);
|
temp_iState_bed = constrain(temp_iState_bed, temp_iState_min_bed, temp_iState_max_bed);
|
||||||
|
@ -419,10 +421,10 @@ void manage_heater()
|
||||||
pid_output = constrain(pTerm_bed + iTerm_bed - dTerm_bed, 0, MAX_BED_POWER);
|
pid_output = constrain(pTerm_bed + iTerm_bed - dTerm_bed, 0, MAX_BED_POWER);
|
||||||
|
|
||||||
#else
|
#else
|
||||||
pid_output = constrain(pid_setpoint_bed, 0, MAX_BED_POWER);
|
pid_output = constrain(target_temperature_bed, 0, MAX_BED_POWER);
|
||||||
#endif //PID_OPENLOOP
|
#endif //PID_OPENLOOP
|
||||||
|
|
||||||
if((current_raw_bed > bed_minttemp) && (current_raw_bed < bed_maxttemp))
|
if((current_temperature_bed > BED_MINTEMP) && (current_temperature_bed < BED_MAXTEMP))
|
||||||
{
|
{
|
||||||
soft_pwm_bed = (int)pid_output >> 1;
|
soft_pwm_bed = (int)pid_output >> 1;
|
||||||
}
|
}
|
||||||
|
@ -430,37 +432,40 @@ void manage_heater()
|
||||||
soft_pwm_bed = 0;
|
soft_pwm_bed = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#elif not defined BED_LIMIT_SWITCHING
|
#elif !defined(BED_LIMIT_SWITCHING)
|
||||||
// Check if temperature is within the correct range
|
// Check if temperature is within the correct range
|
||||||
if((current_raw_bed > bed_minttemp) && (current_raw_bed < bed_maxttemp)) {
|
if((current_temperature_bed > BED_MINTEMP) && (current_temperature_bed < BED_MAXTEMP))
|
||||||
if(current_raw_bed >= target_raw_bed)
|
{
|
||||||
|
if(current_temperature_bed >= target_temperature_bed)
|
||||||
{
|
{
|
||||||
soft_pwm_bed = 0;
|
soft_pwm_bed = 0;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
soft_pwm_bed = MAX_BED_POWER>>1;
|
soft_pwm_bed = MAX_BED_POWER>>1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else {
|
else
|
||||||
soft_pwm_bed = 0;
|
{
|
||||||
|
soft_pwm_bed = 0;
|
||||||
WRITE(HEATER_BED_PIN,LOW);
|
WRITE(HEATER_BED_PIN,LOW);
|
||||||
}
|
}
|
||||||
#else //#ifdef BED_LIMIT_SWITCHING
|
#else //#ifdef BED_LIMIT_SWITCHING
|
||||||
// Check if temperature is within the correct band
|
// Check if temperature is within the correct band
|
||||||
if((current_raw_bed > bed_minttemp) && (current_raw_bed < bed_maxttemp)) {
|
if((current_temperature_bed > BED_MINTEMP) && (current_temperature_bed < BED_MAXTEMP))
|
||||||
if(current_raw_bed > target_bed_high_temp)
|
{
|
||||||
|
if(current_temperature_bed > target_temperature_bed + BED_HYSTERESIS)
|
||||||
{
|
{
|
||||||
soft_pwm_bed = 0;
|
soft_pwm_bed = 0;
|
||||||
}
|
}
|
||||||
else
|
else if(current_temperature_bed <= target_temperature_bed - BED_HYSTERESIS)
|
||||||
if(current_raw_bed <= target_bed_low_temp)
|
|
||||||
{
|
{
|
||||||
soft_pwm_bed = MAX_BED_POWER>>1;
|
soft_pwm_bed = MAX_BED_POWER>>1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else {
|
else
|
||||||
soft_pwm_bed = 0;
|
{
|
||||||
|
soft_pwm_bed = 0;
|
||||||
WRITE(HEATER_BED_PIN,LOW);
|
WRITE(HEATER_BED_PIN,LOW);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -468,86 +473,9 @@ void manage_heater()
|
||||||
}
|
}
|
||||||
|
|
||||||
#define PGM_RD_W(x) (short)pgm_read_word(&x)
|
#define PGM_RD_W(x) (short)pgm_read_word(&x)
|
||||||
// Takes hot end temperature value as input and returns corresponding raw value.
|
|
||||||
// For a thermistor, it uses the RepRap thermistor temp table.
|
|
||||||
// This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
|
|
||||||
// This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
|
|
||||||
int temp2analog(int celsius, uint8_t e) {
|
|
||||||
if(e >= EXTRUDERS)
|
|
||||||
{
|
|
||||||
SERIAL_ERROR_START;
|
|
||||||
SERIAL_ERROR((int)e);
|
|
||||||
SERIAL_ERRORLNPGM(" - Invalid extruder number!");
|
|
||||||
kill();
|
|
||||||
}
|
|
||||||
#ifdef HEATER_0_USES_MAX6675
|
|
||||||
if (e == 0)
|
|
||||||
{
|
|
||||||
return celsius * 4;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
if(heater_ttbl_map[e] != 0)
|
|
||||||
{
|
|
||||||
int raw = 0;
|
|
||||||
byte i;
|
|
||||||
short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]);
|
|
||||||
|
|
||||||
for (i=1; i<heater_ttbllen_map[e]; i++)
|
|
||||||
{
|
|
||||||
if (PGM_RD_W((*tt)[i][1]) < celsius)
|
|
||||||
{
|
|
||||||
raw = PGM_RD_W((*tt)[i-1][0]) +
|
|
||||||
(celsius - PGM_RD_W((*tt)[i-1][1])) *
|
|
||||||
(PGM_RD_W((*tt)[i][0]) - PGM_RD_W((*tt)[i-1][0])) /
|
|
||||||
(PGM_RD_W((*tt)[i][1]) - PGM_RD_W((*tt)[i-1][1]));
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Overflow: Set to last value in the table
|
|
||||||
if (i == heater_ttbllen_map[e]) raw = PGM_RD_W((*tt)[i-1][0]);
|
|
||||||
|
|
||||||
return (1023 * OVERSAMPLENR) - raw;
|
|
||||||
}
|
|
||||||
return ((celsius-TEMP_SENSOR_AD595_OFFSET)/TEMP_SENSOR_AD595_GAIN) * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Takes bed temperature value as input and returns corresponding raw value.
|
|
||||||
// For a thermistor, it uses the RepRap thermistor temp table.
|
|
||||||
// This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
|
|
||||||
// This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
|
|
||||||
int temp2analogBed(int celsius) {
|
|
||||||
#ifdef BED_USES_THERMISTOR
|
|
||||||
int raw = 0;
|
|
||||||
byte i;
|
|
||||||
|
|
||||||
for (i=1; i<bedtemptable_len; i++)
|
|
||||||
{
|
|
||||||
if (PGM_RD_W(bedtemptable[i][1]) < celsius)
|
|
||||||
{
|
|
||||||
raw = PGM_RD_W(bedtemptable[i-1][0]) +
|
|
||||||
(celsius - PGM_RD_W(bedtemptable[i-1][1])) *
|
|
||||||
(PGM_RD_W(bedtemptable[i][0]) - PGM_RD_W(bedtemptable[i-1][0])) /
|
|
||||||
(PGM_RD_W(bedtemptable[i][1]) - PGM_RD_W(bedtemptable[i-1][1]));
|
|
||||||
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Overflow: Set to last value in the table
|
|
||||||
if (i == bedtemptable_len) raw = PGM_RD_W(bedtemptable[i-1][0]);
|
|
||||||
|
|
||||||
return (1023 * OVERSAMPLENR) - raw;
|
|
||||||
#elif defined BED_USES_AD595
|
|
||||||
return lround(((celsius-TEMP_SENSOR_AD595_OFFSET)/TEMP_SENSOR_AD595_GAIN) * (1024.0 * OVERSAMPLENR/ (5.0 * 100.0) ) );
|
|
||||||
#else
|
|
||||||
return 0;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
// Derived from RepRap FiveD extruder::getTemperature()
|
// Derived from RepRap FiveD extruder::getTemperature()
|
||||||
// For hot end temperature measurement.
|
// For hot end temperature measurement.
|
||||||
float analog2temp(int raw, uint8_t e) {
|
static float analog2temp(int raw, uint8_t e) {
|
||||||
if(e >= EXTRUDERS)
|
if(e >= EXTRUDERS)
|
||||||
{
|
{
|
||||||
SERIAL_ERROR_START;
|
SERIAL_ERROR_START;
|
||||||
|
@ -565,10 +493,9 @@ float analog2temp(int raw, uint8_t e) {
|
||||||
if(heater_ttbl_map[e] != NULL)
|
if(heater_ttbl_map[e] != NULL)
|
||||||
{
|
{
|
||||||
float celsius = 0;
|
float celsius = 0;
|
||||||
byte i;
|
uint8_t i;
|
||||||
short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]);
|
short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]);
|
||||||
|
|
||||||
raw = (1023 * OVERSAMPLENR) - raw;
|
|
||||||
for (i=1; i<heater_ttbllen_map[e]; i++)
|
for (i=1; i<heater_ttbllen_map[e]; i++)
|
||||||
{
|
{
|
||||||
if (PGM_RD_W((*tt)[i][0]) > raw)
|
if (PGM_RD_W((*tt)[i][0]) > raw)
|
||||||
|
@ -591,27 +518,25 @@ float analog2temp(int raw, uint8_t e) {
|
||||||
|
|
||||||
// Derived from RepRap FiveD extruder::getTemperature()
|
// Derived from RepRap FiveD extruder::getTemperature()
|
||||||
// For bed temperature measurement.
|
// For bed temperature measurement.
|
||||||
float analog2tempBed(int raw) {
|
static float analog2tempBed(int raw) {
|
||||||
#ifdef BED_USES_THERMISTOR
|
#ifdef BED_USES_THERMISTOR
|
||||||
float celsius = 0;
|
float celsius = 0;
|
||||||
byte i;
|
byte i;
|
||||||
|
|
||||||
raw = (1023 * OVERSAMPLENR) - raw;
|
for (i=1; i<BEDTEMPTABLE_LEN; i++)
|
||||||
|
|
||||||
for (i=1; i<bedtemptable_len; i++)
|
|
||||||
{
|
{
|
||||||
if (PGM_RD_W(bedtemptable[i][0]) > raw)
|
if (PGM_RD_W(BEDTEMPTABLE[i][0]) > raw)
|
||||||
{
|
{
|
||||||
celsius = PGM_RD_W(bedtemptable[i-1][1]) +
|
celsius = PGM_RD_W(BEDTEMPTABLE[i-1][1]) +
|
||||||
(raw - PGM_RD_W(bedtemptable[i-1][0])) *
|
(raw - PGM_RD_W(BEDTEMPTABLE[i-1][0])) *
|
||||||
(float)(PGM_RD_W(bedtemptable[i][1]) - PGM_RD_W(bedtemptable[i-1][1])) /
|
(float)(PGM_RD_W(BEDTEMPTABLE[i][1]) - PGM_RD_W(BEDTEMPTABLE[i-1][1])) /
|
||||||
(float)(PGM_RD_W(bedtemptable[i][0]) - PGM_RD_W(bedtemptable[i-1][0]));
|
(float)(PGM_RD_W(BEDTEMPTABLE[i][0]) - PGM_RD_W(BEDTEMPTABLE[i-1][0]));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overflow: Set to last value in the table
|
// Overflow: Set to last value in the table
|
||||||
if (i == bedtemptable_len) celsius = PGM_RD_W(bedtemptable[i-1][1]);
|
if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i-1][1]);
|
||||||
|
|
||||||
return celsius;
|
return celsius;
|
||||||
#elif defined BED_USES_AD595
|
#elif defined BED_USES_AD595
|
||||||
|
@ -621,6 +546,24 @@ float analog2tempBed(int raw) {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* 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()
|
||||||
|
{
|
||||||
|
for(uint8_t e=0;e<EXTRUDERS;e++)
|
||||||
|
{
|
||||||
|
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
|
||||||
|
}
|
||||||
|
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
||||||
|
|
||||||
|
//Reset the watchdog after we know we have a temperature measurement.
|
||||||
|
watchdog_reset();
|
||||||
|
|
||||||
|
CRITICAL_SECTION_START;
|
||||||
|
temp_meas_ready = false;
|
||||||
|
CRITICAL_SECTION_END;
|
||||||
|
}
|
||||||
|
|
||||||
void tp_init()
|
void tp_init()
|
||||||
{
|
{
|
||||||
// Finish init of mult extruder arrays
|
// Finish init of mult extruder arrays
|
||||||
|
@ -716,31 +659,87 @@ void tp_init()
|
||||||
delay(250);
|
delay(250);
|
||||||
|
|
||||||
#ifdef HEATER_0_MINTEMP
|
#ifdef HEATER_0_MINTEMP
|
||||||
minttemp[0] = temp2analog(HEATER_0_MINTEMP, 0);
|
minttemp[0] = HEATER_0_MINTEMP;
|
||||||
|
while(analog2temp(minttemp_raw[0], 0) < HEATER_0_MINTEMP) {
|
||||||
|
#if HEATER_0_RAW_LO_TEMP < HEATER_0_RAW_HI_TEMP
|
||||||
|
minttemp_raw[0] += OVERSAMPLENR;
|
||||||
|
#else
|
||||||
|
minttemp_raw[0] -= OVERSAMPLENR;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
#endif //MINTEMP
|
#endif //MINTEMP
|
||||||
#ifdef HEATER_0_MAXTEMP
|
#ifdef HEATER_0_MAXTEMP
|
||||||
maxttemp[0] = temp2analog(HEATER_0_MAXTEMP, 0);
|
maxttemp[0] = HEATER_0_MAXTEMP;
|
||||||
|
while(analog2temp(maxttemp_raw[0], 0) > HEATER_0_MAXTEMP) {
|
||||||
|
#if HEATER_0_RAW_LO_TEMP < HEATER_0_RAW_HI_TEMP
|
||||||
|
maxttemp_raw[0] -= OVERSAMPLENR;
|
||||||
|
#else
|
||||||
|
maxttemp_raw[0] += OVERSAMPLENR;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
#endif //MAXTEMP
|
#endif //MAXTEMP
|
||||||
|
|
||||||
#if (EXTRUDERS > 1) && defined(HEATER_1_MINTEMP)
|
#if (EXTRUDERS > 1) && defined(HEATER_1_MINTEMP)
|
||||||
minttemp[1] = temp2analog(HEATER_1_MINTEMP, 1);
|
minttemp[1] = HEATER_1_MINTEMP;
|
||||||
|
while(analog2temp(minttemp_raw[1], 1) > HEATER_1_MINTEMP) {
|
||||||
|
#if HEATER_1_RAW_LO_TEMP < HEATER_1_RAW_HI_TEMP
|
||||||
|
minttemp_raw[1] += OVERSAMPLENR;
|
||||||
|
#else
|
||||||
|
minttemp_raw[1] -= OVERSAMPLENR;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
#endif // MINTEMP 1
|
#endif // MINTEMP 1
|
||||||
#if (EXTRUDERS > 1) && defined(HEATER_1_MAXTEMP)
|
#if (EXTRUDERS > 1) && defined(HEATER_1_MAXTEMP)
|
||||||
maxttemp[1] = temp2analog(HEATER_1_MAXTEMP, 1);
|
maxttemp[1] = HEATER_1_MAXTEMP;
|
||||||
|
while(analog2temp(maxttemp_raw[1], 1) > HEATER_1_MAXTEMP) {
|
||||||
|
#if HEATER_1_RAW_LO_TEMP < HEATER_1_RAW_HI_TEMP
|
||||||
|
maxttemp_raw[1] -= OVERSAMPLENR;
|
||||||
|
#else
|
||||||
|
maxttemp_raw[1] += OVERSAMPLENR;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
#endif //MAXTEMP 1
|
#endif //MAXTEMP 1
|
||||||
|
|
||||||
#if (EXTRUDERS > 2) && defined(HEATER_2_MINTEMP)
|
#if (EXTRUDERS > 2) && defined(HEATER_2_MINTEMP)
|
||||||
minttemp[2] = temp2analog(HEATER_2_MINTEMP, 2);
|
minttemp[2] = HEATER_2_MINTEMP;
|
||||||
|
while(analog2temp(minttemp_raw[2], 2) > HEATER_2_MINTEMP) {
|
||||||
|
#if HEATER_2_RAW_LO_TEMP < HEATER_2_RAW_HI_TEMP
|
||||||
|
minttemp_raw[2] += OVERSAMPLENR;
|
||||||
|
#else
|
||||||
|
minttemp_raw[2] -= OVERSAMPLENR;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
#endif //MINTEMP 2
|
#endif //MINTEMP 2
|
||||||
#if (EXTRUDERS > 2) && defined(HEATER_2_MAXTEMP)
|
#if (EXTRUDERS > 2) && defined(HEATER_2_MAXTEMP)
|
||||||
maxttemp[2] = temp2analog(HEATER_2_MAXTEMP, 2);
|
maxttemp[2] = HEATER_2_MAXTEMP;
|
||||||
|
while(analog2temp(maxttemp_raw[2], 2) > HEATER_2_MAXTEMP) {
|
||||||
|
#if HEATER_2_RAW_LO_TEMP < HEATER_2_RAW_HI_TEMP
|
||||||
|
maxttemp_raw[2] -= OVERSAMPLENR;
|
||||||
|
#else
|
||||||
|
maxttemp_raw[2] += OVERSAMPLENR;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
#endif //MAXTEMP 2
|
#endif //MAXTEMP 2
|
||||||
|
|
||||||
#ifdef BED_MINTEMP
|
#ifdef BED_MINTEMP
|
||||||
bed_minttemp = temp2analogBed(BED_MINTEMP);
|
/* No bed MINTEMP error implemented?!? */ /*
|
||||||
|
while(analog2tempBed(bed_minttemp_raw) < BED_MINTEMP) {
|
||||||
|
#if HEATER_BED_RAW_LO_TEMP < HEATER_BED_RAW_HI_TEMP
|
||||||
|
bed_minttemp_raw += OVERSAMPLENR;
|
||||||
|
#else
|
||||||
|
bed_minttemp_raw -= OVERSAMPLENR;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
*/
|
||||||
#endif //BED_MINTEMP
|
#endif //BED_MINTEMP
|
||||||
#ifdef BED_MAXTEMP
|
#ifdef BED_MAXTEMP
|
||||||
bed_maxttemp = temp2analogBed(BED_MAXTEMP);
|
while(analog2tempBed(bed_maxttemp_raw) > BED_MAXTEMP) {
|
||||||
|
#if HEATER_BED_RAW_LO_TEMP < HEATER_BED_RAW_HI_TEMP
|
||||||
|
bed_maxttemp_raw -= OVERSAMPLENR;
|
||||||
|
#else
|
||||||
|
bed_maxttemp_raw += OVERSAMPLENR;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
#endif //BED_MAXTEMP
|
#endif //BED_MAXTEMP
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -765,7 +764,7 @@ void disable_heater()
|
||||||
setTargetHotend(0,i);
|
setTargetHotend(0,i);
|
||||||
setTargetBed(0);
|
setTargetBed(0);
|
||||||
#if TEMP_0_PIN > -1
|
#if TEMP_0_PIN > -1
|
||||||
target_raw[0]=0;
|
target_temperature[0]=0;
|
||||||
soft_pwm[0]=0;
|
soft_pwm[0]=0;
|
||||||
#if HEATER_0_PIN > -1
|
#if HEATER_0_PIN > -1
|
||||||
WRITE(HEATER_0_PIN,LOW);
|
WRITE(HEATER_0_PIN,LOW);
|
||||||
|
@ -773,7 +772,7 @@ void disable_heater()
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_1_PIN > -1
|
#if TEMP_1_PIN > -1
|
||||||
target_raw[1]=0;
|
target_temperature[1]=0;
|
||||||
soft_pwm[1]=0;
|
soft_pwm[1]=0;
|
||||||
#if HEATER_1_PIN > -1
|
#if HEATER_1_PIN > -1
|
||||||
WRITE(HEATER_1_PIN,LOW);
|
WRITE(HEATER_1_PIN,LOW);
|
||||||
|
@ -781,7 +780,7 @@ void disable_heater()
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_2_PIN > -1
|
#if TEMP_2_PIN > -1
|
||||||
target_raw[2]=0;
|
target_temperature[2]=0;
|
||||||
soft_pwm[2]=0;
|
soft_pwm[2]=0;
|
||||||
#if HEATER_2_PIN > -1
|
#if HEATER_2_PIN > -1
|
||||||
WRITE(HEATER_2_PIN,LOW);
|
WRITE(HEATER_2_PIN,LOW);
|
||||||
|
@ -789,7 +788,7 @@ void disable_heater()
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_BED_PIN > -1
|
#if TEMP_BED_PIN > -1
|
||||||
target_raw_bed=0;
|
target_temperature_bed=0;
|
||||||
soft_pwm_bed=0;
|
soft_pwm_bed=0;
|
||||||
#if HEATER_BED_PIN > -1
|
#if HEATER_BED_PIN > -1
|
||||||
WRITE(HEATER_BED_PIN,LOW);
|
WRITE(HEATER_BED_PIN,LOW);
|
||||||
|
@ -803,6 +802,7 @@ void max_temp_error(uint8_t e) {
|
||||||
SERIAL_ERROR_START;
|
SERIAL_ERROR_START;
|
||||||
SERIAL_ERRORLN((int)e);
|
SERIAL_ERRORLN((int)e);
|
||||||
SERIAL_ERRORLNPGM(": Extruder switched off. MAXTEMP triggered !");
|
SERIAL_ERRORLNPGM(": Extruder switched off. MAXTEMP triggered !");
|
||||||
|
LCD_ALERTMESSAGEPGM("Err: MAXTEMP");
|
||||||
}
|
}
|
||||||
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
||||||
Stop();
|
Stop();
|
||||||
|
@ -815,6 +815,7 @@ void min_temp_error(uint8_t e) {
|
||||||
SERIAL_ERROR_START;
|
SERIAL_ERROR_START;
|
||||||
SERIAL_ERRORLN((int)e);
|
SERIAL_ERRORLN((int)e);
|
||||||
SERIAL_ERRORLNPGM(": Extruder switched off. MINTEMP triggered !");
|
SERIAL_ERRORLNPGM(": Extruder switched off. MINTEMP triggered !");
|
||||||
|
LCD_ALERTMESSAGEPGM("Err: MINTEMP");
|
||||||
}
|
}
|
||||||
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
||||||
Stop();
|
Stop();
|
||||||
|
@ -828,6 +829,7 @@ void bed_max_temp_error(void) {
|
||||||
if(IsStopped() == false) {
|
if(IsStopped() == false) {
|
||||||
SERIAL_ERROR_START;
|
SERIAL_ERROR_START;
|
||||||
SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !!");
|
SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !!");
|
||||||
|
LCD_ALERTMESSAGEPGM("Err: MAXTEMP BED");
|
||||||
}
|
}
|
||||||
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
||||||
Stop();
|
Stop();
|
||||||
|
@ -1031,33 +1033,17 @@ ISR(TIMER0_COMPB_vect)
|
||||||
|
|
||||||
if(temp_count >= 16) // 8 ms * 16 = 128ms.
|
if(temp_count >= 16) // 8 ms * 16 = 128ms.
|
||||||
{
|
{
|
||||||
#if defined(HEATER_0_USES_AD595) || defined(HEATER_0_USES_MAX6675)
|
if (!temp_meas_ready) //Only update the raw values if they have been read. Else we could be updating them during reading.
|
||||||
current_raw[0] = raw_temp_0_value;
|
{
|
||||||
#else
|
current_temperature_raw[0] = raw_temp_0_value;
|
||||||
current_raw[0] = 16383 - raw_temp_0_value;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if EXTRUDERS > 1
|
#if EXTRUDERS > 1
|
||||||
#ifdef HEATER_1_USES_AD595
|
current_temperature_raw[1] = raw_temp_1_value;
|
||||||
current_raw[1] = raw_temp_1_value;
|
|
||||||
#else
|
|
||||||
current_raw[1] = 16383 - raw_temp_1_value;
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if EXTRUDERS > 2
|
#if EXTRUDERS > 2
|
||||||
#ifdef HEATER_2_USES_AD595
|
current_temperature_raw[2] = raw_temp_2_value;
|
||||||
current_raw[2] = raw_temp_2_value;
|
|
||||||
#else
|
|
||||||
current_raw[2] = 16383 - raw_temp_2_value;
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
current_temperature_bed_raw = raw_temp_bed_value;
|
||||||
#ifdef BED_USES_AD595
|
}
|
||||||
current_raw_bed = raw_temp_bed_value;
|
|
||||||
#else
|
|
||||||
current_raw_bed = 16383 - raw_temp_bed_value;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
temp_meas_ready = true;
|
temp_meas_ready = true;
|
||||||
temp_count = 0;
|
temp_count = 0;
|
||||||
|
@ -1066,23 +1052,63 @@ ISR(TIMER0_COMPB_vect)
|
||||||
raw_temp_2_value = 0;
|
raw_temp_2_value = 0;
|
||||||
raw_temp_bed_value = 0;
|
raw_temp_bed_value = 0;
|
||||||
|
|
||||||
for(unsigned char e = 0; e < EXTRUDERS; e++) {
|
#if HEATER_0_RAW_LO_TEMP > HEATER_0_RAW_HI_TEMP
|
||||||
if(current_raw[e] >= maxttemp[e]) {
|
if(current_temperature_raw[0] <= maxttemp_raw[0]) {
|
||||||
target_raw[e] = 0;
|
#else
|
||||||
max_temp_error(e);
|
if(current_temperature_raw[0] >= maxttemp_raw[0]) {
|
||||||
}
|
#endif
|
||||||
if(current_raw[e] <= minttemp[e]) {
|
max_temp_error(0);
|
||||||
target_raw[e] = 0;
|
|
||||||
min_temp_error(e);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
#if HEATER_0_RAW_LO_TEMP > HEATER_0_RAW_HI_TEMP
|
||||||
|
if(current_temperature_raw[0] >= minttemp_raw[0]) {
|
||||||
|
#else
|
||||||
|
if(current_temperature_raw[0] <= minttemp_raw[0]) {
|
||||||
|
#endif
|
||||||
|
min_temp_error(0);
|
||||||
|
}
|
||||||
|
#if EXTRUDERS > 1
|
||||||
|
#if HEATER_1_RAW_LO_TEMP > HEATER_1_RAW_HI_TEMP
|
||||||
|
if(current_temperature_raw[1] <= maxttemp_raw[1]) {
|
||||||
|
#else
|
||||||
|
if(current_temperature_raw[1] >= maxttemp_raw[1]) {
|
||||||
|
#endif
|
||||||
|
max_temp_error(1);
|
||||||
|
}
|
||||||
|
#if HEATER_1_RAW_LO_TEMP > HEATER_1_RAW_HI_TEMP
|
||||||
|
if(current_temperature_raw[1] >= minttemp_raw[1]) {
|
||||||
|
#else
|
||||||
|
if(current_temperature_raw[1] <= minttemp_raw[1]) {
|
||||||
|
#endif
|
||||||
|
min_temp_error(1);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if EXTRUDERS > 2
|
||||||
|
#if HEATER_2_RAW_LO_TEMP > HEATER_2_RAW_HI_TEMP
|
||||||
|
if(current_temperature_raw[2] <= maxttemp_raw[2]) {
|
||||||
|
#else
|
||||||
|
if(current_temperature_raw[2] >= maxttemp_raw[2]) {
|
||||||
|
#endif
|
||||||
|
max_temp_error(2);
|
||||||
|
}
|
||||||
|
#if HEATER_2_RAW_LO_TEMP > HEATER_2_RAW_HI_TEMP
|
||||||
|
if(current_temperature_raw[2] >= minttemp_raw[2]) {
|
||||||
|
#else
|
||||||
|
if(current_temperature_raw[2] <= minttemp_raw[2]) {
|
||||||
|
#endif
|
||||||
|
min_temp_error(2);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(BED_MAXTEMP) && (HEATER_BED_PIN > -1)
|
/* No bed MINTEMP error? */
|
||||||
if(current_raw_bed >= bed_maxttemp) {
|
#if defined(BED_MAXTEMP) && (TEMP_SENSOR_BED != 0)
|
||||||
target_raw_bed = 0;
|
# if HEATER_BED_RAW_LO_TEMP > HEATER_BED_RAW_HI_TEMP
|
||||||
|
if(current_temperature_bed_raw <= bed_maxttemp_raw) {
|
||||||
|
#else
|
||||||
|
if(current_temperature_bed_raw >= bed_maxttemp_raw) {
|
||||||
|
#endif
|
||||||
|
target_temperature_bed = 0;
|
||||||
bed_max_temp_error();
|
bed_max_temp_error();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -33,27 +33,16 @@ void manage_heater(); //it is critical that this is called periodically.
|
||||||
|
|
||||||
//low leven conversion routines
|
//low leven conversion routines
|
||||||
// do not use this routines and variables outsie of temperature.cpp
|
// do not use this routines and variables outsie of temperature.cpp
|
||||||
int temp2analog(int celsius, uint8_t e);
|
extern int target_temperature[EXTRUDERS];
|
||||||
int temp2analogBed(int celsius);
|
extern float current_temperature[EXTRUDERS];
|
||||||
float analog2temp(int raw, uint8_t e);
|
extern int target_temperature_bed;
|
||||||
float analog2tempBed(int raw);
|
extern float current_temperature_bed;
|
||||||
extern int target_raw[EXTRUDERS];
|
|
||||||
extern int heatingtarget_raw[EXTRUDERS];
|
|
||||||
extern int current_raw[EXTRUDERS];
|
|
||||||
extern int target_raw_bed;
|
|
||||||
extern int current_raw_bed;
|
|
||||||
#ifdef BED_LIMIT_SWITCHING
|
|
||||||
extern int target_bed_low_temp ;
|
|
||||||
extern int target_bed_high_temp ;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
extern float Kp,Ki,Kd,Kc;
|
extern float Kp,Ki,Kd,Kc;
|
||||||
extern float pid_setpoint[EXTRUDERS];
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef PIDTEMPBED
|
#ifdef PIDTEMPBED
|
||||||
extern float bedKp,bedKi,bedKd;
|
extern float bedKp,bedKi,bedKd;
|
||||||
extern float pid_setpoint_bed;
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//high level conversion routines, for use outside of temperature.cpp
|
//high level conversion routines, for use outside of temperature.cpp
|
||||||
|
@ -61,61 +50,43 @@ extern int current_raw_bed;
|
||||||
//deg=degreeCelsius
|
//deg=degreeCelsius
|
||||||
|
|
||||||
FORCE_INLINE float degHotend(uint8_t extruder) {
|
FORCE_INLINE float degHotend(uint8_t extruder) {
|
||||||
return analog2temp(current_raw[extruder], extruder);
|
return current_temperature[extruder];
|
||||||
};
|
};
|
||||||
|
|
||||||
FORCE_INLINE float degBed() {
|
FORCE_INLINE float degBed() {
|
||||||
return analog2tempBed(current_raw_bed);
|
return current_temperature_bed;
|
||||||
};
|
};
|
||||||
|
|
||||||
FORCE_INLINE float degTargetHotend(uint8_t extruder) {
|
FORCE_INLINE float degTargetHotend(uint8_t extruder) {
|
||||||
return analog2temp(target_raw[extruder], extruder);
|
return target_temperature[extruder];
|
||||||
};
|
};
|
||||||
|
|
||||||
FORCE_INLINE float degTargetBed() {
|
FORCE_INLINE float degTargetBed() {
|
||||||
return analog2tempBed(target_raw_bed);
|
return target_temperature_bed;
|
||||||
};
|
};
|
||||||
|
|
||||||
FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) {
|
FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) {
|
||||||
target_raw[extruder] = temp2analog(celsius, extruder);
|
target_temperature[extruder] = celsius;
|
||||||
#ifdef PIDTEMP
|
|
||||||
pid_setpoint[extruder] = celsius;
|
|
||||||
#endif //PIDTEMP
|
|
||||||
};
|
};
|
||||||
|
|
||||||
FORCE_INLINE void setTargetBed(const float &celsius) {
|
FORCE_INLINE void setTargetBed(const float &celsius) {
|
||||||
|
target_temperature_bed = celsius;
|
||||||
target_raw_bed = temp2analogBed(celsius);
|
|
||||||
#ifdef PIDTEMPBED
|
|
||||||
pid_setpoint_bed = celsius;
|
|
||||||
#elif defined BED_LIMIT_SWITCHING
|
|
||||||
if(celsius>BED_HYSTERESIS)
|
|
||||||
{
|
|
||||||
target_bed_low_temp= temp2analogBed(celsius-BED_HYSTERESIS);
|
|
||||||
target_bed_high_temp= temp2analogBed(celsius+BED_HYSTERESIS);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
target_bed_low_temp=0;
|
|
||||||
target_bed_high_temp=0;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
};
|
};
|
||||||
|
|
||||||
FORCE_INLINE bool isHeatingHotend(uint8_t extruder){
|
FORCE_INLINE bool isHeatingHotend(uint8_t extruder){
|
||||||
return target_raw[extruder] > current_raw[extruder];
|
return target_temperature[extruder] > current_temperature[extruder];
|
||||||
};
|
};
|
||||||
|
|
||||||
FORCE_INLINE bool isHeatingBed() {
|
FORCE_INLINE bool isHeatingBed() {
|
||||||
return target_raw_bed > current_raw_bed;
|
return target_temperature_bed > current_temperature_bed;
|
||||||
};
|
};
|
||||||
|
|
||||||
FORCE_INLINE bool isCoolingHotend(uint8_t extruder) {
|
FORCE_INLINE bool isCoolingHotend(uint8_t extruder) {
|
||||||
return target_raw[extruder] < current_raw[extruder];
|
return target_temperature[extruder] < current_temperature[extruder];
|
||||||
};
|
};
|
||||||
|
|
||||||
FORCE_INLINE bool isCoolingBed() {
|
FORCE_INLINE bool isCoolingBed() {
|
||||||
return target_raw_bed < current_raw_bed;
|
return target_temperature_bed < current_temperature_bed;
|
||||||
};
|
};
|
||||||
|
|
||||||
#define degHotend0() degHotend(0)
|
#define degHotend0() degHotend(0)
|
||||||
|
|
|
@ -461,49 +461,92 @@ const short temptable_55[][2] PROGMEM = {
|
||||||
#define TT_NAME(_N) _TT_NAME(_N)
|
#define TT_NAME(_N) _TT_NAME(_N)
|
||||||
|
|
||||||
#ifdef THERMISTORHEATER_0
|
#ifdef THERMISTORHEATER_0
|
||||||
#define heater_0_temptable TT_NAME(THERMISTORHEATER_0)
|
# define HEATER_0_TEMPTABLE TT_NAME(THERMISTORHEATER_0)
|
||||||
#define heater_0_temptable_len (sizeof(heater_0_temptable)/sizeof(*heater_0_temptable))
|
# define HEATER_0_TEMPTABLE_LEN (sizeof(HEATER_0_TEMPTABLE)/sizeof(*HEATER_0_TEMPTABLE))
|
||||||
#else
|
#else
|
||||||
#ifdef HEATER_0_USES_THERMISTOR
|
# ifdef HEATER_0_USES_THERMISTOR
|
||||||
#error No heater 0 thermistor table specified
|
# error No heater 0 thermistor table specified
|
||||||
#else // HEATER_0_USES_THERMISTOR
|
# else // HEATER_0_USES_THERMISTOR
|
||||||
#define heater_0_temptable 0
|
# define HEATER_0_TEMPTABLE NULL
|
||||||
#define heater_0_temptable_len 0
|
# define HEATER_0_TEMPTABLE_LEN 0
|
||||||
#endif // HEATER_0_USES_THERMISTOR
|
# endif // HEATER_0_USES_THERMISTOR
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//Set the high and low raw values for the heater, this indicates which raw value is a high or low temperature
|
||||||
|
#ifndef HEATER_0_RAW_HI_TEMP
|
||||||
|
# ifdef HEATER_0_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
|
||||||
|
# define HEATER_0_RAW_HI_TEMP 0
|
||||||
|
# define HEATER_0_RAW_LO_TEMP 16383
|
||||||
|
# else //In case of an thermocouple the highest temperature results in the highest ADC value
|
||||||
|
# define HEATER_0_RAW_HI_TEMP 16383
|
||||||
|
# define HEATER_0_RAW_LO_TEMP 0
|
||||||
|
# endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef THERMISTORHEATER_1
|
#ifdef THERMISTORHEATER_1
|
||||||
#define heater_1_temptable TT_NAME(THERMISTORHEATER_1)
|
# define HEATER_1_TEMPTABLE TT_NAME(THERMISTORHEATER_1)
|
||||||
#define heater_1_temptable_len (sizeof(heater_1_temptable)/sizeof(*heater_1_temptable))
|
# define HEATER_1_TEMPTABLE_LEN (sizeof(HEATER_1_TEMPTABLE)/sizeof(*HEATER_1_TEMPTABLE))
|
||||||
#else
|
#else
|
||||||
#ifdef HEATER_1_USES_THERMISTOR
|
# ifdef HEATER_1_USES_THERMISTOR
|
||||||
#error No heater 1 thermistor table specified
|
# error No heater 1 thermistor table specified
|
||||||
#else // HEATER_1_USES_THERMISTOR
|
# else // HEATER_1_USES_THERMISTOR
|
||||||
#define heater_1_temptable 0
|
# define HEATER_1_TEMPTABLE NULL
|
||||||
#define heater_1_temptable_len 0
|
# define HEATER_1_TEMPTABLE_LEN 0
|
||||||
#endif // HEATER_1_USES_THERMISTOR
|
# endif // HEATER_1_USES_THERMISTOR
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//Set the high and low raw values for the heater, this indicates which raw value is a high or low temperature
|
||||||
|
#ifndef HEATER_1_RAW_HI_TEMP
|
||||||
|
# ifdef HEATER_1_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
|
||||||
|
# define HEATER_1_RAW_HI_TEMP 0
|
||||||
|
# define HEATER_1_RAW_LO_TEMP 16383
|
||||||
|
# else //In case of an thermocouple the highest temperature results in the highest ADC value
|
||||||
|
# define HEATER_1_RAW_HI_TEMP 16383
|
||||||
|
# define HEATER_1_RAW_LO_TEMP 0
|
||||||
|
# endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef THERMISTORHEATER_2
|
#ifdef THERMISTORHEATER_2
|
||||||
#define heater_2_temptable TT_NAME(THERMISTORHEATER_2)
|
# define HEATER_2_TEMPTABLE TT_NAME(THERMISTORHEATER_2)
|
||||||
#define heater_2_temptable_len (sizeof(heater_2_temptable)/sizeof(*heater_2_temptable))
|
# define HEATER_2_TEMPTABLE_LEN (sizeof(HEATER_2_TEMPTABLE)/sizeof(*HEATER_2_TEMPTABLE))
|
||||||
#else
|
#else
|
||||||
#ifdef HEATER_2_USES_THERMISTOR
|
# ifdef HEATER_2_USES_THERMISTOR
|
||||||
#error No heater 2 thermistor table specified
|
# error No heater 2 thermistor table specified
|
||||||
#else // HEATER_2_USES_THERMISTOR
|
# else // HEATER_2_USES_THERMISTOR
|
||||||
#define heater_2_temptable 0
|
# define HEATER_2_TEMPTABLE NULL
|
||||||
#define heater_2_temptable_len 0
|
# define HEATER_2_TEMPTABLE_LEN 0
|
||||||
#endif // HEATER_2_USES_THERMISTOR
|
# endif // HEATER_2_USES_THERMISTOR
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//Set the high and low raw values for the heater, this indicates which raw value is a high or low temperature
|
||||||
|
#ifndef HEATER_2_RAW_HI_TEMP
|
||||||
|
# ifdef HEATER_2_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
|
||||||
|
# define HEATER_2_RAW_HI_TEMP 0
|
||||||
|
# define HEATER_2_RAW_LO_TEMP 16383
|
||||||
|
# else //In case of an thermocouple the highest temperature results in the highest ADC value
|
||||||
|
# define HEATER_2_RAW_HI_TEMP 16383
|
||||||
|
# define HEATER_2_RAW_LO_TEMP 0
|
||||||
|
# endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef THERMISTORBED
|
#ifdef THERMISTORBED
|
||||||
#define bedtemptable TT_NAME(THERMISTORBED)
|
# define BEDTEMPTABLE TT_NAME(THERMISTORBED)
|
||||||
#define bedtemptable_len (sizeof(bedtemptable)/sizeof(*bedtemptable))
|
# define BEDTEMPTABLE_LEN (sizeof(BEDTEMPTABLE)/sizeof(*BEDTEMPTABLE))
|
||||||
#else
|
#else
|
||||||
#ifdef BED_USES_THERMISTOR
|
# ifdef BED_USES_THERMISTOR
|
||||||
#error No bed thermistor table specified
|
# error No bed thermistor table specified
|
||||||
#endif // BED_USES_THERMISTOR
|
# endif // BED_USES_THERMISTOR
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//Set the high and low raw values for the heater, this indicates which raw value is a high or low temperature
|
||||||
|
#ifndef HEATER_BED_RAW_HI_TEMP
|
||||||
|
# ifdef BED_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
|
||||||
|
# define HEATER_BED_RAW_HI_TEMP 0
|
||||||
|
# define HEATER_BED_RAW_LO_TEMP 16383
|
||||||
|
# else //In case of an thermocouple the highest temperature results in the highest ADC value
|
||||||
|
# define HEATER_BED_RAW_HI_TEMP 16383
|
||||||
|
# define HEATER_BED_RAW_LO_TEMP 0
|
||||||
|
# endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif //THERMISTORTABLES_H_
|
#endif //THERMISTORTABLES_H_
|
||||||
|
|
||||||
|
|
3713
Marlin/ultralcd.cpp
3713
Marlin/ultralcd.cpp
|
@ -1,29 +1,13 @@
|
||||||
#include "language.h"
|
|
||||||
#include "temperature.h"
|
#include "temperature.h"
|
||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
#ifdef ULTRA_LCD
|
#ifdef ULTRA_LCD
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#include "language.h"
|
#include "language.h"
|
||||||
|
#include "cardreader.h"
|
||||||
#include "temperature.h"
|
#include "temperature.h"
|
||||||
#include "ConfigurationStore.h"
|
#include "ConfigurationStore.h"
|
||||||
|
|
||||||
//===========================================================================
|
/* Configuration settings */
|
||||||
//=============================imported variables============================
|
|
||||||
//===========================================================================
|
|
||||||
|
|
||||||
extern long position[4];
|
|
||||||
#ifdef SDSUPPORT
|
|
||||||
#include "cardreader.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//===========================================================================
|
|
||||||
//=============================public variables============================
|
|
||||||
//===========================================================================
|
|
||||||
volatile uint8_t buttons=0; //the last checked buttons in a bit array.
|
|
||||||
long encoderpos=0;
|
|
||||||
short lastenc=0;
|
|
||||||
|
|
||||||
//TODO: This should be in a preferences file.
|
|
||||||
int plaPreheatHotendTemp;
|
int plaPreheatHotendTemp;
|
||||||
int plaPreheatHPBTemp;
|
int plaPreheatHPBTemp;
|
||||||
int plaPreheatFanSpeed;
|
int plaPreheatFanSpeed;
|
||||||
|
@ -31,222 +15,668 @@ int plaPreheatFanSpeed;
|
||||||
int absPreheatHotendTemp;
|
int absPreheatHotendTemp;
|
||||||
int absPreheatHPBTemp;
|
int absPreheatHPBTemp;
|
||||||
int absPreheatFanSpeed;
|
int absPreheatFanSpeed;
|
||||||
|
/* !Configuration settings */
|
||||||
|
|
||||||
//===========================================================================
|
//Function pointer to menu functions.
|
||||||
//=============================private variables============================
|
typedef void (*menuFunc_t)();
|
||||||
//===========================================================================
|
|
||||||
static char messagetext[LCD_WIDTH]="";
|
|
||||||
|
|
||||||
//return for string conversion routines
|
uint8_t lcd_status_message_level;
|
||||||
static char conv[8];
|
char lcd_status_message[LCD_WIDTH+1] = WELCOME_MSG;
|
||||||
|
|
||||||
LCD_CLASS lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
|
#include "ultralcd_implementation_hitachi_HD44780.h"
|
||||||
|
|
||||||
static unsigned long previous_millis_lcd=0;
|
/** forward declerations **/
|
||||||
//static long previous_millis_buttons=0;
|
/* Different menus */
|
||||||
|
static void lcd_status_screen();
|
||||||
|
#ifdef ULTIPANEL
|
||||||
|
static void lcd_main_menu();
|
||||||
|
static void lcd_tune_menu();
|
||||||
|
static void lcd_prepare_menu();
|
||||||
|
static void lcd_move_menu();
|
||||||
|
static void lcd_control_menu();
|
||||||
|
static void lcd_control_temperature_menu();
|
||||||
|
static void lcd_control_temperature_preheat_pla_settings_menu();
|
||||||
|
static void lcd_control_temperature_preheat_abs_settings_menu();
|
||||||
|
static void lcd_control_motion_menu();
|
||||||
|
static void lcd_control_retract_menu();
|
||||||
|
static void lcd_sdcard_menu();
|
||||||
|
|
||||||
|
static void lcd_quick_feedback();//Cause an LCD refresh, and give the user visual or audiable feedback that something has happend
|
||||||
|
|
||||||
#ifdef NEWPANEL
|
/* Different types of actions that can be used in menuitems. */
|
||||||
static unsigned long blocking=0;
|
static void menu_action_back(menuFunc_t data);
|
||||||
#else
|
static void menu_action_submenu(menuFunc_t data);
|
||||||
static unsigned long blocking[8]={0,0,0,0,0,0,0,0};
|
static void menu_action_gcode(const char* pgcode);
|
||||||
|
static void menu_action_function(menuFunc_t data);
|
||||||
|
static void menu_action_sdfile(const char* filename, char* longFilename);
|
||||||
|
static void menu_action_sddirectory(const char* filename, char* longFilename);
|
||||||
|
static void menu_action_setting_edit_bool(const char* pstr, bool* ptr);
|
||||||
|
static void menu_action_setting_edit_int3(const char* pstr, int* ptr, int minValue, int maxValue);
|
||||||
|
static void menu_action_setting_edit_float3(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||||
|
static void menu_action_setting_edit_float32(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||||
|
static void menu_action_setting_edit_float5(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||||
|
static void menu_action_setting_edit_float51(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||||
|
static void menu_action_setting_edit_float52(const char* pstr, float* ptr, float minValue, float maxValue);
|
||||||
|
static void menu_action_setting_edit_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue);
|
||||||
|
|
||||||
|
#define ENCODER_STEPS_PER_MENU_ITEM 5
|
||||||
|
|
||||||
|
/* Helper macros for menus */
|
||||||
|
#define START_MENU() do { \
|
||||||
|
if (encoderPosition > 0x8000) encoderPosition = 0; \
|
||||||
|
if (encoderPosition / ENCODER_STEPS_PER_MENU_ITEM < currentMenuViewOffset) currentMenuViewOffset = encoderPosition / ENCODER_STEPS_PER_MENU_ITEM;\
|
||||||
|
uint8_t _lineNr = currentMenuViewOffset, _menuItemNr; \
|
||||||
|
for(uint8_t _drawLineNr = 0; _drawLineNr < LCD_HEIGHT; _drawLineNr++, _lineNr++) { \
|
||||||
|
_menuItemNr = 0;
|
||||||
|
#define MENU_ITEM(type, label, args...) do { \
|
||||||
|
if (_menuItemNr == _lineNr) { \
|
||||||
|
if (lcdDrawUpdate) { \
|
||||||
|
if ((encoderPosition / ENCODER_STEPS_PER_MENU_ITEM) == _menuItemNr) { \
|
||||||
|
lcd_implementation_drawmenu_ ## type ## _selected (_drawLineNr, PSTR(label) , ## args ); \
|
||||||
|
}else{\
|
||||||
|
lcd_implementation_drawmenu_ ## type (_drawLineNr, PSTR(label) , ## args ); \
|
||||||
|
}\
|
||||||
|
}\
|
||||||
|
if (LCD_CLICKED && (encoderPosition / ENCODER_STEPS_PER_MENU_ITEM) == _menuItemNr) {\
|
||||||
|
lcd_quick_feedback(); \
|
||||||
|
menu_action_ ## type ( args ); \
|
||||||
|
return;\
|
||||||
|
}\
|
||||||
|
}\
|
||||||
|
_menuItemNr++;\
|
||||||
|
} while(0)
|
||||||
|
#define MENU_ITEM_DUMMY() do { _menuItemNr++; } while(0)
|
||||||
|
#define MENU_ITEM_EDIT(type, label, args...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label) , ## args )
|
||||||
|
#define END_MENU() \
|
||||||
|
if (encoderPosition / ENCODER_STEPS_PER_MENU_ITEM >= _menuItemNr) encoderPosition = _menuItemNr * ENCODER_STEPS_PER_MENU_ITEM - 1; \
|
||||||
|
if ((uint8_t)(encoderPosition / ENCODER_STEPS_PER_MENU_ITEM) >= currentMenuViewOffset + LCD_HEIGHT) { currentMenuViewOffset = (encoderPosition / ENCODER_STEPS_PER_MENU_ITEM) - LCD_HEIGHT + 1; lcdDrawUpdate = 1; _lineNr = currentMenuViewOffset - 1; _drawLineNr = -1; } \
|
||||||
|
} } while(0)
|
||||||
|
|
||||||
|
/** Used variables to keep track of the menu */
|
||||||
|
volatile uint8_t buttons;//Contains the bits of the currently pressed buttons.
|
||||||
|
|
||||||
|
uint8_t currentMenuViewOffset; /* scroll offset in the current menu */
|
||||||
|
uint32_t blocking_enc;
|
||||||
|
uint8_t lastEncoderBits;
|
||||||
|
int8_t encoderDiff; /* encoderDiff is updated from interrupt context and added to encoderPosition every LCD update */
|
||||||
|
uint32_t encoderPosition;
|
||||||
|
#if (SDCARDDETECT > -1)
|
||||||
|
bool lcd_oldcardstatus;
|
||||||
|
#endif
|
||||||
|
#endif//ULTIPANEL
|
||||||
|
|
||||||
|
menuFunc_t currentMenu = lcd_status_screen; /* function pointer to the currently active menu */
|
||||||
|
uint32_t lcd_next_update_millis;
|
||||||
|
uint8_t lcd_status_update_delay;
|
||||||
|
uint8_t lcdDrawUpdate = 2; /* Set to none-zero when the LCD needs to draw, decreased after every draw. Set to 2 in LCD routines so the LCD gets atleast 1 full redraw (first redraw is partial) */
|
||||||
|
|
||||||
|
//prevMenu and prevEncoderPosition are used to store the previous menu location when editing settings.
|
||||||
|
menuFunc_t prevMenu = NULL;
|
||||||
|
uint16_t prevEncoderPosition;
|
||||||
|
//Variables used when editing values.
|
||||||
|
const char* editLabel;
|
||||||
|
void* editValue;
|
||||||
|
int32_t minEditValue, maxEditValue;
|
||||||
|
|
||||||
|
/* Main status screen. It's up to the implementation specific part to show what is needed. As this is very display dependend */
|
||||||
|
static void lcd_status_screen()
|
||||||
|
{
|
||||||
|
if (lcd_status_update_delay)
|
||||||
|
lcd_status_update_delay--;
|
||||||
|
else
|
||||||
|
lcdDrawUpdate = 1;
|
||||||
|
if (lcdDrawUpdate)
|
||||||
|
{
|
||||||
|
lcd_implementation_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 */
|
||||||
|
}
|
||||||
|
#ifdef ULTIPANEL
|
||||||
|
if (LCD_CLICKED)
|
||||||
|
{
|
||||||
|
currentMenu = lcd_main_menu;
|
||||||
|
lcd_quick_feedback();
|
||||||
|
}
|
||||||
|
if (abs(encoderPosition / 2) > 1)
|
||||||
|
feedmultiply += encoderPosition / 2;
|
||||||
|
encoderPosition = 0;
|
||||||
|
if (feedmultiply < 10)
|
||||||
|
feedmultiply = 10;
|
||||||
|
if (feedmultiply > 999)
|
||||||
|
feedmultiply = 999;
|
||||||
|
#endif//ULTIPANEL
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef ULTIPANEL
|
||||||
|
static void lcd_return_to_status()
|
||||||
|
{
|
||||||
|
encoderPosition = 0;
|
||||||
|
currentMenu = lcd_status_screen;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_sdcard_pause()
|
||||||
|
{
|
||||||
|
card.pauseSDPrint();
|
||||||
|
}
|
||||||
|
static void lcd_sdcard_resume()
|
||||||
|
{
|
||||||
|
card.startFileprint();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_sdcard_stop()
|
||||||
|
{
|
||||||
|
card.sdprinting = false;
|
||||||
|
card.closefile();
|
||||||
|
quickStop();
|
||||||
|
if(SD_FINISHED_STEPPERRELEASE)
|
||||||
|
{
|
||||||
|
enquecommand_P(PSTR(SD_FINISHED_RELEASECOMMAND));
|
||||||
|
}
|
||||||
|
autotempShutdown();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Menu implementation */
|
||||||
|
static void lcd_main_menu()
|
||||||
|
{
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_WATCH, lcd_status_screen);
|
||||||
|
if (IS_SD_PRINTING)
|
||||||
|
{
|
||||||
|
MENU_ITEM(submenu, MSG_TUNE, lcd_tune_menu);
|
||||||
|
}else{
|
||||||
|
MENU_ITEM(submenu, MSG_PREPARE, lcd_prepare_menu);
|
||||||
|
}
|
||||||
|
MENU_ITEM(submenu, MSG_CONTROL, lcd_control_menu);
|
||||||
|
#ifdef SDSUPPORT
|
||||||
|
if (card.cardOK)
|
||||||
|
{
|
||||||
|
if (card.isFileOpen())
|
||||||
|
{
|
||||||
|
if (card.sdprinting)
|
||||||
|
MENU_ITEM(function, MSG_PAUSE_PRINT, lcd_sdcard_pause);
|
||||||
|
else
|
||||||
|
MENU_ITEM(function, MSG_RESUME_PRINT, lcd_sdcard_resume);
|
||||||
|
MENU_ITEM(function, MSG_STOP_PRINT, lcd_sdcard_stop);
|
||||||
|
}else{
|
||||||
|
MENU_ITEM(submenu, MSG_CARD_MENU, lcd_sdcard_menu);
|
||||||
|
}
|
||||||
|
}else{
|
||||||
|
MENU_ITEM(submenu, MSG_NO_CARD, lcd_sdcard_menu);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef SDSUPPORT
|
||||||
|
static void lcd_autostart_sd()
|
||||||
|
{
|
||||||
|
card.lastnr=0;
|
||||||
|
card.setroot();
|
||||||
|
card.checkautostart(true);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static MainMenu menu;
|
void lcd_preheat_pla()
|
||||||
|
|
||||||
|
|
||||||
void lcdProgMemprint(const char *str)
|
|
||||||
{
|
{
|
||||||
char ch=pgm_read_byte(str);
|
setTargetHotend0(plaPreheatHotendTemp);
|
||||||
while(ch)
|
setTargetHotend1(plaPreheatHotendTemp);
|
||||||
{
|
setTargetHotend2(plaPreheatHotendTemp);
|
||||||
lcd.print(ch);
|
setTargetBed(plaPreheatHPBTemp);
|
||||||
ch=pgm_read_byte(++str);
|
#if FAN_PIN > -1
|
||||||
}
|
fanSpeed = plaPreheatFanSpeed;
|
||||||
}
|
analogWrite(FAN_PIN, fanSpeed);
|
||||||
#define LCD_PRINT_PGM(x) lcdProgMemprint(PSTR(x))
|
#endif
|
||||||
|
lcd_return_to_status();
|
||||||
|
|
||||||
//===========================================================================
|
|
||||||
//=============================functions ============================
|
|
||||||
//===========================================================================
|
|
||||||
|
|
||||||
int intround(const float &x){return int(0.5+x);}
|
|
||||||
|
|
||||||
void lcd_setstatus(const char* message)
|
|
||||||
{
|
|
||||||
strncpy(messagetext,message,LCD_WIDTH);
|
|
||||||
messagetext[strlen(message)]=0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void lcd_setstatuspgm(const char* message)
|
void lcd_preheat_abs()
|
||||||
{
|
{
|
||||||
char ch=pgm_read_byte(message);
|
setTargetHotend0(absPreheatHotendTemp);
|
||||||
char *target=messagetext;
|
setTargetHotend1(absPreheatHotendTemp);
|
||||||
uint8_t cnt=0;
|
setTargetHotend2(absPreheatHotendTemp);
|
||||||
while(ch &&cnt<LCD_WIDTH)
|
setTargetBed(absPreheatHPBTemp);
|
||||||
{
|
#if FAN_PIN > -1
|
||||||
*target=ch;
|
fanSpeed = absPreheatFanSpeed;
|
||||||
target++;
|
analogWrite(FAN_PIN, fanSpeed);
|
||||||
cnt++;
|
#endif
|
||||||
ch=pgm_read_byte(++message);
|
lcd_return_to_status();
|
||||||
}
|
|
||||||
*target=0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void lcd_setalertstatuspgm(const char* message)
|
static void lcd_tune_menu()
|
||||||
{
|
{
|
||||||
lcd_setstatuspgm(message);
|
START_MENU();
|
||||||
menu.showStatus();
|
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_SPEED, &feedmultiply, 10, 999);
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
|
||||||
|
#if TEMP_SENSOR_1 != 0
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_NOZZLE1, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
|
||||||
|
#endif
|
||||||
|
#if TEMP_SENSOR_2 != 0
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_NOZZLE2, &target_temperature[2], 0, HEATER_2_MAXTEMP - 15);
|
||||||
|
#endif
|
||||||
|
#if TEMP_SENSOR_BED != 0
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15);
|
||||||
|
#endif
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_FLOW, &extrudemultiply, 10, 999);
|
||||||
|
END_MENU();
|
||||||
}
|
}
|
||||||
|
|
||||||
FORCE_INLINE void clear()
|
static void lcd_prepare_menu()
|
||||||
{
|
{
|
||||||
lcd.clear();
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
|
||||||
|
#ifdef SDSUPPORT
|
||||||
|
//MENU_ITEM(function, MSG_AUTOSTART, lcd_autostart_sd);
|
||||||
|
#endif
|
||||||
|
MENU_ITEM(gcode, MSG_DISABLE_STEPPERS, PSTR("M84"));
|
||||||
|
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
|
||||||
|
//MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0"));
|
||||||
|
MENU_ITEM(function, MSG_PREHEAT_PLA, lcd_preheat_pla);
|
||||||
|
MENU_ITEM(function, MSG_PREHEAT_ABS, lcd_preheat_abs);
|
||||||
|
MENU_ITEM(gcode, MSG_COOLDOWN, PSTR("M104 S0\nM140 S0"));
|
||||||
|
MENU_ITEM(submenu, MSG_MOVE_AXIS, lcd_move_menu);
|
||||||
|
END_MENU();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
float move_menu_scale;
|
||||||
|
static void lcd_move_menu_axis();
|
||||||
|
|
||||||
|
static void lcd_move_x()
|
||||||
|
{
|
||||||
|
if (encoderPosition != 0)
|
||||||
|
{
|
||||||
|
current_position[X_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
||||||
|
if (current_position[X_AXIS] < X_MIN_POS)
|
||||||
|
current_position[X_AXIS] = X_MIN_POS;
|
||||||
|
if (current_position[X_AXIS] > X_MAX_POS)
|
||||||
|
current_position[X_AXIS] = X_MAX_POS;
|
||||||
|
encoderPosition = 0;
|
||||||
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600, active_extruder);
|
||||||
|
lcdDrawUpdate = 1;
|
||||||
|
}
|
||||||
|
if (lcdDrawUpdate)
|
||||||
|
{
|
||||||
|
lcd_implementation_drawedit(PSTR("X"), ftostr31(current_position[X_AXIS]));
|
||||||
|
}
|
||||||
|
if (LCD_CLICKED)
|
||||||
|
{
|
||||||
|
lcd_quick_feedback();
|
||||||
|
currentMenu = lcd_move_menu_axis;
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
static void lcd_move_y()
|
||||||
|
{
|
||||||
|
if (encoderPosition != 0)
|
||||||
|
{
|
||||||
|
current_position[Y_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
||||||
|
if (current_position[Y_AXIS] < Y_MIN_POS)
|
||||||
|
current_position[Y_AXIS] = Y_MIN_POS;
|
||||||
|
if (current_position[Y_AXIS] > Y_MAX_POS)
|
||||||
|
current_position[Y_AXIS] = Y_MAX_POS;
|
||||||
|
encoderPosition = 0;
|
||||||
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600, active_extruder);
|
||||||
|
lcdDrawUpdate = 1;
|
||||||
|
}
|
||||||
|
if (lcdDrawUpdate)
|
||||||
|
{
|
||||||
|
lcd_implementation_drawedit(PSTR("Y"), ftostr31(current_position[Y_AXIS]));
|
||||||
|
}
|
||||||
|
if (LCD_CLICKED)
|
||||||
|
{
|
||||||
|
lcd_quick_feedback();
|
||||||
|
currentMenu = lcd_move_menu_axis;
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
static void lcd_move_z()
|
||||||
|
{
|
||||||
|
if (encoderPosition != 0)
|
||||||
|
{
|
||||||
|
current_position[Z_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
||||||
|
if (current_position[Z_AXIS] < Z_MIN_POS)
|
||||||
|
current_position[Z_AXIS] = Z_MIN_POS;
|
||||||
|
if (current_position[Z_AXIS] > Z_MAX_POS)
|
||||||
|
current_position[Z_AXIS] = Z_MAX_POS;
|
||||||
|
encoderPosition = 0;
|
||||||
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 60, active_extruder);
|
||||||
|
lcdDrawUpdate = 1;
|
||||||
|
}
|
||||||
|
if (lcdDrawUpdate)
|
||||||
|
{
|
||||||
|
lcd_implementation_drawedit(PSTR("Z"), ftostr31(current_position[Z_AXIS]));
|
||||||
|
}
|
||||||
|
if (LCD_CLICKED)
|
||||||
|
{
|
||||||
|
lcd_quick_feedback();
|
||||||
|
currentMenu = lcd_move_menu_axis;
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
static void lcd_move_e()
|
||||||
|
{
|
||||||
|
if (encoderPosition != 0)
|
||||||
|
{
|
||||||
|
current_position[E_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
||||||
|
encoderPosition = 0;
|
||||||
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 20, active_extruder);
|
||||||
|
lcdDrawUpdate = 1;
|
||||||
|
}
|
||||||
|
if (lcdDrawUpdate)
|
||||||
|
{
|
||||||
|
lcd_implementation_drawedit(PSTR("Extruder"), ftostr31(current_position[E_AXIS]));
|
||||||
|
}
|
||||||
|
if (LCD_CLICKED)
|
||||||
|
{
|
||||||
|
lcd_quick_feedback();
|
||||||
|
currentMenu = lcd_move_menu_axis;
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_move_menu_axis()
|
||||||
|
{
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_MOVE_AXIS, lcd_move_menu);
|
||||||
|
MENU_ITEM(submenu, "Move X", lcd_move_x);
|
||||||
|
MENU_ITEM(submenu, "Move Y", lcd_move_y);
|
||||||
|
MENU_ITEM(submenu, "Move Z", lcd_move_z);
|
||||||
|
if (move_menu_scale < 10.0)
|
||||||
|
{
|
||||||
|
MENU_ITEM(submenu, "Extruder", lcd_move_e);
|
||||||
|
}
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_move_menu_10mm()
|
||||||
|
{
|
||||||
|
move_menu_scale = 10.0;
|
||||||
|
lcd_move_menu_axis();
|
||||||
|
}
|
||||||
|
static void lcd_move_menu_1mm()
|
||||||
|
{
|
||||||
|
move_menu_scale = 1.0;
|
||||||
|
lcd_move_menu_axis();
|
||||||
|
}
|
||||||
|
static void lcd_move_menu_01mm()
|
||||||
|
{
|
||||||
|
move_menu_scale = 0.1;
|
||||||
|
lcd_move_menu_axis();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_move_menu()
|
||||||
|
{
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
|
||||||
|
MENU_ITEM(submenu, "Move 10mm", lcd_move_menu_10mm);
|
||||||
|
MENU_ITEM(submenu, "Move 1mm", lcd_move_menu_1mm);
|
||||||
|
MENU_ITEM(submenu, "Move 0.1mm", lcd_move_menu_01mm);
|
||||||
|
//TODO:X,Y,Z,E
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_control_menu()
|
||||||
|
{
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
|
||||||
|
MENU_ITEM(submenu, MSG_TEMPERATURE, lcd_control_temperature_menu);
|
||||||
|
MENU_ITEM(submenu, MSG_MOTION, lcd_control_motion_menu);
|
||||||
|
#ifdef FWRETRACT
|
||||||
|
MENU_ITEM(submenu, MSG_RETRACT, lcd_control_retract_menu);
|
||||||
|
#endif
|
||||||
|
#ifdef EEPROM_SETTINGS
|
||||||
|
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
|
||||||
|
MENU_ITEM(function, MSG_LOAD_EPROM, Config_RetrieveSettings);
|
||||||
|
#endif
|
||||||
|
MENU_ITEM(function, MSG_RESTORE_FAILSAFE, Config_ResetDefault);
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_control_temperature_menu()
|
||||||
|
{
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
|
||||||
|
#if TEMP_SENSOR_1 != 0
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_NOZZLE1, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
|
||||||
|
#endif
|
||||||
|
#if TEMP_SENSOR_2 != 0
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_NOZZLE2, &target_temperature[2], 0, HEATER_2_MAXTEMP - 15);
|
||||||
|
#endif
|
||||||
|
#if TEMP_SENSOR_BED != 0
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15);
|
||||||
|
#endif
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
|
||||||
|
#ifdef AUTOTEMP
|
||||||
|
MENU_ITEM_EDIT(bool, MSG_AUTOTEMP, &autotemp_enabled);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_MIN, &autotemp_min, 0, HEATER_0_MAXTEMP - 15);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_MAX, &autotemp_max, 0, HEATER_0_MAXTEMP - 15);
|
||||||
|
MENU_ITEM_EDIT(float32, MSG_FACTOR, &autotemp_factor, 0.0, 1.0);
|
||||||
|
#endif
|
||||||
|
#ifdef PIDTEMP
|
||||||
|
MENU_ITEM_EDIT(float52, MSG_PID_P, &Kp, 1, 9990);
|
||||||
|
//TODO, I and D should have a PID_dT multiplier (Ki = PID_I * PID_dT, Kd = PID_D / PID_dT)
|
||||||
|
MENU_ITEM_EDIT(float52, MSG_PID_I, &Ki, 1, 9990);
|
||||||
|
MENU_ITEM_EDIT(float52, MSG_PID_D, &Kd, 1, 9990);
|
||||||
|
# ifdef PID_ADD_EXTRUSION_RATE
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_PID_C, &Kc, 1, 9990);
|
||||||
|
# endif//PID_ADD_EXTRUSION_RATE
|
||||||
|
#endif//PIDTEMP
|
||||||
|
MENU_ITEM(submenu, MSG_PREHEAT_PLA_SETTINGS, lcd_control_temperature_preheat_pla_settings_menu);
|
||||||
|
MENU_ITEM(submenu, MSG_PREHEAT_ABS_SETTINGS, lcd_control_temperature_preheat_abs_settings_menu);
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_control_temperature_preheat_pla_settings_menu()
|
||||||
|
{
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu);
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &plaPreheatFanSpeed, 0, 255);
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &plaPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15);
|
||||||
|
#if TEMP_SENSOR_BED != 0
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_BED, &plaPreheatHPBTemp, 0, BED_MAXTEMP - 15);
|
||||||
|
#endif
|
||||||
|
#ifdef EEPROM_SETTINGS
|
||||||
|
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
|
||||||
|
#endif
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_control_temperature_preheat_abs_settings_menu()
|
||||||
|
{
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu);
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &absPreheatFanSpeed, 0, 255);
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &absPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15);
|
||||||
|
#if TEMP_SENSOR_BED != 0
|
||||||
|
MENU_ITEM_EDIT(int3, MSG_BED, &absPreheatHPBTemp, 0, BED_MAXTEMP - 15);
|
||||||
|
#endif
|
||||||
|
#ifdef EEPROM_SETTINGS
|
||||||
|
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
|
||||||
|
#endif
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
|
||||||
|
static void lcd_control_motion_menu()
|
||||||
|
{
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
|
||||||
|
MENU_ITEM_EDIT(float5, MSG_ACC, &acceleration, 500, 99000);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_VXY_JERK, &max_xy_jerk, 1, 990);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_VMAX MSG_X, &max_feedrate[X_AXIS], 1, 999);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_VMAX MSG_Y, &max_feedrate[Y_AXIS], 1, 999);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_VMAX MSG_Z, &max_feedrate[Z_AXIS], 1, 999);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E, &max_feedrate[E_AXIS], 1, 999);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_VMIN, &minimumfeedrate, 0, 999);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_VTRAV_MIN, &mintravelfeedrate, 0, 999);
|
||||||
|
MENU_ITEM_EDIT(long5, MSG_AMAX MSG_X, &max_acceleration_units_per_sq_second[X_AXIS], 100, 99000);
|
||||||
|
MENU_ITEM_EDIT(long5, MSG_AMAX MSG_Y, &max_acceleration_units_per_sq_second[Y_AXIS], 100, 99000);
|
||||||
|
MENU_ITEM_EDIT(long5, MSG_AMAX MSG_Z, &max_acceleration_units_per_sq_second[Z_AXIS], 100, 99000);
|
||||||
|
MENU_ITEM_EDIT(long5, MSG_AMAX MSG_E, &max_acceleration_units_per_sq_second[E_AXIS], 100, 99000);
|
||||||
|
MENU_ITEM_EDIT(float5, MSG_A_RETRACT, &retract_acceleration, 100, 99000);
|
||||||
|
MENU_ITEM_EDIT(float52, MSG_XSTEPS, &axis_steps_per_unit[X_AXIS], 5, 9999);
|
||||||
|
MENU_ITEM_EDIT(float52, MSG_YSTEPS, &axis_steps_per_unit[Y_AXIS], 5, 9999);
|
||||||
|
MENU_ITEM_EDIT(float51, MSG_ZSTEPS, &axis_steps_per_unit[Z_AXIS], 5, 9999);
|
||||||
|
MENU_ITEM_EDIT(float51, MSG_ESTEPS, &axis_steps_per_unit[E_AXIS], 5, 9999);
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef FWRETRACT
|
||||||
|
static void lcd_control_retract_menu()
|
||||||
|
{
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
|
||||||
|
MENU_ITEM_EDIT(bool, MSG_AUTORETRACT, &autoretract_enabled);
|
||||||
|
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT, &retract_length, 0, 100);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_CONTROL_RETRACTF, &retract_feedrate, 1, 999);
|
||||||
|
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_ZLIFT, &retract_zlift, 0, 999);
|
||||||
|
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_RECOVER, &retract_recover_length, 0, 100);
|
||||||
|
MENU_ITEM_EDIT(float3, MSG_CONTROL_RETRACT_RECOVERF, &retract_recover_feedrate, 1, 999);
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if SDCARDDETECT == -1
|
||||||
|
static void lcd_sd_refresh()
|
||||||
|
{
|
||||||
|
card.initsd();
|
||||||
|
currentMenuViewOffset = 0;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
static void lcd_sd_updir()
|
||||||
|
{
|
||||||
|
card.updir();
|
||||||
|
currentMenuViewOffset = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void lcd_sdcard_menu()
|
||||||
|
{
|
||||||
|
uint16_t fileCnt = card.getnrfilenames();
|
||||||
|
START_MENU();
|
||||||
|
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
|
||||||
|
card.getWorkDirName();
|
||||||
|
if(card.filename[0]=='/')
|
||||||
|
{
|
||||||
|
#if SDCARDDETECT == -1
|
||||||
|
MENU_ITEM(function, LCD_STR_REFRESH MSG_REFRESH, lcd_sd_refresh);
|
||||||
|
#endif
|
||||||
|
}else{
|
||||||
|
MENU_ITEM(function, LCD_STR_FOLDER "..", lcd_sd_updir);
|
||||||
|
}
|
||||||
|
|
||||||
|
for(uint16_t i=0;i<fileCnt;i++)
|
||||||
|
{
|
||||||
|
if (_menuItemNr == _lineNr)
|
||||||
|
{
|
||||||
|
card.getfilename(i);
|
||||||
|
if (card.filenameIsDir)
|
||||||
|
{
|
||||||
|
MENU_ITEM(sddirectory, MSG_CARD_MENU, card.filename, card.longFilename);
|
||||||
|
}else{
|
||||||
|
MENU_ITEM(sdfile, MSG_CARD_MENU, card.filename, card.longFilename);
|
||||||
|
}
|
||||||
|
}else{
|
||||||
|
MENU_ITEM_DUMMY();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
END_MENU();
|
||||||
|
}
|
||||||
|
|
||||||
|
#define menu_edit_type(_type, _name, _strFunc, scale) \
|
||||||
|
void menu_edit_ ## _name () \
|
||||||
|
{ \
|
||||||
|
if ((int32_t)encoderPosition < minEditValue) \
|
||||||
|
encoderPosition = minEditValue; \
|
||||||
|
if ((int32_t)encoderPosition > maxEditValue) \
|
||||||
|
encoderPosition = maxEditValue; \
|
||||||
|
if (lcdDrawUpdate) \
|
||||||
|
lcd_implementation_drawedit(editLabel, _strFunc(((_type)encoderPosition) / scale)); \
|
||||||
|
if (LCD_CLICKED) \
|
||||||
|
{ \
|
||||||
|
*((_type*)editValue) = ((_type)encoderPosition) / scale; \
|
||||||
|
lcd_quick_feedback(); \
|
||||||
|
currentMenu = prevMenu; \
|
||||||
|
encoderPosition = prevEncoderPosition; \
|
||||||
|
} \
|
||||||
|
} \
|
||||||
|
static void menu_action_setting_edit_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue) \
|
||||||
|
{ \
|
||||||
|
prevMenu = currentMenu; \
|
||||||
|
prevEncoderPosition = encoderPosition; \
|
||||||
|
\
|
||||||
|
lcdDrawUpdate = 2; \
|
||||||
|
currentMenu = menu_edit_ ## _name; \
|
||||||
|
\
|
||||||
|
editLabel = pstr; \
|
||||||
|
editValue = ptr; \
|
||||||
|
minEditValue = minValue * scale; \
|
||||||
|
maxEditValue = maxValue * scale; \
|
||||||
|
encoderPosition = (*ptr) * scale; \
|
||||||
|
}
|
||||||
|
menu_edit_type(int, int3, itostr3, 1)
|
||||||
|
menu_edit_type(float, float3, ftostr3, 1)
|
||||||
|
menu_edit_type(float, float32, ftostr32, 100)
|
||||||
|
menu_edit_type(float, float5, ftostr5, 0.01)
|
||||||
|
menu_edit_type(float, float51, ftostr51, 10)
|
||||||
|
menu_edit_type(float, float52, ftostr52, 100)
|
||||||
|
menu_edit_type(unsigned long, long5, ftostr5, 0.01)
|
||||||
|
|
||||||
|
/** End of menus **/
|
||||||
|
|
||||||
|
static void lcd_quick_feedback()
|
||||||
|
{
|
||||||
|
lcdDrawUpdate = 2;
|
||||||
|
blocking_enc = millis() + 500;
|
||||||
|
lcd_implementation_quick_feedback();
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Menu action functions **/
|
||||||
|
static void menu_action_back(menuFunc_t data)
|
||||||
|
{
|
||||||
|
currentMenu = data;
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
static void menu_action_submenu(menuFunc_t data)
|
||||||
|
{
|
||||||
|
currentMenu = data;
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
static void menu_action_gcode(const char* pgcode)
|
||||||
|
{
|
||||||
|
enquecommand_P(pgcode);
|
||||||
|
}
|
||||||
|
static void menu_action_function(menuFunc_t data)
|
||||||
|
{
|
||||||
|
(*data)();
|
||||||
|
}
|
||||||
|
static void menu_action_sdfile(const char* filename, char* longFilename)
|
||||||
|
{
|
||||||
|
char cmd[30];
|
||||||
|
char* c;
|
||||||
|
sprintf_P(cmd, PSTR("M23 %s"), filename);
|
||||||
|
for(c = &cmd[4]; *c; c++)
|
||||||
|
*c = tolower(*c);
|
||||||
|
enquecommand(cmd);
|
||||||
|
enquecommand_P(PSTR("M24"));
|
||||||
|
lcd_return_to_status();
|
||||||
|
}
|
||||||
|
static void menu_action_sddirectory(const char* filename, char* longFilename)
|
||||||
|
{
|
||||||
|
card.chdir(filename);
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
static void menu_action_setting_edit_bool(const char* pstr, bool* ptr)
|
||||||
|
{
|
||||||
|
*ptr = !(*ptr);
|
||||||
|
}
|
||||||
|
#endif//ULTIPANEL
|
||||||
|
|
||||||
|
/** LCD API **/
|
||||||
void lcd_init()
|
void lcd_init()
|
||||||
{
|
{
|
||||||
//beep();
|
lcd_implementation_init();
|
||||||
#ifdef ULTIPANEL
|
|
||||||
lcd_buttons_init();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
byte Degree[8] =
|
#ifdef NEWPANEL
|
||||||
{
|
|
||||||
B01100,
|
|
||||||
B10010,
|
|
||||||
B10010,
|
|
||||||
B01100,
|
|
||||||
B00000,
|
|
||||||
B00000,
|
|
||||||
B00000,
|
|
||||||
B00000
|
|
||||||
};
|
|
||||||
byte Thermometer[8] =
|
|
||||||
{
|
|
||||||
B00100,
|
|
||||||
B01010,
|
|
||||||
B01010,
|
|
||||||
B01010,
|
|
||||||
B01010,
|
|
||||||
B10001,
|
|
||||||
B10001,
|
|
||||||
B01110
|
|
||||||
};
|
|
||||||
byte uplevel[8]={
|
|
||||||
B00100,
|
|
||||||
B01110,
|
|
||||||
B11111,
|
|
||||||
B00100,
|
|
||||||
B11100,
|
|
||||||
B00000,
|
|
||||||
B00000,
|
|
||||||
B00000
|
|
||||||
}; //thanks joris
|
|
||||||
byte refresh[8]={
|
|
||||||
B00000,
|
|
||||||
B00110,
|
|
||||||
B11001,
|
|
||||||
B11000,
|
|
||||||
B00011,
|
|
||||||
B10011,
|
|
||||||
B01100,
|
|
||||||
B00000,
|
|
||||||
}; //thanks joris
|
|
||||||
byte folder [8]={
|
|
||||||
B00000,
|
|
||||||
B11100,
|
|
||||||
B11111,
|
|
||||||
B10001,
|
|
||||||
B10001,
|
|
||||||
B11111,
|
|
||||||
B00000,
|
|
||||||
B00000
|
|
||||||
}; //thanks joris
|
|
||||||
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
|
||||||
lcd.createChar(1,Degree);
|
|
||||||
lcd.createChar(2,Thermometer);
|
|
||||||
lcd.createChar(3,uplevel);
|
|
||||||
lcd.createChar(4,refresh);
|
|
||||||
lcd.createChar(5,folder);
|
|
||||||
LCD_MESSAGEPGM(WELCOME_MSG);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void beep()
|
|
||||||
{
|
|
||||||
//return;
|
|
||||||
#ifdef ULTIPANEL
|
|
||||||
#if (BEEPER > -1)
|
|
||||||
{
|
|
||||||
pinMode(BEEPER,OUTPUT);
|
|
||||||
for(int8_t i=0;i<20;i++){
|
|
||||||
WRITE(BEEPER,HIGH);
|
|
||||||
delay(5);
|
|
||||||
WRITE(BEEPER,LOW);
|
|
||||||
delay(5);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
void beepshort()
|
|
||||||
{
|
|
||||||
//return;
|
|
||||||
#ifdef ULTIPANEL
|
|
||||||
#if (BEEPER > -1)
|
|
||||||
{
|
|
||||||
pinMode(BEEPER,OUTPUT);
|
|
||||||
for(int8_t i=0;i<10;i++){
|
|
||||||
WRITE(BEEPER,HIGH);
|
|
||||||
delay(3);
|
|
||||||
WRITE(BEEPER,LOW);
|
|
||||||
delay(3);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
void lcd_update()
|
|
||||||
{
|
|
||||||
#ifdef ULTIPANEL
|
|
||||||
static uint8_t oldbuttons=0;
|
|
||||||
//static long previous_millis_buttons=0;
|
|
||||||
//static long previous_lcdinit=0;
|
|
||||||
// buttons_check(); // Done in temperature interrupt
|
|
||||||
//previous_millis_buttons=millis();
|
|
||||||
unsigned long ms=millis();
|
|
||||||
for(int8_t i=0; i<8; i++) {
|
|
||||||
#ifndef NEWPANEL
|
|
||||||
if((blocking[i]>ms))
|
|
||||||
buttons &= ~(1<<i);
|
|
||||||
#else
|
|
||||||
if((blocking>ms))
|
|
||||||
buttons &= ~(1<<i);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
if((buttons==oldbuttons) && ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
|
|
||||||
return;
|
|
||||||
oldbuttons=buttons;
|
|
||||||
#else
|
|
||||||
|
|
||||||
if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
|
|
||||||
return;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
previous_millis_lcd=millis();
|
|
||||||
menu.update();
|
|
||||||
}
|
|
||||||
#ifdef ULTIPANEL
|
|
||||||
|
|
||||||
|
|
||||||
void lcd_buttons_init()
|
|
||||||
{
|
|
||||||
#ifdef NEWPANEL
|
|
||||||
pinMode(BTN_EN1,INPUT);
|
pinMode(BTN_EN1,INPUT);
|
||||||
pinMode(BTN_EN2,INPUT);
|
pinMode(BTN_EN2,INPUT);
|
||||||
pinMode(BTN_ENC,INPUT);
|
pinMode(BTN_ENC,INPUT);
|
||||||
|
@ -254,12 +684,7 @@ void lcd_buttons_init()
|
||||||
WRITE(BTN_EN1,HIGH);
|
WRITE(BTN_EN1,HIGH);
|
||||||
WRITE(BTN_EN2,HIGH);
|
WRITE(BTN_EN2,HIGH);
|
||||||
WRITE(BTN_ENC,HIGH);
|
WRITE(BTN_ENC,HIGH);
|
||||||
#if (SDCARDDETECT > -1)
|
#else
|
||||||
{
|
|
||||||
WRITE(SDCARDDETECT,HIGH);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#else
|
|
||||||
pinMode(SHIFT_CLK,OUTPUT);
|
pinMode(SHIFT_CLK,OUTPUT);
|
||||||
pinMode(SHIFT_LD,OUTPUT);
|
pinMode(SHIFT_LD,OUTPUT);
|
||||||
pinMode(SHIFT_EN,OUTPUT);
|
pinMode(SHIFT_EN,OUTPUT);
|
||||||
|
@ -267,2670 +692,171 @@ void lcd_buttons_init()
|
||||||
WRITE(SHIFT_OUT,HIGH);
|
WRITE(SHIFT_OUT,HIGH);
|
||||||
WRITE(SHIFT_LD,HIGH);
|
WRITE(SHIFT_LD,HIGH);
|
||||||
WRITE(SHIFT_EN,LOW);
|
WRITE(SHIFT_EN,LOW);
|
||||||
#endif
|
#endif//!NEWPANEL
|
||||||
|
#if (SDCARDDETECT > -1)
|
||||||
|
WRITE(SDCARDDETECT, HIGH);
|
||||||
|
lcd_oldcardstatus = IS_SD_INSERTED;
|
||||||
|
#endif//(SDCARDDETECT > -1)
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Warning, this is called from interrupt context! */
|
void lcd_update()
|
||||||
|
{
|
||||||
|
static unsigned long timeoutToStatus = 0;
|
||||||
|
|
||||||
|
lcd_buttons_update();
|
||||||
|
|
||||||
|
#if (SDCARDDETECT > -1)
|
||||||
|
if((IS_SD_INSERTED != lcd_oldcardstatus))
|
||||||
|
{
|
||||||
|
lcdDrawUpdate = 2;
|
||||||
|
lcd_oldcardstatus = IS_SD_INSERTED;
|
||||||
|
lcd_implementation_init(); // to maybe revive the lcd if static electricty killed it.
|
||||||
|
|
||||||
|
if(lcd_oldcardstatus)
|
||||||
|
{
|
||||||
|
card.initsd();
|
||||||
|
LCD_MESSAGEPGM(MSG_SD_INSERTED);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
card.release();
|
||||||
|
LCD_MESSAGEPGM(MSG_SD_REMOVED);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif//CARDINSERTED
|
||||||
|
|
||||||
|
if (lcd_next_update_millis < millis())
|
||||||
|
{
|
||||||
|
#ifdef ULTIPANEL
|
||||||
|
if (encoderDiff)
|
||||||
|
{
|
||||||
|
lcdDrawUpdate = 1;
|
||||||
|
encoderPosition += encoderDiff;
|
||||||
|
encoderDiff = 0;
|
||||||
|
timeoutToStatus = millis() + LCD_TIMEOUT_TO_STATUS;
|
||||||
|
}
|
||||||
|
if (LCD_CLICKED)
|
||||||
|
timeoutToStatus = millis() + LCD_TIMEOUT_TO_STATUS;
|
||||||
|
#endif//ULTIPANEL
|
||||||
|
|
||||||
|
(*currentMenu)();
|
||||||
|
#ifdef ULTIPANEL
|
||||||
|
if(timeoutToStatus < millis() && currentMenu != lcd_status_screen)
|
||||||
|
{
|
||||||
|
lcd_return_to_status();
|
||||||
|
lcdDrawUpdate = 2;
|
||||||
|
}
|
||||||
|
#endif//ULTIPANEL
|
||||||
|
if (lcdDrawUpdate == 2)
|
||||||
|
lcd_implementation_clear();
|
||||||
|
if (lcdDrawUpdate)
|
||||||
|
lcdDrawUpdate--;
|
||||||
|
lcd_next_update_millis = millis() + 100;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void lcd_setstatus(const char* message)
|
||||||
|
{
|
||||||
|
if (lcd_status_message_level > 0)
|
||||||
|
return;
|
||||||
|
strncpy(lcd_status_message, message, LCD_WIDTH);
|
||||||
|
lcdDrawUpdate = 2;
|
||||||
|
}
|
||||||
|
void lcd_setstatuspgm(const char* message)
|
||||||
|
{
|
||||||
|
if (lcd_status_message_level > 0)
|
||||||
|
return;
|
||||||
|
strncpy_P(lcd_status_message, message, LCD_WIDTH);
|
||||||
|
lcdDrawUpdate = 2;
|
||||||
|
}
|
||||||
|
void lcd_setalertstatuspgm(const char* message)
|
||||||
|
{
|
||||||
|
lcd_setstatuspgm(message);
|
||||||
|
lcd_status_message_level = 1;
|
||||||
|
#ifdef ULTIPANEL
|
||||||
|
lcd_return_to_status();
|
||||||
|
#endif//ULTIPANEL
|
||||||
|
}
|
||||||
|
void lcd_reset_alert_level()
|
||||||
|
{
|
||||||
|
lcd_status_message_level = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef ULTIPANEL
|
||||||
|
/* Warning: This function is called from interrupt context */
|
||||||
void lcd_buttons_update()
|
void lcd_buttons_update()
|
||||||
{
|
{
|
||||||
|
#ifdef NEWPANEL
|
||||||
#ifdef NEWPANEL
|
|
||||||
uint8_t newbutton=0;
|
uint8_t newbutton=0;
|
||||||
if(READ(BTN_EN1)==0) newbutton|=EN_A;
|
if(READ(BTN_EN1)==0) newbutton|=EN_A;
|
||||||
if(READ(BTN_EN2)==0) newbutton|=EN_B;
|
if(READ(BTN_EN2)==0) newbutton|=EN_B;
|
||||||
if((blocking<millis()) &&(READ(BTN_ENC)==0))
|
if((blocking_enc<millis()) && (READ(BTN_ENC)==0))
|
||||||
newbutton|=EN_C;
|
newbutton |= EN_C;
|
||||||
buttons=newbutton;
|
buttons = newbutton;
|
||||||
#else //read it from the shift register
|
#else //read it from the shift register
|
||||||
uint8_t newbutton=0;
|
uint8_t newbutton=0;
|
||||||
WRITE(SHIFT_LD,LOW);
|
WRITE(SHIFT_LD,LOW);
|
||||||
WRITE(SHIFT_LD,HIGH);
|
WRITE(SHIFT_LD,HIGH);
|
||||||
unsigned char tmp_buttons=0;
|
unsigned char tmp_buttons=0;
|
||||||
for(int8_t i=0;i<8;i++)
|
for(int8_t i=0;i<8;i++)
|
||||||
{
|
{
|
||||||
newbutton = newbutton>>1;
|
newbutton = newbutton>>1;
|
||||||
if(READ(SHIFT_OUT))
|
if(READ(SHIFT_OUT))
|
||||||
newbutton|=(1<<7);
|
newbutton|=(1<<7);
|
||||||
WRITE(SHIFT_CLK,HIGH);
|
WRITE(SHIFT_CLK,HIGH);
|
||||||
WRITE(SHIFT_CLK,LOW);
|
WRITE(SHIFT_CLK,LOW);
|
||||||
}
|
}
|
||||||
buttons=~newbutton; //invert it, because a pressed switch produces a logical 0
|
buttons=~newbutton; //invert it, because a pressed switch produces a logical 0
|
||||||
#endif
|
#endif//!NEWPANEL
|
||||||
|
|
||||||
//manage encoder rotation
|
//manage encoder rotation
|
||||||
char enc=0;
|
uint8_t enc=0;
|
||||||
if(buttons&EN_A)
|
if(buttons&EN_A)
|
||||||
enc|=(1<<0);
|
enc|=(1<<0);
|
||||||
if(buttons&EN_B)
|
if(buttons&EN_B)
|
||||||
enc|=(1<<1);
|
enc|=(1<<1);
|
||||||
if(enc!=lastenc)
|
if(enc != lastEncoderBits)
|
||||||
{
|
|
||||||
switch(enc)
|
|
||||||
{
|
{
|
||||||
case encrot0:
|
switch(enc)
|
||||||
if(lastenc==encrot3)
|
|
||||||
encoderpos++;
|
|
||||||
else if(lastenc==encrot1)
|
|
||||||
encoderpos--;
|
|
||||||
break;
|
|
||||||
case encrot1:
|
|
||||||
if(lastenc==encrot0)
|
|
||||||
encoderpos++;
|
|
||||||
else if(lastenc==encrot2)
|
|
||||||
encoderpos--;
|
|
||||||
break;
|
|
||||||
case encrot2:
|
|
||||||
if(lastenc==encrot1)
|
|
||||||
encoderpos++;
|
|
||||||
else if(lastenc==encrot3)
|
|
||||||
encoderpos--;
|
|
||||||
break;
|
|
||||||
case encrot3:
|
|
||||||
if(lastenc==encrot2)
|
|
||||||
encoderpos++;
|
|
||||||
else if(lastenc==encrot0)
|
|
||||||
encoderpos--;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
lastenc=enc;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
MainMenu::MainMenu()
|
|
||||||
{
|
|
||||||
status=Main_Status;
|
|
||||||
displayStartingRow=0;
|
|
||||||
activeline=0;
|
|
||||||
force_lcd_update=true;
|
|
||||||
linechanging=false;
|
|
||||||
tune=false;
|
|
||||||
}
|
|
||||||
|
|
||||||
void MainMenu::showStatus()
|
|
||||||
{
|
|
||||||
#if LCD_HEIGHT==4
|
|
||||||
static int olddegHotEnd0=-1;
|
|
||||||
static int oldtargetHotEnd0=-1;
|
|
||||||
//force_lcd_update=true;
|
|
||||||
if(force_lcd_update) //initial display of content
|
|
||||||
{
|
|
||||||
encoderpos=feedmultiply;
|
|
||||||
clear();
|
|
||||||
lcd.setCursor(0,0);LCD_PRINT_PGM("\002000/000\001 ");
|
|
||||||
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
|
||||||
lcd.setCursor(10,0);LCD_PRINT_PGM("B000/000\001 ");
|
|
||||||
#elif EXTRUDERS > 1
|
|
||||||
lcd.setCursor(10,0);LCD_PRINT_PGM("\002000/000\001 ");
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
int tHotEnd0=intround(degHotend0());
|
|
||||||
if((tHotEnd0!=olddegHotEnd0)||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(1,0);
|
|
||||||
lcd.print(ftostr3(tHotEnd0));
|
|
||||||
olddegHotEnd0=tHotEnd0;
|
|
||||||
}
|
|
||||||
int ttHotEnd0=intround(degTargetHotend0());
|
|
||||||
if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(5,0);
|
|
||||||
lcd.print(ftostr3(ttHotEnd0));
|
|
||||||
oldtargetHotEnd0=ttHotEnd0;
|
|
||||||
}
|
|
||||||
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
|
||||||
static int oldtBed=-1;
|
|
||||||
static int oldtargetBed=-1;
|
|
||||||
int tBed=intround(degBed());
|
|
||||||
if((tBed!=oldtBed)||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(11,0);
|
|
||||||
lcd.print(ftostr3(tBed));
|
|
||||||
oldtBed=tBed;
|
|
||||||
}
|
|
||||||
int targetBed=intround(degTargetBed());
|
|
||||||
if((targetBed!=oldtargetBed)||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(15,0);
|
|
||||||
lcd.print(ftostr3(targetBed));
|
|
||||||
oldtargetBed=targetBed;
|
|
||||||
}
|
|
||||||
#elif EXTRUDERS > 1
|
|
||||||
static int olddegHotEnd1=-1;
|
|
||||||
static int oldtargetHotEnd1=-1;
|
|
||||||
int tHotEnd1=intround(degHotend1());
|
|
||||||
if((tHotEnd1!=olddegHotEnd1)||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(11,0);
|
|
||||||
lcd.print(ftostr3(tHotEnd1));
|
|
||||||
olddegHotEnd1=tHotEnd1;
|
|
||||||
}
|
|
||||||
int ttHotEnd1=intround(degTargetHotend1());
|
|
||||||
if((ttHotEnd1!=oldtargetHotEnd1)||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(15,0);
|
|
||||||
lcd.print(ftostr3(ttHotEnd1));
|
|
||||||
oldtargetHotEnd1=ttHotEnd1;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
//starttime=2;
|
|
||||||
static uint16_t oldtime=0;
|
|
||||||
if(starttime!=0)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,1);
|
|
||||||
uint16_t time=millis()/60000-starttime/60000;
|
|
||||||
|
|
||||||
if(starttime!=oldtime)
|
|
||||||
{
|
|
||||||
lcd.print(itostr2(time/60));LCD_PRINT_PGM("h ");lcd.print(itostr2(time%60));LCD_PRINT_PGM("m");
|
|
||||||
oldtime=time;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
static int oldzpos=0;
|
|
||||||
int currentz=current_position[2]*100;
|
|
||||||
if((currentz!=oldzpos)||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(10,1);
|
|
||||||
LCD_PRINT_PGM("Z:");lcd.print(ftostr52(current_position[2]));
|
|
||||||
oldzpos=currentz;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int oldfeedmultiply=0;
|
|
||||||
int curfeedmultiply=feedmultiply;
|
|
||||||
|
|
||||||
if(feedmultiplychanged == true) {
|
|
||||||
feedmultiplychanged = false;
|
|
||||||
encoderpos = curfeedmultiply;
|
|
||||||
}
|
|
||||||
|
|
||||||
if(encoderpos!=curfeedmultiply||force_lcd_update)
|
|
||||||
{
|
|
||||||
curfeedmultiply=encoderpos;
|
|
||||||
if(curfeedmultiply<10)
|
|
||||||
curfeedmultiply=10;
|
|
||||||
if(curfeedmultiply>999)
|
|
||||||
curfeedmultiply=999;
|
|
||||||
feedmultiply=curfeedmultiply;
|
|
||||||
encoderpos=curfeedmultiply;
|
|
||||||
}
|
|
||||||
|
|
||||||
if((curfeedmultiply!=oldfeedmultiply)||force_lcd_update)
|
|
||||||
{
|
|
||||||
oldfeedmultiply=curfeedmultiply;
|
|
||||||
lcd.setCursor(0,2);
|
|
||||||
lcd.print(itostr3(curfeedmultiply));LCD_PRINT_PGM("% ");
|
|
||||||
}
|
|
||||||
|
|
||||||
if(messagetext[0]!='\0')
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,LCD_HEIGHT-1);
|
|
||||||
lcd.print(messagetext);
|
|
||||||
uint8_t n=strlen(messagetext);
|
|
||||||
for(int8_t i=0;i<LCD_WIDTH-n;i++)
|
|
||||||
lcd.print(" ");
|
|
||||||
messagetext[0]='\0';
|
|
||||||
}
|
|
||||||
#ifdef SDSUPPORT
|
|
||||||
static uint8_t oldpercent=101;
|
|
||||||
uint8_t percent=card.percentDone();
|
|
||||||
if(oldpercent!=percent ||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(10,2);
|
|
||||||
lcd.print(itostr3((int)percent));
|
|
||||||
LCD_PRINT_PGM("%SD");
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#else //smaller LCDS----------------------------------
|
|
||||||
static int olddegHotEnd0=-1;
|
|
||||||
static int oldtargetHotEnd0=-1;
|
|
||||||
if(force_lcd_update) //initial display of content
|
|
||||||
{
|
|
||||||
encoderpos=feedmultiply;
|
|
||||||
lcd.setCursor(0,0);LCD_PRINT_PGM("\002---/---\001 ");
|
|
||||||
}
|
|
||||||
|
|
||||||
int tHotEnd0=intround(degHotend0());
|
|
||||||
int ttHotEnd0=intround(degTargetHotend0());
|
|
||||||
|
|
||||||
|
|
||||||
if((abs(tHotEnd0-olddegHotEnd0)>1)||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(1,0);
|
|
||||||
lcd.print(ftostr3(tHotEnd0));
|
|
||||||
olddegHotEnd0=tHotEnd0;
|
|
||||||
}
|
|
||||||
if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(5,0);
|
|
||||||
lcd.print(ftostr3(ttHotEnd0));
|
|
||||||
oldtargetHotEnd0=ttHotEnd0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if(messagetext[0]!='\0')
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,LCD_HEIGHT-1);
|
|
||||||
lcd.print(messagetext);
|
|
||||||
uint8_t n=strlen(messagetext);
|
|
||||||
for(int8_t i=0;i<LCD_WIDTH-n;i++)
|
|
||||||
lcd.print(" ");
|
|
||||||
messagetext[0]='\0';
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
force_lcd_update=false;
|
|
||||||
}
|
|
||||||
|
|
||||||
enum {ItemP_exit, ItemP_autostart,ItemP_disstep,ItemP_home, ItemP_origin, ItemP_preheat_pla, ItemP_preheat_abs, ItemP_cooldown,/*ItemP_extrude,*/ItemP_move};
|
|
||||||
|
|
||||||
//any action must not contain a ',' character anywhere, or this breaks:
|
|
||||||
#define MENUITEM(repaint_action, click_action) \
|
|
||||||
{\
|
|
||||||
if(force_lcd_update) { lcd.setCursor(0,line); repaint_action; } \
|
|
||||||
if((activeline==line) && LCD_CLICKED) {click_action} \
|
|
||||||
}
|
|
||||||
|
|
||||||
void MainMenu::showPrepare()
|
|
||||||
{
|
|
||||||
#ifdef ULTIPANEL
|
|
||||||
uint8_t line=0;
|
|
||||||
clearIfNecessary();
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
//Serial.println((int)(line-lineoffset));
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
case ItemP_exit:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_MAIN) , LCD_BLOCK;status=Main_Menu;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemP_autostart:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_AUTOSTART) , LCD_BLOCK;
|
|
||||||
#ifdef SDSUPPORT
|
|
||||||
card.lastnr=0;card.setroot();card.checkautostart(true);
|
|
||||||
#endif
|
|
||||||
beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemP_disstep:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_DISABLE_STEPPERS) , LCD_BLOCK;enquecommand("M84");beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemP_home:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_AUTO_HOME) , LCD_BLOCK;enquecommand("G28");beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemP_origin:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_SET_ORIGIN) , LCD_BLOCK;enquecommand("G92 X0 Y0 Z0");beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemP_preheat_pla:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_PREHEAT_PLA) , LCD_BLOCK;setTargetHotend0(plaPreheatHotendTemp);setTargetBed(plaPreheatHPBTemp);
|
|
||||||
#if FAN_PIN > -1
|
|
||||||
fanSpeed = plaPreheatFanSpeed;
|
|
||||||
analogWrite(FAN_PIN, fanSpeed);
|
|
||||||
#endif
|
|
||||||
beepshort(); );
|
|
||||||
break;
|
|
||||||
case ItemP_preheat_abs:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_PREHEAT_ABS) , LCD_BLOCK;setTargetHotend0(absPreheatHotendTemp);setTargetBed(absPreheatHPBTemp);
|
|
||||||
#if FAN_PIN > -1
|
|
||||||
fanSpeed = absPreheatFanSpeed;
|
|
||||||
analogWrite(FAN_PIN, fanSpeed);
|
|
||||||
#endif
|
|
||||||
beepshort(); );
|
|
||||||
break;
|
|
||||||
case ItemP_cooldown:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_COOLDOWN) , LCD_BLOCK;setTargetHotend0(0);setTargetHotend1(0);setTargetHotend2(0);setTargetBed(0);beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
// case ItemP_extrude:
|
|
||||||
// MENUITEM( LCD_PRINT_PGM(" Extrude") , LCD_BLOCK;enquecommand("G92 E0");enquecommand("G1 F700 E50");beepshort(); ) ;
|
|
||||||
// break;
|
|
||||||
case ItemP_move:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_MOVE_AXIS) , LCD_BLOCK;status=Sub_PrepareMove;beepshort(); );
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
updateActiveLines(ItemP_move,encoderpos);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
enum {
|
|
||||||
ItemAM_exit,
|
|
||||||
ItemAM_X, ItemAM_Y, ItemAM_Z, ItemAM_E, ItemAM_ERetract
|
|
||||||
};
|
|
||||||
|
|
||||||
void MainMenu::showAxisMove()
|
|
||||||
{
|
|
||||||
uint8_t line=0;
|
|
||||||
int oldencoderpos=0;
|
|
||||||
clearIfNecessary();
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
case ItemAM_exit:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_PREPARE_ALT) , LCD_BLOCK;status=Main_Prepare;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemAM_X:
|
|
||||||
{
|
|
||||||
//oldencoderpos=0;
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(" X:");
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(current_position[X_AXIS]));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
enquecommand("G91");
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
enquecommand("G90");
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if (encoderpos >0)
|
|
||||||
{
|
|
||||||
enquecommand("G1 F700 X0.1");
|
|
||||||
oldencoderpos=encoderpos;
|
|
||||||
encoderpos=0;
|
|
||||||
}
|
|
||||||
|
|
||||||
else if (encoderpos < 0)
|
|
||||||
{
|
|
||||||
enquecommand("G1 F700 X-0.1");
|
|
||||||
oldencoderpos=encoderpos;
|
|
||||||
encoderpos=0;
|
|
||||||
}
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(current_position[X_AXIS]));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case ItemAM_Y:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(" Y:");
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(current_position[Y_AXIS]));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
enquecommand("G91");
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
enquecommand("G90");
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if (encoderpos >0)
|
|
||||||
{
|
|
||||||
enquecommand("G1 F700 Y0.1");
|
|
||||||
oldencoderpos=encoderpos;
|
|
||||||
encoderpos=0;
|
|
||||||
}
|
|
||||||
|
|
||||||
else if (encoderpos < 0)
|
|
||||||
{
|
|
||||||
enquecommand("G1 F700 Y-0.1");
|
|
||||||
oldencoderpos=encoderpos;
|
|
||||||
encoderpos=0;
|
|
||||||
}
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(current_position[Y_AXIS]));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case ItemAM_Z:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(" Z:");
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(current_position[Z_AXIS]));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
enquecommand("G91");
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
enquecommand("G90");
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if (encoderpos >0)
|
|
||||||
{
|
|
||||||
enquecommand("G1 F70 Z0.1");
|
|
||||||
oldencoderpos=encoderpos;
|
|
||||||
encoderpos=0;
|
|
||||||
}
|
|
||||||
|
|
||||||
else if (encoderpos < 0)
|
|
||||||
{
|
|
||||||
enquecommand("G1 F70 Z-0.1");
|
|
||||||
oldencoderpos=encoderpos;
|
|
||||||
encoderpos=0;
|
|
||||||
}
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(current_position[Z_AXIS]));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case ItemAM_E:
|
|
||||||
// ErikDB: TODO: this length should be changed for volumetric.
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_EXTRUDE) , LCD_BLOCK;enquecommand("G92 E0");enquecommand("G1 F70 E1");beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemAM_ERetract:
|
|
||||||
// ErikDB: TODO: this length should be changed for volumetric.
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_RETRACT) , LCD_BLOCK;enquecommand("G92 E0");enquecommand("G1 F700 E-1");beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
updateActiveLines(ItemAM_ERetract,encoderpos);
|
|
||||||
}
|
|
||||||
|
|
||||||
enum {ItemT_exit,ItemT_speed,ItemT_flow,ItemT_nozzle,
|
|
||||||
#if (HEATER_BED_PIN > -1)
|
|
||||||
ItemT_bed,
|
|
||||||
#endif
|
|
||||||
ItemT_fan};
|
|
||||||
|
|
||||||
void MainMenu::showTune()
|
|
||||||
{
|
|
||||||
uint8_t line=0;
|
|
||||||
clearIfNecessary();
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
//Serial.println((int)(line-lineoffset));
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
case ItemT_exit:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_MAIN) , LCD_BLOCK;status=Main_Menu;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemT_speed:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_SPEED);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(feedmultiply));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED) //AnalogWrite(FAN_PIN, fanpwm);
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
{
|
||||||
encoderpos=feedmultiply;
|
case encrot0:
|
||||||
}
|
if(lastEncoderBits==encrot3)
|
||||||
else
|
encoderDiff++;
|
||||||
{
|
else if(lastEncoderBits==encrot1)
|
||||||
encoderpos=activeline*lcdslow;
|
encoderDiff--;
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<1) encoderpos=1;
|
|
||||||
if(encoderpos>400) encoderpos=400;
|
|
||||||
feedmultiply = encoderpos;
|
|
||||||
feedmultiplychanged=true;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemT_nozzle:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_NOZZLE);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=intround(degTargetHotend0());
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
setTargetHotend0(encoderpos);
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
#if (HEATER_BED_PIN > -1)
|
|
||||||
case ItemT_bed:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_BED);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetBed())));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=intround(degTargetBed());
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
setTargetBed(encoderpos);
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
case ItemT_fan:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_FAN_SPEED);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(fanSpeed));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED) //nalogWrite(FAN_PIN, fanpwm);
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=fanSpeed;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>255) encoderpos=255;
|
|
||||||
fanSpeed=encoderpos;
|
|
||||||
analogWrite(FAN_PIN, fanSpeed);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemT_flow://axis_steps_per_unit[i] = code_value();
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_FLOW);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr52(axis_steps_per_unit[E_AXIS]));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(axis_steps_per_unit[E_AXIS]*100.0);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[E_AXIS]);
|
|
||||||
position[E_AXIS]=lround(position[E_AXIS]*factor);
|
|
||||||
//current_position[E_AXIS]*=factor;
|
|
||||||
axis_steps_per_unit[E_AXIS]= encoderpos/100.0;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<5) encoderpos=5;
|
|
||||||
if(encoderpos>999999) encoderpos=999999;
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr52(encoderpos/100.0));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
updateActiveLines(ItemT_fan,encoderpos);
|
|
||||||
}
|
|
||||||
|
|
||||||
/*does not work
|
|
||||||
#define MENUCHANGEITEM(repaint_action, enter_action, accept_action, change_action) \
|
|
||||||
{\
|
|
||||||
if(force_lcd_update) { lcd.setCursor(0,line); repaint_action; } \
|
|
||||||
if(activeline==line) \
|
|
||||||
{ \
|
|
||||||
if(LCD_CLICKED) \
|
|
||||||
{ \
|
|
||||||
linechanging=!linechanging; \
|
|
||||||
if(linechanging) {enter_action;} \
|
|
||||||
else {accept_action;} \
|
|
||||||
} \
|
|
||||||
else \
|
|
||||||
if(linechanging) {change_action};}\
|
|
||||||
}
|
|
||||||
*/
|
|
||||||
|
|
||||||
enum {
|
|
||||||
ItemCT_exit,ItemCT_nozzle0,
|
|
||||||
#ifdef AUTOTEMP
|
|
||||||
ItemCT_autotempactive,
|
|
||||||
ItemCT_autotempmin,ItemCT_autotempmax,ItemCT_autotempfact,
|
|
||||||
#endif
|
|
||||||
#if EXTRUDERS > 1
|
|
||||||
ItemCT_nozzle1,
|
|
||||||
#endif
|
|
||||||
#if EXTRUDERS > 2
|
|
||||||
ItemCT_nozzle2,
|
|
||||||
#endif
|
|
||||||
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
|
||||||
ItemCT_bed,
|
|
||||||
#endif
|
|
||||||
ItemCT_fan,
|
|
||||||
ItemCT_PID_P,ItemCT_PID_I,ItemCT_PID_D,ItemCT_PID_C,
|
|
||||||
ItemCT_PLA_PreHeat_Setting,
|
|
||||||
ItemCT_ABS_PreHeat_Setting,
|
|
||||||
};
|
|
||||||
|
|
||||||
void MainMenu::showControlTemp()
|
|
||||||
{
|
|
||||||
uint8_t line=0;
|
|
||||||
clearIfNecessary();
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
case ItemCT_exit:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_CONTROL) , LCD_BLOCK;status=Main_Control;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemCT_nozzle0:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_NOZZLE);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=intround(degTargetHotend0());
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
setTargetHotend0(encoderpos);
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
#if EXTRUDERS > 1
|
|
||||||
case ItemCT_nozzle1:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_NOZZLE1);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend1())));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=intround(degTargetHotend1());
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
setTargetHotend1(encoderpos);
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
#endif
|
|
||||||
#if EXTRUDERS > 2
|
|
||||||
case ItemCT_nozzle2:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_NOZZLE2);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend2())));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=intround(degTargetHotend2());
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
setTargetHotend2(encoderpos);
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
#endif
|
|
||||||
#ifdef AUTOTEMP
|
|
||||||
case ItemCT_autotempmin:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_MIN);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_min));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=intround(autotemp_min);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
autotemp_min=encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCT_autotempmax:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_MAX);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_max));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=intround(autotemp_max);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
autotemp_max=encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCT_autotempfact:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_FACTOR);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr32(autotemp_factor));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=intround(autotemp_factor*100);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
autotemp_max=encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>99) encoderpos=99;
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr32(encoderpos/100.));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCT_autotempactive:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_AUTOTEMP);
|
|
||||||
lcd.setCursor(13,line);
|
|
||||||
if(autotemp_enabled)
|
|
||||||
LCD_PRINT_PGM(MSG_ON);
|
|
||||||
else
|
|
||||||
LCD_PRINT_PGM(MSG_OFF);
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
autotemp_enabled=!autotemp_enabled;
|
|
||||||
lcd.setCursor(13,line);
|
|
||||||
if(autotemp_enabled)
|
|
||||||
LCD_PRINT_PGM(MSG_ON);
|
|
||||||
else
|
|
||||||
LCD_PRINT_PGM(MSG_OFF);
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
#endif //autotemp
|
|
||||||
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
|
|
||||||
case ItemCT_bed:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_BED);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetBed())));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=intround(degTargetBed());
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
setTargetBed(encoderpos);
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
#endif
|
|
||||||
case ItemCT_fan:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_FAN_SPEED);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(fanSpeed));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED) //nalogWrite(FAN_PIN, fanpwm);
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=fanSpeed;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>255) encoderpos=255;
|
|
||||||
fanSpeed=encoderpos;
|
|
||||||
analogWrite(FAN_PIN, fanSpeed);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
#ifdef PIDTEMP
|
|
||||||
case ItemCT_PID_P:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(" PID-P: ");
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(Kp));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)Kp;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
Kp= encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<1) encoderpos=1;
|
|
||||||
if(encoderpos>9990) encoderpos=9990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCT_PID_I:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_PID_I);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr51(Ki/PID_dT));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(Ki*10/PID_dT);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
Ki= encoderpos/10.*PID_dT;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>9990) encoderpos=9990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr51(encoderpos/10.));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCT_PID_D:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_PID_D);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(Kd*PID_dT));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(Kd/5./PID_dT);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
Kd= encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>9990) encoderpos=9990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCT_PID_C:
|
|
||||||
#ifdef PID_ADD_EXTRUSION_RATE
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_PID_C);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(Kc));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)Kc;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
Kc= encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case ItemCT_PLA_PreHeat_Setting:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_PREHEAT_PLA_SETTINGS) , LCD_BLOCK;status=Sub_PreheatPLASettings;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemCT_ABS_PreHeat_Setting:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_PREHEAT_ABS_SETTINGS) , LCD_BLOCK;status=Sub_PreheatABSSettings;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
|
|
||||||
updateActiveLines(ItemCT_ABS_PreHeat_Setting,encoderpos);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
enum {
|
|
||||||
ItemCM_exit,
|
|
||||||
ItemCM_acc, ItemCM_xyjerk,
|
|
||||||
ItemCM_vmaxx, ItemCM_vmaxy, ItemCM_vmaxz, ItemCM_vmaxe,
|
|
||||||
ItemCM_vtravmin,ItemCM_vmin,
|
|
||||||
ItemCM_amaxx, ItemCM_amaxy, ItemCM_amaxz, ItemCM_amaxe,
|
|
||||||
ItemCM_aret, ItemCM_xsteps,ItemCM_ysteps, ItemCM_zsteps, ItemCM_esteps
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void MainMenu::showControlMotion()
|
|
||||||
{
|
|
||||||
uint8_t line=0;
|
|
||||||
clearIfNecessary();
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
case ItemCM_exit:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_CONTROL) , LCD_BLOCK;status=Main_Control;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemCM_acc:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_ACC);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));LCD_PRINT_PGM("00");
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)acceleration/100;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
acceleration= encoderpos*100;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<5) encoderpos=5;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));LCD_PRINT_PGM("00");
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCM_xyjerk: //max_xy_jerk
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_VXY_JERK);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)max_xy_jerk;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
max_xy_jerk= encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<1) encoderpos=1;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemCM_vmaxx:
|
|
||||||
case ItemCM_vmaxy:
|
|
||||||
case ItemCM_vmaxz:
|
|
||||||
case ItemCM_vmaxe:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_VMAX);
|
|
||||||
if(i==ItemCM_vmaxx)LCD_PRINT_PGM(MSG_X);
|
|
||||||
if(i==ItemCM_vmaxy)LCD_PRINT_PGM(MSG_Y);
|
|
||||||
if(i==ItemCM_vmaxz)LCD_PRINT_PGM(MSG_Z);
|
|
||||||
if(i==ItemCM_vmaxe)LCD_PRINT_PGM(MSG_E);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemCM_vmaxx]));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)max_feedrate[i-ItemCM_vmaxx];
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
max_feedrate[i-ItemCM_vmaxx]= encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<1) encoderpos=1;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemCM_vmin:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_VMIN);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(minimumfeedrate);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
minimumfeedrate= encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCM_vtravmin:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_VTRAV_MIN);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)mintravelfeedrate;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
mintravelfeedrate= encoderpos;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemCM_amaxx:
|
|
||||||
case ItemCM_amaxy:
|
|
||||||
case ItemCM_amaxz:
|
|
||||||
case ItemCM_amaxe:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(" Amax ");
|
|
||||||
if(i==ItemCM_amaxx)LCD_PRINT_PGM(MSG_X);
|
|
||||||
if(i==ItemCM_amaxy)LCD_PRINT_PGM(MSG_Y);
|
|
||||||
if(i==ItemCM_amaxz)LCD_PRINT_PGM(MSG_Z);
|
|
||||||
if(i==ItemCM_amaxe)LCD_PRINT_PGM(MSG_E);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100));LCD_PRINT_PGM("00");
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
max_acceleration_units_per_sq_second[i-ItemCM_amaxx]= encoderpos*100;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<1) encoderpos=1;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));LCD_PRINT_PGM("00");
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
|
|
||||||
|
|
||||||
case ItemCM_aret://float retract_acceleration = 7000;
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_A_RETRACT);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));LCD_PRINT_PGM("00");
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)retract_acceleration/100;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
retract_acceleration= encoderpos*100;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<10) encoderpos=10;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));LCD_PRINT_PGM("00");
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCM_xsteps://axis_steps_per_unit[i] = code_value();
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_XSTEPS);
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[X_AXIS]));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(axis_steps_per_unit[X_AXIS]*100.0);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[X_AXIS]);
|
|
||||||
position[X_AXIS]=lround(position[X_AXIS]*factor);
|
|
||||||
//current_position[X_AXIS]*=factor;
|
|
||||||
axis_steps_per_unit[X_AXIS]= encoderpos/100.0;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<5) encoderpos=5;
|
|
||||||
if(encoderpos>999999) encoderpos=999999;
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCM_ysteps://axis_steps_per_unit[i] = code_value();
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_YSTEPS);
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[Y_AXIS]));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(axis_steps_per_unit[Y_AXIS]*100.0);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[Y_AXIS]);
|
|
||||||
position[Y_AXIS]=lround(position[Y_AXIS]*factor);
|
|
||||||
//current_position[Y_AXIS]*=factor;
|
|
||||||
axis_steps_per_unit[Y_AXIS]= encoderpos/100.0;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<5) encoderpos=5;
|
|
||||||
if(encoderpos>999999) encoderpos=999999;
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemCM_zsteps://axis_steps_per_unit[i] = code_value();
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_ZSTEPS);
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr51(axis_steps_per_unit[Z_AXIS]));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(axis_steps_per_unit[Z_AXIS]*100.0);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[Z_AXIS]);
|
|
||||||
position[Z_AXIS]=lround(position[Z_AXIS]*factor);
|
|
||||||
//current_position[Z_AXIS]*=factor;
|
|
||||||
axis_steps_per_unit[Z_AXIS]= encoderpos/100.0;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<5) encoderpos=5;
|
|
||||||
if(encoderpos>999999) encoderpos=999999;
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemCM_esteps://axis_steps_per_unit[i] = code_value();
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_ESTEPS);
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr51(axis_steps_per_unit[E_AXIS]));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(axis_steps_per_unit[E_AXIS]*100.0);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[E_AXIS]);
|
|
||||||
position[E_AXIS]=lround(position[E_AXIS]*factor);
|
|
||||||
//current_position[E_AXIS]*=factor;
|
|
||||||
axis_steps_per_unit[E_AXIS]= encoderpos/100.0;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<5) encoderpos=5;
|
|
||||||
if(encoderpos>999999) encoderpos=999999;
|
|
||||||
lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
updateActiveLines(ItemCM_esteps,encoderpos);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
enum {
|
|
||||||
ItemR_exit,
|
|
||||||
ItemR_autoretract,
|
|
||||||
ItemR_retract_length,ItemR_retract_feedrate,ItemR_retract_zlift,
|
|
||||||
ItemR_unretract_length,ItemR_unretract_feedrate,
|
|
||||||
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void MainMenu::showControlRetract()
|
|
||||||
{
|
|
||||||
#ifdef FWRETRACT
|
|
||||||
uint8_t line=0;
|
|
||||||
clearIfNecessary();
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
case ItemR_exit:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_CONTROL) , LCD_BLOCK;status=Main_Control;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
|
|
||||||
//float retract_length=2, retract_feedrate=1200, retract_zlift=0.4;
|
|
||||||
//float retract_recover_length=0, retract_recover_feedrate=500;
|
|
||||||
case ItemR_autoretract:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_AUTORETRACT);
|
|
||||||
lcd.setCursor(13,line);
|
|
||||||
if(autoretract_enabled)
|
|
||||||
LCD_PRINT_PGM(MSG_ON);
|
|
||||||
else
|
|
||||||
LCD_PRINT_PGM(MSG_OFF);
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
autoretract_enabled=!autoretract_enabled;
|
|
||||||
lcd.setCursor(13,line);
|
|
||||||
if(autoretract_enabled)
|
|
||||||
LCD_PRINT_PGM(MSG_ON);
|
|
||||||
else
|
|
||||||
LCD_PRINT_PGM(MSG_OFF);
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemR_retract_length:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_CONTROL_RETRACT);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr52(retract_length));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(retract_length*100);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
retract_length= encoderpos/100.;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<1) encoderpos=1;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr52(encoderpos/100.));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemR_retract_feedrate:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_CONTROL_RETRACTF);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(retract_feedrate));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(retract_feedrate/5);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
retract_feedrate= encoderpos*5.;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<1) encoderpos=1;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemR_retract_zlift://float retract_acceleration = 7000;
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_CONTROL_RETRACT_ZLIFT);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr52(retract_zlift));;
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(retract_zlift*10);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
retract_zlift= encoderpos/10.;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr52(encoderpos/10.));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
case ItemR_unretract_length:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_CONTROL_RETRACT_RECOVER);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr52(retract_recover_length));;
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)(retract_recover_length*100);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
retract_recover_length= encoderpos/100.;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr52(encoderpos/100.));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemR_unretract_feedrate:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_CONTROL_RETRACT_RECOVERF);
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(retract_recover_feedrate));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=(long)retract_recover_feedrate/5;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
retract_recover_feedrate= encoderpos*5.;
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<1) encoderpos=1;
|
|
||||||
if(encoderpos>990) encoderpos=990;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5));
|
|
||||||
}
|
|
||||||
|
|
||||||
}break;
|
|
||||||
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
updateActiveLines(ItemR_unretract_feedrate,encoderpos);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
enum {
|
|
||||||
ItemC_exit,ItemC_temp,ItemC_move,
|
|
||||||
#ifdef FWRETRACT
|
|
||||||
ItemC_rectract,
|
|
||||||
#endif
|
|
||||||
ItemC_store, ItemC_load,ItemC_failsafe
|
|
||||||
};
|
|
||||||
|
|
||||||
void MainMenu::showControl()
|
|
||||||
{
|
|
||||||
uint8_t line=0;
|
|
||||||
clearIfNecessary();
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
case ItemC_exit:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_MAIN_WIDE) , LCD_BLOCK;status=Main_Menu;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemC_temp:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_TEMPERATURE_WIDE) , LCD_BLOCK;status=Sub_TempControl;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemC_move:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_MOTION_WIDE) , LCD_BLOCK;status=Sub_MotionControl;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
#ifdef FWRETRACT
|
|
||||||
case ItemC_rectract:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_RECTRACT_WIDE) , LCD_BLOCK;status=Sub_RetractControl;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
case ItemC_store:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_STORE_EPROM);
|
|
||||||
}
|
|
||||||
if((activeline==line) && LCD_CLICKED)
|
|
||||||
{
|
|
||||||
//enquecommand("M84");
|
|
||||||
beepshort();
|
|
||||||
LCD_BLOCK;
|
|
||||||
Config_StoreSettings();
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
case ItemC_load:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_LOAD_EPROM);
|
|
||||||
}
|
|
||||||
if((activeline==line) && LCD_CLICKED)
|
|
||||||
{
|
|
||||||
//enquecommand("M84");
|
|
||||||
beepshort();
|
|
||||||
LCD_BLOCK;
|
|
||||||
Config_RetrieveSettings();
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
case ItemC_failsafe:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_RESTORE_FAILSAFE);
|
|
||||||
}
|
|
||||||
if((activeline==line) && LCD_CLICKED)
|
|
||||||
{
|
|
||||||
//enquecommand("M84");
|
|
||||||
beepshort();
|
|
||||||
LCD_BLOCK;
|
|
||||||
Config_ResetDefault();
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
updateActiveLines(ItemC_failsafe,encoderpos);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void MainMenu::showSD()
|
|
||||||
{
|
|
||||||
#ifdef SDSUPPORT
|
|
||||||
uint8_t line=0;
|
|
||||||
|
|
||||||
clearIfNecessary();
|
|
||||||
static uint8_t nrfiles=0;
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
if(card.cardOK)
|
|
||||||
{
|
|
||||||
nrfiles=card.getnrfilenames();
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
nrfiles=0;
|
|
||||||
lineoffset=0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
bool enforceupdate=false;
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
case 0:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_MAIN) , LCD_BLOCK;status=Main_Menu;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
// case 1:
|
|
||||||
// {
|
|
||||||
// if(force_lcd_update)
|
|
||||||
// {
|
|
||||||
// lcd.setCursor(0,line);
|
|
||||||
// if(CARDINSERTED)
|
|
||||||
// {
|
|
||||||
// LCD_PRINT_PGM(" \004Refresh");
|
|
||||||
// }
|
|
||||||
// else
|
|
||||||
// {
|
|
||||||
// LCD_PRINT_PGM(" \004Insert Card");
|
|
||||||
// }
|
|
||||||
//
|
|
||||||
// }
|
|
||||||
// if((activeline==line) && LCD_CLICKED)
|
|
||||||
// {
|
|
||||||
// LCD_BLOCK;
|
|
||||||
// beepshort();
|
|
||||||
// card.initsd();
|
|
||||||
// force_lcd_update=true;
|
|
||||||
// nrfiles=card.getnrfilenames();
|
|
||||||
// }
|
|
||||||
// }break;
|
|
||||||
case 1:
|
|
||||||
MENUITEM( lcd.print(" ");card.getWorkDirName();
|
|
||||||
if(card.filename[0]=='/') LCD_PRINT_PGM(MSG_REFRESH);
|
|
||||||
else {
|
|
||||||
lcd.print("\005");
|
|
||||||
lcd.print(card.filename);
|
|
||||||
lcd.print("/..");
|
|
||||||
} ,
|
|
||||||
LCD_BLOCK;
|
|
||||||
if(SDCARDDETECT == -1) card.initsd();
|
|
||||||
card.updir();
|
|
||||||
enforceupdate=true;
|
|
||||||
lineoffset=0;
|
|
||||||
beepshort(); ) ;
|
|
||||||
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
{
|
|
||||||
#define FIRSTITEM 2
|
|
||||||
if(i-FIRSTITEM<nrfiles)
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
card.getfilename(i-FIRSTITEM);
|
|
||||||
//Serial.print("Filenr:");Serial.println(i-2);
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(" ");
|
|
||||||
if(card.filenameIsDir)
|
|
||||||
{
|
|
||||||
lcd.print("\005");
|
|
||||||
card.longFilename[LCD_WIDTH-2] = '\0';
|
|
||||||
}
|
|
||||||
if (card.longFilename[0])
|
|
||||||
{
|
|
||||||
card.longFilename[LCD_WIDTH-1] = '\0';
|
|
||||||
lcd.print(card.longFilename);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
lcd.print(card.filename);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if((activeline==line) && LCD_CLICKED)
|
|
||||||
{
|
|
||||||
LCD_BLOCK
|
|
||||||
card.getfilename(i-FIRSTITEM);
|
|
||||||
if(card.filenameIsDir)
|
|
||||||
{
|
|
||||||
for(uint8_t i=0;i<strlen(card.filename);i++)
|
|
||||||
card.filename[i]=tolower(card.filename[i]);
|
|
||||||
card.chdir(card.filename);
|
|
||||||
lineoffset=0;
|
|
||||||
enforceupdate=true;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
char cmd[30];
|
|
||||||
for(uint8_t i=0;i<strlen(card.filename);i++)
|
|
||||||
card.filename[i]=tolower(card.filename[i]);
|
|
||||||
sprintf(cmd,"M23 %s",card.filename);
|
|
||||||
//sprintf(cmd,"M115");
|
|
||||||
enquecommand(cmd);
|
|
||||||
enquecommand("M24");
|
|
||||||
beep();
|
|
||||||
status=Main_Status;
|
|
||||||
if (card.longFilename[0])
|
|
||||||
{
|
|
||||||
card.longFilename[LCD_WIDTH-1] = '\0';
|
|
||||||
lcd_setstatus(card.longFilename);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
lcd_setstatus(card.filename);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
updateActiveLines(FIRSTITEM+nrfiles-1,encoderpos);
|
|
||||||
if(enforceupdate)
|
|
||||||
{
|
|
||||||
force_lcd_update=true;
|
|
||||||
enforceupdate=false;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
enum {ItemM_watch, ItemM_prepare, ItemM_control, ItemM_file, ItemM_pause};
|
|
||||||
void MainMenu::showMainMenu()
|
|
||||||
{
|
|
||||||
|
|
||||||
#ifndef ULTIPANEL
|
|
||||||
force_lcd_update=false;
|
|
||||||
#endif
|
|
||||||
if(tune)
|
|
||||||
{
|
|
||||||
if(!(movesplanned() || IS_SD_PRINTING))
|
|
||||||
{
|
|
||||||
force_lcd_update=true;
|
|
||||||
tune=false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
if(movesplanned() || IS_SD_PRINTING)
|
|
||||||
{
|
|
||||||
force_lcd_update=true;
|
|
||||||
tune=true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
clearIfNecessary();
|
|
||||||
uint8_t line=0;
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
case ItemM_watch:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_WATCH) , LCD_BLOCK;status=Main_Status;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
case ItemM_prepare:
|
|
||||||
MENUITEM( if(!tune) LCD_PRINT_PGM(MSG_PREPARE);else LCD_PRINT_PGM(MSG_TUNE); , LCD_BLOCK;status=Main_Prepare;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case ItemM_control:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_CONTROL_ARROW) , LCD_BLOCK;status=Main_Control;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
#ifdef SDSUPPORT
|
|
||||||
case ItemM_file:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);
|
|
||||||
if(IS_SD_INSERTED)
|
|
||||||
{
|
|
||||||
if(card.sdprinting)
|
|
||||||
LCD_PRINT_PGM(MSG_STOP_PRINT);
|
|
||||||
else
|
|
||||||
LCD_PRINT_PGM(MSG_CARD_MENU);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
LCD_PRINT_PGM(MSG_NO_CARD);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if(IS_SD_INSERTED&&(activeline==line) && LCD_CLICKED)
|
|
||||||
{
|
|
||||||
card.printingHasFinished();
|
|
||||||
LCD_BLOCK;
|
|
||||||
status=Main_SD;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
case ItemM_pause:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);
|
|
||||||
if(IS_SD_INSERTED)
|
|
||||||
{
|
|
||||||
if(card.sdprinting)
|
|
||||||
LCD_PRINT_PGM(MSG_PAUSE_PRINT);
|
|
||||||
else
|
|
||||||
LCD_PRINT_PGM(MSG_RESUME_PRINT);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
//LCD_PRINT_PGM(MSG_NO_CARD);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if(IS_SD_INSERTED && (activeline==line) && LCD_CLICKED)
|
|
||||||
{
|
|
||||||
if(card.sdprinting)
|
|
||||||
{
|
|
||||||
card.pauseSDPrint();
|
|
||||||
beepshort();
|
|
||||||
status = Main_Status;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
card.startFileprint();
|
|
||||||
starttime=millis();
|
|
||||||
beepshort();
|
|
||||||
status = Main_Status;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
#else
|
|
||||||
case ItemM_file:
|
|
||||||
break;
|
|
||||||
case ItemM_pause:
|
|
||||||
break;
|
break;
|
||||||
#endif
|
case encrot1:
|
||||||
default:
|
if(lastEncoderBits==encrot0)
|
||||||
SERIAL_ERROR_START;
|
encoderDiff++;
|
||||||
SERIAL_ERRORLNPGM(MSG_SERIAL_ERROR_MENU_STRUCTURE);
|
else if(lastEncoderBits==encrot2)
|
||||||
break;
|
encoderDiff--;
|
||||||
|
break;
|
||||||
|
case encrot2:
|
||||||
|
if(lastEncoderBits==encrot1)
|
||||||
|
encoderDiff++;
|
||||||
|
else if(lastEncoderBits==encrot3)
|
||||||
|
encoderDiff--;
|
||||||
|
break;
|
||||||
|
case encrot3:
|
||||||
|
if(lastEncoderBits==encrot2)
|
||||||
|
encoderDiff++;
|
||||||
|
else if(lastEncoderBits==encrot0)
|
||||||
|
encoderDiff--;
|
||||||
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
line++;
|
lastEncoderBits = enc;
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t numberOfLines = 4;
|
|
||||||
#ifdef SDSUPPORT
|
|
||||||
numberOfLines = 4;
|
|
||||||
#else
|
|
||||||
numberOfLines = 3;
|
|
||||||
#endif
|
|
||||||
updateActiveLines(numberOfLines,encoderpos);
|
|
||||||
}
|
}
|
||||||
|
#endif//ULTIPANEL
|
||||||
|
|
||||||
void MainMenu::update()
|
/********************************/
|
||||||
{
|
/** Float conversion utilities **/
|
||||||
static MainStatus oldstatus=Main_Menu; //init automatically causes foce_lcd_update=true
|
/********************************/
|
||||||
static unsigned long timeoutToStatus=0;
|
|
||||||
#if (SDCARDDETECT > -1)
|
|
||||||
//This code is only relivant if you have an SDcard detect pin.
|
|
||||||
static bool oldcardstatus=false;
|
|
||||||
if((IS_SD_INSERTED != oldcardstatus))
|
|
||||||
{
|
|
||||||
force_lcd_update=true;
|
|
||||||
oldcardstatus=IS_SD_INSERTED;
|
|
||||||
lcd_init(); // to maybe revive the lcd if static electricty killed it.
|
|
||||||
//Serial.println("echo: SD CHANGE");
|
|
||||||
if(IS_SD_INSERTED)
|
|
||||||
{
|
|
||||||
card.initsd();
|
|
||||||
LCD_MESSAGEPGM(MSG_SD_INSERTED);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
card.release();
|
|
||||||
LCD_MESSAGEPGM(MSG_SD_REMOVED);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if(status!=oldstatus)
|
|
||||||
{
|
|
||||||
force_lcd_update=true;
|
|
||||||
encoderpos=0;
|
|
||||||
lineoffset=0;
|
|
||||||
|
|
||||||
oldstatus=status;
|
|
||||||
}
|
|
||||||
if( (encoderpos!=lastencoderpos) || LCD_CLICKED)
|
|
||||||
timeoutToStatus=millis()+LCD_TIMEOUT_TO_STATUS;
|
|
||||||
|
|
||||||
switch(status)
|
|
||||||
{
|
|
||||||
case Main_Status:
|
|
||||||
{
|
|
||||||
showStatus();
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=false;
|
|
||||||
LCD_BLOCK
|
|
||||||
status=Main_Menu;
|
|
||||||
timeoutToStatus=millis()+LCD_TIMEOUT_TO_STATUS;
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
case Main_Menu:
|
|
||||||
{
|
|
||||||
showMainMenu();
|
|
||||||
linechanging=false;
|
|
||||||
}break;
|
|
||||||
case Main_Prepare:
|
|
||||||
{
|
|
||||||
if(tune)
|
|
||||||
{
|
|
||||||
showTune();
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
showPrepare();
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
case Sub_PrepareMove:
|
|
||||||
{
|
|
||||||
showAxisMove();
|
|
||||||
}break;
|
|
||||||
case Main_Control:
|
|
||||||
{
|
|
||||||
showControl();
|
|
||||||
}break;
|
|
||||||
case Sub_MotionControl:
|
|
||||||
{
|
|
||||||
showControlMotion();
|
|
||||||
}break;
|
|
||||||
case Sub_RetractControl:
|
|
||||||
{
|
|
||||||
showControlRetract();
|
|
||||||
}break;
|
|
||||||
case Sub_TempControl:
|
|
||||||
{
|
|
||||||
showControlTemp();
|
|
||||||
}break;
|
|
||||||
case Main_SD:
|
|
||||||
{
|
|
||||||
showSD();
|
|
||||||
}break;
|
|
||||||
case Sub_PreheatPLASettings:
|
|
||||||
{
|
|
||||||
showPLAsettings();
|
|
||||||
}break;
|
|
||||||
case Sub_PreheatABSSettings:
|
|
||||||
{
|
|
||||||
showABSsettings();
|
|
||||||
}break;
|
|
||||||
}
|
|
||||||
|
|
||||||
if(timeoutToStatus<millis())
|
|
||||||
status=Main_Status;
|
|
||||||
//force_lcd_update=false;
|
|
||||||
lastencoderpos=encoderpos;
|
|
||||||
}
|
|
||||||
|
|
||||||
enum {
|
|
||||||
ItemPLAPreHeat_Exit,
|
|
||||||
ItemPLAPreHeat_set_PLA_FanSpeed,
|
|
||||||
ItemPLAPreHeat_set_nozzle,
|
|
||||||
ItemPLAPreHeat_set_HPB,
|
|
||||||
ItemPLAPreHeat_Store_Eprom
|
|
||||||
};
|
|
||||||
|
|
||||||
void MainMenu::showPLAsettings()
|
|
||||||
{
|
|
||||||
#ifdef ULTIPANEL
|
|
||||||
uint8_t line=0;
|
|
||||||
clearIfNecessary();
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
|
|
||||||
case ItemPLAPreHeat_Exit:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_TEMPERATURE_RTN) , LCD_BLOCK;status=Sub_TempControl;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case ItemPLAPreHeat_set_PLA_FanSpeed:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_FAN_SPEED);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(plaPreheatFanSpeed));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=plaPreheatFanSpeed;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>255) encoderpos=255;
|
|
||||||
plaPreheatFanSpeed=encoderpos;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemPLAPreHeat_set_nozzle:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_NOZZLE);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(plaPreheatHotendTemp));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=plaPreheatHotendTemp;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
plaPreheatHotendTemp = encoderpos;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemPLAPreHeat_set_HPB:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_BED);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(plaPreheatHPBTemp));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=plaPreheatHPBTemp;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>250) encoderpos=150;
|
|
||||||
plaPreheatHPBTemp = encoderpos;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
case ItemPLAPreHeat_Store_Eprom:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_STORE_EPROM);
|
|
||||||
}
|
|
||||||
if((activeline==line) && LCD_CLICKED)
|
|
||||||
{
|
|
||||||
//enquecommand("M84");
|
|
||||||
beepshort();
|
|
||||||
LCD_BLOCK;
|
|
||||||
Config_StoreSettings();
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
updateActiveLines(ItemPLAPreHeat_Store_Eprom,encoderpos);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
enum {
|
|
||||||
ItemABSPreHeat_Exit,
|
|
||||||
ItemABSPreHeat_set_FanSpeed,
|
|
||||||
ItemABSPreHeat_set_nozzle,
|
|
||||||
ItemABSPreHeat_set_HPB,
|
|
||||||
ItemABSPreHeat_Store_Eprom
|
|
||||||
};
|
|
||||||
|
|
||||||
void MainMenu::showABSsettings()
|
|
||||||
{
|
|
||||||
#ifdef ULTIPANEL
|
|
||||||
uint8_t line=0;
|
|
||||||
clearIfNecessary();
|
|
||||||
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
|
|
||||||
{
|
|
||||||
switch(i)
|
|
||||||
{
|
|
||||||
|
|
||||||
case ItemABSPreHeat_Exit:
|
|
||||||
MENUITEM( LCD_PRINT_PGM(MSG_TEMPERATURE_RTN) , LCD_BLOCK;status=Sub_TempControl;beepshort(); ) ;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case ItemABSPreHeat_set_FanSpeed:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_FAN_SPEED);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(absPreheatFanSpeed));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=absPreheatFanSpeed;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>255) encoderpos=255;
|
|
||||||
absPreheatFanSpeed=encoderpos;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemABSPreHeat_set_nozzle:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_NOZZLE);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(absPreheatHotendTemp));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=absPreheatHotendTemp;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>260) encoderpos=260;
|
|
||||||
absPreheatHotendTemp = encoderpos;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
|
|
||||||
case ItemABSPreHeat_set_HPB:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_BED);
|
|
||||||
lcd.setCursor(13,line);lcd.print(ftostr3(absPreheatHPBTemp));
|
|
||||||
}
|
|
||||||
|
|
||||||
if((activeline!=line) )
|
|
||||||
break;
|
|
||||||
|
|
||||||
if(LCD_CLICKED)
|
|
||||||
{
|
|
||||||
linechanging=!linechanging;
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
encoderpos=absPreheatHPBTemp;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
encoderpos=activeline*lcdslow;
|
|
||||||
beepshort();
|
|
||||||
}
|
|
||||||
LCD_BLOCK;
|
|
||||||
}
|
|
||||||
if(linechanging)
|
|
||||||
{
|
|
||||||
if(encoderpos<0) encoderpos=0;
|
|
||||||
if(encoderpos>250) encoderpos=150;
|
|
||||||
absPreheatHPBTemp = encoderpos;
|
|
||||||
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
case ItemABSPreHeat_Store_Eprom:
|
|
||||||
{
|
|
||||||
if(force_lcd_update)
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,line);LCD_PRINT_PGM(MSG_STORE_EPROM);
|
|
||||||
}
|
|
||||||
if((activeline==line) && LCD_CLICKED)
|
|
||||||
{
|
|
||||||
//enquecommand("M84");
|
|
||||||
beepshort();
|
|
||||||
LCD_BLOCK;
|
|
||||||
Config_StoreSettings();
|
|
||||||
}
|
|
||||||
}break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
line++;
|
|
||||||
}
|
|
||||||
updateActiveLines(ItemABSPreHeat_Store_Eprom,encoderpos);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
//**********************************************************************************************************
|
|
||||||
// convert float to string with +123.4 format
|
// convert float to string with +123.4 format
|
||||||
|
char conv[8];
|
||||||
char *ftostr3(const float &x)
|
char *ftostr3(const float &x)
|
||||||
{
|
{
|
||||||
//sprintf(conv,"%5.1f",x);
|
return itostr3((int)x);
|
||||||
int xx=x;
|
|
||||||
conv[0]=(xx/100)%10+'0';
|
|
||||||
conv[1]=(xx/10)%10+'0';
|
|
||||||
conv[2]=(xx)%10+'0';
|
|
||||||
conv[3]=0;
|
|
||||||
return conv;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
char *itostr2(const uint8_t &x)
|
char *itostr2(const uint8_t &x)
|
||||||
|
@ -2967,7 +893,7 @@ char *ftostr32(const float &x)
|
||||||
conv[2]='.';
|
conv[2]='.';
|
||||||
conv[3]=(xx/10)%10+'0';
|
conv[3]=(xx/10)%10+'0';
|
||||||
conv[4]=(xx)%10+'0';
|
conv[4]=(xx)%10+'0';
|
||||||
conv[6]=0;
|
conv[5]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2985,23 +911,86 @@ char *itostr31(const int &xx)
|
||||||
|
|
||||||
char *itostr3(const int &xx)
|
char *itostr3(const int &xx)
|
||||||
{
|
{
|
||||||
conv[0]=(xx/100)%10+'0';
|
if (xx >= 100)
|
||||||
conv[1]=(xx/10)%10+'0';
|
conv[0]=(xx/100)%10+'0';
|
||||||
|
else
|
||||||
|
conv[0]=' ';
|
||||||
|
if (xx >= 10)
|
||||||
|
conv[1]=(xx/10)%10+'0';
|
||||||
|
else
|
||||||
|
conv[1]=' ';
|
||||||
conv[2]=(xx)%10+'0';
|
conv[2]=(xx)%10+'0';
|
||||||
conv[3]=0;
|
conv[3]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
char *itostr3left(const int &xx)
|
||||||
|
{
|
||||||
|
if (xx >= 100)
|
||||||
|
{
|
||||||
|
conv[0]=(xx/100)%10+'0';
|
||||||
|
conv[1]=(xx/10)%10+'0';
|
||||||
|
conv[2]=(xx)%10+'0';
|
||||||
|
conv[3]=0;
|
||||||
|
}
|
||||||
|
else if (xx >= 10)
|
||||||
|
{
|
||||||
|
conv[0]=(xx/10)%10+'0';
|
||||||
|
conv[1]=(xx)%10+'0';
|
||||||
|
conv[2]=0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
conv[0]=(xx)%10+'0';
|
||||||
|
conv[1]=0;
|
||||||
|
}
|
||||||
|
return conv;
|
||||||
|
}
|
||||||
|
|
||||||
char *itostr4(const int &xx)
|
char *itostr4(const int &xx)
|
||||||
{
|
{
|
||||||
conv[0]=(xx/1000)%10+'0';
|
if (xx >= 1000)
|
||||||
conv[1]=(xx/100)%10+'0';
|
conv[0]=(xx/1000)%10+'0';
|
||||||
conv[2]=(xx/10)%10+'0';
|
else
|
||||||
|
conv[0]=' ';
|
||||||
|
if (xx >= 100)
|
||||||
|
conv[1]=(xx/100)%10+'0';
|
||||||
|
else
|
||||||
|
conv[1]=' ';
|
||||||
|
if (xx >= 10)
|
||||||
|
conv[2]=(xx/10)%10+'0';
|
||||||
|
else
|
||||||
|
conv[2]=' ';
|
||||||
conv[3]=(xx)%10+'0';
|
conv[3]=(xx)%10+'0';
|
||||||
conv[4]=0;
|
conv[4]=0;
|
||||||
return conv;
|
return conv;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// convert float to string with 12345 format
|
||||||
|
char *ftostr5(const float &x)
|
||||||
|
{
|
||||||
|
long xx=abs(x);
|
||||||
|
if (xx >= 10000)
|
||||||
|
conv[0]=(xx/10000)%10+'0';
|
||||||
|
else
|
||||||
|
conv[0]=' ';
|
||||||
|
if (xx >= 1000)
|
||||||
|
conv[1]=(xx/1000)%10+'0';
|
||||||
|
else
|
||||||
|
conv[1]=' ';
|
||||||
|
if (xx >= 100)
|
||||||
|
conv[2]=(xx/100)%10+'0';
|
||||||
|
else
|
||||||
|
conv[2]=' ';
|
||||||
|
if (xx >= 10)
|
||||||
|
conv[3]=(xx/10)%10+'0';
|
||||||
|
else
|
||||||
|
conv[3]=' ';
|
||||||
|
conv[4]=(xx)%10+'0';
|
||||||
|
conv[5]=0;
|
||||||
|
return conv;
|
||||||
|
}
|
||||||
|
|
||||||
// convert float to string with +1234.5 format
|
// convert float to string with +1234.5 format
|
||||||
char *ftostr51(const float &x)
|
char *ftostr51(const float &x)
|
||||||
{
|
{
|
||||||
|
@ -3035,5 +1024,3 @@ char *ftostr52(const float &x)
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif //ULTRA_LCD
|
#endif //ULTRA_LCD
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -5,21 +5,12 @@
|
||||||
|
|
||||||
#ifdef ULTRA_LCD
|
#ifdef ULTRA_LCD
|
||||||
|
|
||||||
#if LANGUAGE_CHOICE == 6
|
|
||||||
#include "LiquidCrystalRus.h"
|
|
||||||
#define LCD_CLASS LiquidCrystalRus
|
|
||||||
#else
|
|
||||||
#include <LiquidCrystal.h>
|
|
||||||
#define LCD_CLASS LiquidCrystal
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void lcd_update();
|
void lcd_update();
|
||||||
void lcd_init();
|
void lcd_init();
|
||||||
void lcd_setstatus(const char* message);
|
void lcd_setstatus(const char* message);
|
||||||
void lcd_setstatuspgm(const char* message);
|
void lcd_setstatuspgm(const char* message);
|
||||||
void lcd_setalertstatuspgm(const char* message);
|
void lcd_setalertstatuspgm(const char* message);
|
||||||
void lcd_buttons_update();
|
void lcd_reset_alert_level();
|
||||||
void lcd_buttons_init();
|
|
||||||
|
|
||||||
#define LCD_MESSAGEPGM(x) lcd_setstatuspgm(PSTR(x))
|
#define LCD_MESSAGEPGM(x) lcd_setstatuspgm(PSTR(x))
|
||||||
#define LCD_ALERTMESSAGEPGM(x) lcd_setalertstatuspgm(PSTR(x))
|
#define LCD_ALERTMESSAGEPGM(x) lcd_setalertstatuspgm(PSTR(x))
|
||||||
|
@ -27,7 +18,12 @@
|
||||||
#define LCD_UPDATE_INTERVAL 100
|
#define LCD_UPDATE_INTERVAL 100
|
||||||
#define LCD_TIMEOUT_TO_STATUS 15000
|
#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
#ifdef ULTIPANEL
|
||||||
|
void lcd_buttons_update();
|
||||||
extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
||||||
|
#else
|
||||||
|
FORCE_INLINE void lcd_buttons_update() {}
|
||||||
|
#endif
|
||||||
|
|
||||||
extern int plaPreheatHotendTemp;
|
extern int plaPreheatHotendTemp;
|
||||||
extern int plaPreheatHPBTemp;
|
extern int plaPreheatHPBTemp;
|
||||||
|
@ -43,7 +39,6 @@
|
||||||
#define EN_A (1<<BLEN_A)
|
#define EN_A (1<<BLEN_A)
|
||||||
|
|
||||||
#define LCD_CLICKED (buttons&EN_C)
|
#define LCD_CLICKED (buttons&EN_C)
|
||||||
#define LCD_BLOCK {blocking=millis()+blocktime;}
|
|
||||||
#else
|
#else
|
||||||
//atomatic, do not change
|
//atomatic, do not change
|
||||||
#define B_LE (1<<BL_LE)
|
#define B_LE (1<<BL_LE)
|
||||||
|
@ -56,101 +51,14 @@
|
||||||
#define EN_A (1<<BLEN_A)
|
#define EN_A (1<<BLEN_A)
|
||||||
|
|
||||||
#define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST))
|
#define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST))
|
||||||
#define LCD_BLOCK {blocking[BL_MI]=millis()+blocktime;blocking[BL_ST]=millis()+blocktime;}
|
#endif//NEWPANEL
|
||||||
#endif
|
|
||||||
|
|
||||||
// blocking time for recognizing a new keypress of one key, ms
|
|
||||||
#define blocktime 500
|
|
||||||
#define lcdslow 5
|
|
||||||
|
|
||||||
enum MainStatus{Main_Status, Main_Menu, Main_Prepare,Sub_PrepareMove, Main_Control, Main_SD,Sub_TempControl,Sub_MotionControl,Sub_RetractControl, Sub_PreheatPLASettings, Sub_PreheatABSSettings};
|
|
||||||
|
|
||||||
extern LCD_CLASS lcd;
|
|
||||||
|
|
||||||
class MainMenu{
|
|
||||||
public:
|
|
||||||
MainMenu();
|
|
||||||
void update();
|
|
||||||
int8_t activeline;
|
|
||||||
MainStatus status;
|
|
||||||
uint8_t displayStartingRow;
|
|
||||||
|
|
||||||
void showStatus();
|
|
||||||
void showMainMenu();
|
|
||||||
void showPrepare();
|
|
||||||
void showTune();
|
|
||||||
void showControl();
|
|
||||||
void showControlMotion();
|
|
||||||
void showControlTemp();
|
|
||||||
void showControlRetract();
|
|
||||||
void showAxisMove();
|
|
||||||
void showSD();
|
|
||||||
void showPLAsettings();
|
|
||||||
void showABSsettings();
|
|
||||||
bool force_lcd_update;
|
|
||||||
long lastencoderpos;
|
|
||||||
int8_t lineoffset;
|
|
||||||
int8_t lastlineoffset;
|
|
||||||
|
|
||||||
bool linechanging;
|
|
||||||
|
|
||||||
bool tune;
|
|
||||||
|
|
||||||
private:
|
|
||||||
FORCE_INLINE void updateActiveLines(const uint8_t &maxlines,volatile long &encoderpos)
|
|
||||||
{
|
|
||||||
if(linechanging) return; // an item is changint its value, do not switch lines hence
|
|
||||||
lastlineoffset=lineoffset;
|
|
||||||
long curencoderpos=encoderpos;
|
|
||||||
force_lcd_update=false;
|
|
||||||
if( (abs(curencoderpos-lastencoderpos)<lcdslow) )
|
|
||||||
{
|
|
||||||
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
|
|
||||||
if(curencoderpos<0)
|
|
||||||
{
|
|
||||||
lineoffset--;
|
|
||||||
if(lineoffset<0) lineoffset=0;
|
|
||||||
curencoderpos=lcdslow-1;
|
|
||||||
}
|
|
||||||
if(curencoderpos>(LCD_HEIGHT-1+1)*lcdslow)
|
|
||||||
{
|
|
||||||
lineoffset++;
|
|
||||||
curencoderpos=(LCD_HEIGHT-1)*lcdslow;
|
|
||||||
if(lineoffset>(maxlines+1-LCD_HEIGHT))
|
|
||||||
lineoffset=maxlines+1-LCD_HEIGHT;
|
|
||||||
if(curencoderpos>maxlines*lcdslow)
|
|
||||||
curencoderpos=maxlines*lcdslow;
|
|
||||||
}
|
|
||||||
lastencoderpos=encoderpos=curencoderpos;
|
|
||||||
activeline=curencoderpos/lcdslow;
|
|
||||||
if(activeline<0) activeline=0;
|
|
||||||
if(activeline>LCD_HEIGHT-1) activeline=LCD_HEIGHT-1;
|
|
||||||
if(activeline>maxlines)
|
|
||||||
{
|
|
||||||
activeline=maxlines;
|
|
||||||
curencoderpos=maxlines*lcdslow;
|
|
||||||
}
|
|
||||||
if(lastlineoffset!=lineoffset)
|
|
||||||
force_lcd_update=true;
|
|
||||||
lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
FORCE_INLINE void clearIfNecessary()
|
|
||||||
{
|
|
||||||
if(lastlineoffset!=lineoffset ||force_lcd_update)
|
|
||||||
{
|
|
||||||
force_lcd_update=true;
|
|
||||||
lcd.clear();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
#else //no lcd
|
#else //no lcd
|
||||||
FORCE_INLINE void lcd_update() {}
|
FORCE_INLINE void lcd_update() {}
|
||||||
FORCE_INLINE void lcd_init() {}
|
FORCE_INLINE void lcd_init() {}
|
||||||
FORCE_INLINE void lcd_setstatus(const char* message) {}
|
FORCE_INLINE void lcd_setstatus(const char* message) {}
|
||||||
FORCE_INLINE void lcd_buttons_init() {}
|
|
||||||
FORCE_INLINE void lcd_buttons_update() {}
|
FORCE_INLINE void lcd_buttons_update() {}
|
||||||
|
FORCE_INLINE void lcd_reset_alert_level() {}
|
||||||
|
|
||||||
#define LCD_MESSAGEPGM(x)
|
#define LCD_MESSAGEPGM(x)
|
||||||
#define LCD_ALERTMESSAGEPGM(x)
|
#define LCD_ALERTMESSAGEPGM(x)
|
||||||
|
@ -162,11 +70,13 @@
|
||||||
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);
|
||||||
|
char *itostr3left(const int &xx);
|
||||||
char *itostr4(const int &xx);
|
char *itostr4(const int &xx);
|
||||||
|
|
||||||
char *ftostr3(const float &x);
|
char *ftostr3(const float &x);
|
||||||
char *ftostr31(const float &x);
|
char *ftostr31(const float &x);
|
||||||
char *ftostr32(const float &x);
|
char *ftostr32(const float &x);
|
||||||
|
char *ftostr5(const float &x);
|
||||||
char *ftostr51(const float &x);
|
char *ftostr51(const float &x);
|
||||||
char *ftostr52(const float &x);
|
char *ftostr52(const float &x);
|
||||||
|
|
||||||
|
|
470
Marlin/ultralcd_implementation_hitachi_HD44780.h
Normal file
470
Marlin/ultralcd_implementation_hitachi_HD44780.h
Normal file
|
@ -0,0 +1,470 @@
|
||||||
|
#ifndef ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
||||||
|
#define ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Implementation of the LCD display routines for a hitachi HD44780 display. These are common LCD character displays.
|
||||||
|
* When selecting the rusian language, a slightly different LCD implementation is used to handle UTF8 characters.
|
||||||
|
**/
|
||||||
|
|
||||||
|
#if LANGUAGE_CHOICE == 6
|
||||||
|
#include "LiquidCrystalRus.h"
|
||||||
|
#define LCD_CLASS LiquidCrystalRus
|
||||||
|
#else
|
||||||
|
#include <LiquidCrystal.h>
|
||||||
|
#define LCD_CLASS LiquidCrystal
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Custom characters defined in the first 8 characters of the LCD */
|
||||||
|
#define LCD_STR_BEDTEMP "\x00"
|
||||||
|
#define LCD_STR_DEGREE "\x01"
|
||||||
|
#define LCD_STR_THERMOMETER "\x02"
|
||||||
|
#define LCD_STR_UPLEVEL "\x03"
|
||||||
|
#define LCD_STR_REFRESH "\x04"
|
||||||
|
#define LCD_STR_FOLDER "\x05"
|
||||||
|
#define LCD_STR_FEEDRATE "\x06"
|
||||||
|
#define LCD_STR_CLOCK "\x07"
|
||||||
|
#define LCD_STR_ARROW_RIGHT "\x7E" /* from the default character set */
|
||||||
|
|
||||||
|
LCD_CLASS lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
|
||||||
|
static void lcd_implementation_init()
|
||||||
|
{
|
||||||
|
byte bedTemp[8] =
|
||||||
|
{
|
||||||
|
B00000,
|
||||||
|
B11111,
|
||||||
|
B10101,
|
||||||
|
B10001,
|
||||||
|
B10101,
|
||||||
|
B11111,
|
||||||
|
B00000,
|
||||||
|
B00000
|
||||||
|
}; //thanks Sonny Mounicou
|
||||||
|
byte degree[8] =
|
||||||
|
{
|
||||||
|
B01100,
|
||||||
|
B10010,
|
||||||
|
B10010,
|
||||||
|
B01100,
|
||||||
|
B00000,
|
||||||
|
B00000,
|
||||||
|
B00000,
|
||||||
|
B00000
|
||||||
|
};
|
||||||
|
byte thermometer[8] =
|
||||||
|
{
|
||||||
|
B00100,
|
||||||
|
B01010,
|
||||||
|
B01010,
|
||||||
|
B01010,
|
||||||
|
B01010,
|
||||||
|
B10001,
|
||||||
|
B10001,
|
||||||
|
B01110
|
||||||
|
};
|
||||||
|
byte uplevel[8]={
|
||||||
|
B00100,
|
||||||
|
B01110,
|
||||||
|
B11111,
|
||||||
|
B00100,
|
||||||
|
B11100,
|
||||||
|
B00000,
|
||||||
|
B00000,
|
||||||
|
B00000
|
||||||
|
}; //thanks joris
|
||||||
|
byte refresh[8]={
|
||||||
|
B00000,
|
||||||
|
B00110,
|
||||||
|
B11001,
|
||||||
|
B11000,
|
||||||
|
B00011,
|
||||||
|
B10011,
|
||||||
|
B01100,
|
||||||
|
B00000,
|
||||||
|
}; //thanks joris
|
||||||
|
byte folder [8]={
|
||||||
|
B00000,
|
||||||
|
B11100,
|
||||||
|
B11111,
|
||||||
|
B10001,
|
||||||
|
B10001,
|
||||||
|
B11111,
|
||||||
|
B00000,
|
||||||
|
B00000
|
||||||
|
}; //thanks joris
|
||||||
|
byte feedrate [8]={
|
||||||
|
B11100,
|
||||||
|
B10000,
|
||||||
|
B11000,
|
||||||
|
B10111,
|
||||||
|
B00101,
|
||||||
|
B00110,
|
||||||
|
B00101,
|
||||||
|
B00000
|
||||||
|
}; //thanks Sonny Mounicou
|
||||||
|
byte clock [8]={
|
||||||
|
B00000,
|
||||||
|
B01110,
|
||||||
|
B10011,
|
||||||
|
B10101,
|
||||||
|
B10001,
|
||||||
|
B01110,
|
||||||
|
B00000,
|
||||||
|
B00000
|
||||||
|
}; //thanks Sonny Mounicou
|
||||||
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
|
lcd.createChar(LCD_STR_BEDTEMP[0], bedTemp);
|
||||||
|
lcd.createChar(LCD_STR_DEGREE[0], degree);
|
||||||
|
lcd.createChar(LCD_STR_THERMOMETER[0], thermometer);
|
||||||
|
lcd.createChar(LCD_STR_UPLEVEL[0], uplevel);
|
||||||
|
lcd.createChar(LCD_STR_REFRESH[0], refresh);
|
||||||
|
lcd.createChar(LCD_STR_FOLDER[0], folder);
|
||||||
|
lcd.createChar(LCD_STR_FEEDRATE[0], feedrate);
|
||||||
|
lcd.createChar(LCD_STR_CLOCK[0], clock);
|
||||||
|
lcd.clear();
|
||||||
|
}
|
||||||
|
static void lcd_implementation_clear()
|
||||||
|
{
|
||||||
|
lcd.clear();
|
||||||
|
}
|
||||||
|
/* Arduino < 1.0.0 is missing a function to print PROGMEM strings, so we need to implement our own */
|
||||||
|
static void lcd_printPGM(const char* str)
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
while((c = pgm_read_byte(str++)) != '\0')
|
||||||
|
{
|
||||||
|
lcd.write(c);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
Possible status screens:
|
||||||
|
16x2 |0123456789012345|
|
||||||
|
|000/000 B000/000|
|
||||||
|
|Status line.....|
|
||||||
|
|
||||||
|
16x4 |0123456789012345|
|
||||||
|
|000/000 B000/000|
|
||||||
|
|SD100% Z000.0|
|
||||||
|
|F100% T--:--|
|
||||||
|
|Status line.....|
|
||||||
|
|
||||||
|
20x2 |01234567890123456789|
|
||||||
|
|T000/000D B000/000D |
|
||||||
|
|Status line.........|
|
||||||
|
|
||||||
|
20x4 |01234567890123456789|
|
||||||
|
|T000/000D B000/000D |
|
||||||
|
|X+000.0 Y+000.0 Z+000.0|
|
||||||
|
|F100% SD100% T--:--|
|
||||||
|
|Status line.........|
|
||||||
|
|
||||||
|
20x4 |01234567890123456789|
|
||||||
|
|T000/000D B000/000D |
|
||||||
|
|T000/000D Z000.0|
|
||||||
|
|F100% SD100% T--:--|
|
||||||
|
|Status line.........|
|
||||||
|
*/
|
||||||
|
static void lcd_implementation_status_screen()
|
||||||
|
{
|
||||||
|
int tHotend=int(degHotend(0) + 0.5);
|
||||||
|
int tTarget=int(degTargetHotend(0) + 0.5);
|
||||||
|
|
||||||
|
#if LCD_WIDTH < 20
|
||||||
|
lcd.setCursor(0, 0);
|
||||||
|
lcd.print(itostr3(tHotend));
|
||||||
|
lcd.print('/');
|
||||||
|
lcd.print(itostr3left(tTarget));
|
||||||
|
|
||||||
|
# if EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
|
//If we have an 2nd extruder or heated bed, show that in the top right corner
|
||||||
|
lcd.setCursor(8, 0);
|
||||||
|
# if EXTRUDERS > 1
|
||||||
|
tHotend = int(degHotend(1) + 0.5);
|
||||||
|
tTarget = int(degTargetHotend(1) + 0.5);
|
||||||
|
lcd.print(LCD_STR_THERMOMETER[0]);
|
||||||
|
# else//Heated bed
|
||||||
|
tHotend=int(degBed() + 0.5);
|
||||||
|
tTarget=int(degTargetBed() + 0.5);
|
||||||
|
lcd.print(LCD_STR_BEDTEMP[0]);
|
||||||
|
# endif
|
||||||
|
lcd.print(itostr3(tHotend));
|
||||||
|
lcd.print('/');
|
||||||
|
lcd.print(itostr3left(tTarget));
|
||||||
|
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
|
|
||||||
|
#else//LCD_WIDTH > 19
|
||||||
|
lcd.setCursor(0, 0);
|
||||||
|
lcd.print(LCD_STR_THERMOMETER[0]);
|
||||||
|
lcd.print(itostr3(tHotend));
|
||||||
|
lcd.print('/');
|
||||||
|
lcd.print(itostr3left(tTarget));
|
||||||
|
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||||
|
|
||||||
|
# if EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
|
//If we have an 2nd extruder or heated bed, show that in the top right corner
|
||||||
|
lcd.setCursor(10, 0);
|
||||||
|
# if EXTRUDERS > 1
|
||||||
|
tHotend = int(degHotend(1) + 0.5);
|
||||||
|
tTarget = int(degTargetHotend(1) + 0.5);
|
||||||
|
lcd.print(LCD_STR_THERMOMETER[0]);
|
||||||
|
# else//Heated bed
|
||||||
|
tHotend=int(degBed() + 0.5);
|
||||||
|
tTarget=int(degTargetBed() + 0.5);
|
||||||
|
lcd.print(LCD_STR_BEDTEMP[0]);
|
||||||
|
# endif
|
||||||
|
lcd.print(itostr3(tHotend));
|
||||||
|
lcd.print('/');
|
||||||
|
lcd.print(itostr3left(tTarget));
|
||||||
|
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||||
|
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
|
#endif//LCD_WIDTH > 19
|
||||||
|
|
||||||
|
#if LCD_HEIGHT > 2
|
||||||
|
//Lines 2 for 4 line LCD
|
||||||
|
# if LCD_WIDTH < 20
|
||||||
|
# ifdef SDSUPPORT
|
||||||
|
lcd.setCursor(0, 2);
|
||||||
|
lcd_printPGM(PSTR("SD"));
|
||||||
|
if (IS_SD_PRINTING)
|
||||||
|
lcd.print(itostr3(card.percentDone()));
|
||||||
|
else
|
||||||
|
lcd_printPGM(PSTR("---"));
|
||||||
|
lcd.print('%');
|
||||||
|
# endif//SDSUPPORT
|
||||||
|
# else//LCD_WIDTH > 19
|
||||||
|
# if EXTRUDERS > 1 && TEMP_SENSOR_BED != 0
|
||||||
|
//If we both have a 2nd extruder and a heated bed, show the heated bed temp on the 2nd line on the left, as the first line is filled with extruder temps
|
||||||
|
tHotend=int(degBed() + 0.5);
|
||||||
|
tTarget=int(degTargetBed() + 0.5);
|
||||||
|
|
||||||
|
lcd.setCursor(0, 1);
|
||||||
|
lcd.print(LCD_STR_BEDTEMP[0]);
|
||||||
|
lcd.print(itostr3(tHotend));
|
||||||
|
lcd.print('/');
|
||||||
|
lcd.print(itostr3left(tTarget));
|
||||||
|
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||||
|
# else
|
||||||
|
lcd.setCursor(0,1);
|
||||||
|
lcd.print('X');
|
||||||
|
lcd.print(ftostr3(current_position[X_AXIS]));
|
||||||
|
lcd_printPGM(PSTR(" Y"));
|
||||||
|
lcd.print(ftostr3(current_position[Y_AXIS]));
|
||||||
|
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
|
# endif//LCD_WIDTH > 19
|
||||||
|
lcd.setCursor(LCD_WIDTH - 7, 1);
|
||||||
|
lcd.print('Z');
|
||||||
|
lcd.print(ftostr31(current_position[Z_AXIS]));
|
||||||
|
#endif//LCD_HEIGHT > 2
|
||||||
|
|
||||||
|
#if LCD_HEIGHT > 3
|
||||||
|
lcd.setCursor(0, 2);
|
||||||
|
lcd.print(LCD_STR_FEEDRATE[0]);
|
||||||
|
lcd.print(itostr3(feedmultiply));
|
||||||
|
lcd.print('%');
|
||||||
|
# if LCD_WIDTH > 19
|
||||||
|
# ifdef SDSUPPORT
|
||||||
|
lcd.setCursor(7, 2);
|
||||||
|
lcd_printPGM(PSTR("SD"));
|
||||||
|
if (IS_SD_PRINTING)
|
||||||
|
lcd.print(itostr3(card.percentDone()));
|
||||||
|
else
|
||||||
|
lcd_printPGM(PSTR("---"));
|
||||||
|
lcd.print('%');
|
||||||
|
# endif//SDSUPPORT
|
||||||
|
# endif//LCD_WIDTH > 19
|
||||||
|
lcd.setCursor(LCD_WIDTH - 6, 2);
|
||||||
|
lcd.print(LCD_STR_CLOCK[0]);
|
||||||
|
if(starttime != 0)
|
||||||
|
{
|
||||||
|
uint16_t time = millis()/60000 - starttime/60000;
|
||||||
|
lcd.print(itostr2(time/60));
|
||||||
|
lcd.print(':');
|
||||||
|
lcd.print(itostr2(time%60));
|
||||||
|
}else{
|
||||||
|
lcd_printPGM(PSTR("--:--"));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//Status message line on the last line
|
||||||
|
lcd.setCursor(0, LCD_HEIGHT - 1);
|
||||||
|
lcd.print(lcd_status_message);
|
||||||
|
}
|
||||||
|
static void lcd_implementation_drawmenu_generic(uint8_t row, const char* pstr, char pre_char, char post_char)
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
uint8_t n = LCD_WIDTH - 1 - 2;
|
||||||
|
lcd.setCursor(0, row);
|
||||||
|
lcd.print(pre_char);
|
||||||
|
while((c = pgm_read_byte(pstr)) != '\0')
|
||||||
|
{
|
||||||
|
lcd.print(c);
|
||||||
|
pstr++;
|
||||||
|
n--;
|
||||||
|
}
|
||||||
|
while(n--)
|
||||||
|
lcd.print(' ');
|
||||||
|
lcd.print(post_char);
|
||||||
|
lcd.print(' ');
|
||||||
|
}
|
||||||
|
static void lcd_implementation_drawmenu_setting_edit_generic(uint8_t row, const char* pstr, char pre_char, char* data)
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
uint8_t n = LCD_WIDTH - 1 - 2 - strlen(data);
|
||||||
|
lcd.setCursor(0, row);
|
||||||
|
lcd.print(pre_char);
|
||||||
|
while((c = pgm_read_byte(pstr)) != '\0')
|
||||||
|
{
|
||||||
|
lcd.print(c);
|
||||||
|
pstr++;
|
||||||
|
n--;
|
||||||
|
}
|
||||||
|
lcd.print(':');
|
||||||
|
while(n--)
|
||||||
|
lcd.print(' ');
|
||||||
|
lcd.print(data);
|
||||||
|
}
|
||||||
|
static void lcd_implementation_drawmenu_setting_edit_generic_P(uint8_t row, const char* pstr, char pre_char, const char* data)
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
uint8_t n = LCD_WIDTH - 1 - 2 - strlen_P(data);
|
||||||
|
lcd.setCursor(0, row);
|
||||||
|
lcd.print(pre_char);
|
||||||
|
while((c = pgm_read_byte(pstr)) != '\0')
|
||||||
|
{
|
||||||
|
lcd.print(c);
|
||||||
|
pstr++;
|
||||||
|
n--;
|
||||||
|
}
|
||||||
|
lcd.print(':');
|
||||||
|
while(n--)
|
||||||
|
lcd.print(' ');
|
||||||
|
lcd_printPGM(data);
|
||||||
|
}
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_int3_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', itostr3(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_int3(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', itostr3(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float3_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr3(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float3(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr3(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float32_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr32(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float32(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr32(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float5_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float5(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float52_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr52(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float52(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr52(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float51_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr51(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float51(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr51(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_long5_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_long5(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_bool_selected(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_bool(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, ' ', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
||||||
|
void lcd_implementation_drawedit(const char* pstr, char* value)
|
||||||
|
{
|
||||||
|
lcd.setCursor(0, 1);
|
||||||
|
lcd_printPGM(pstr);
|
||||||
|
lcd.print(':');
|
||||||
|
lcd.setCursor(19 - strlen(value), 1);
|
||||||
|
lcd.print(value);
|
||||||
|
}
|
||||||
|
static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
uint8_t n = LCD_WIDTH - 1;
|
||||||
|
lcd.setCursor(0, row);
|
||||||
|
lcd.print('>');
|
||||||
|
if (longFilename[0] != '\0')
|
||||||
|
{
|
||||||
|
filename = longFilename;
|
||||||
|
longFilename[LCD_WIDTH-1] = '\0';
|
||||||
|
}
|
||||||
|
while((c = *filename) != '\0')
|
||||||
|
{
|
||||||
|
lcd.print(c);
|
||||||
|
filename++;
|
||||||
|
n--;
|
||||||
|
}
|
||||||
|
while(n--)
|
||||||
|
lcd.print(' ');
|
||||||
|
}
|
||||||
|
static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
uint8_t n = LCD_WIDTH - 1;
|
||||||
|
lcd.setCursor(0, row);
|
||||||
|
lcd.print(' ');
|
||||||
|
if (longFilename[0] != '\0')
|
||||||
|
{
|
||||||
|
filename = longFilename;
|
||||||
|
longFilename[LCD_WIDTH-1] = '\0';
|
||||||
|
}
|
||||||
|
while((c = *filename) != '\0')
|
||||||
|
{
|
||||||
|
lcd.print(c);
|
||||||
|
filename++;
|
||||||
|
n--;
|
||||||
|
}
|
||||||
|
while(n--)
|
||||||
|
lcd.print(' ');
|
||||||
|
}
|
||||||
|
static void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
uint8_t n = LCD_WIDTH - 2;
|
||||||
|
lcd.setCursor(0, row);
|
||||||
|
lcd.print('>');
|
||||||
|
lcd.print(LCD_STR_FOLDER[0]);
|
||||||
|
if (longFilename[0] != '\0')
|
||||||
|
{
|
||||||
|
filename = longFilename;
|
||||||
|
longFilename[LCD_WIDTH-2] = '\0';
|
||||||
|
}
|
||||||
|
while((c = *filename) != '\0')
|
||||||
|
{
|
||||||
|
lcd.print(c);
|
||||||
|
filename++;
|
||||||
|
n--;
|
||||||
|
}
|
||||||
|
while(n--)
|
||||||
|
lcd.print(' ');
|
||||||
|
}
|
||||||
|
static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
uint8_t n = LCD_WIDTH - 2;
|
||||||
|
lcd.setCursor(0, row);
|
||||||
|
lcd.print(' ');
|
||||||
|
lcd.print(LCD_STR_FOLDER[0]);
|
||||||
|
if (longFilename[0] != '\0')
|
||||||
|
{
|
||||||
|
filename = longFilename;
|
||||||
|
longFilename[LCD_WIDTH-2] = '\0';
|
||||||
|
}
|
||||||
|
while((c = *filename) != '\0')
|
||||||
|
{
|
||||||
|
lcd.print(c);
|
||||||
|
filename++;
|
||||||
|
n--;
|
||||||
|
}
|
||||||
|
while(n--)
|
||||||
|
lcd.print(' ');
|
||||||
|
}
|
||||||
|
#define lcd_implementation_drawmenu_back_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0])
|
||||||
|
#define lcd_implementation_drawmenu_back(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', LCD_STR_UPLEVEL[0])
|
||||||
|
#define lcd_implementation_drawmenu_submenu_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, '>', LCD_STR_ARROW_RIGHT[0])
|
||||||
|
#define lcd_implementation_drawmenu_submenu(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', LCD_STR_ARROW_RIGHT[0])
|
||||||
|
#define lcd_implementation_drawmenu_gcode_selected(row, pstr, gcode) lcd_implementation_drawmenu_generic(row, pstr, '>', ' ')
|
||||||
|
#define lcd_implementation_drawmenu_gcode(row, pstr, gcode) lcd_implementation_drawmenu_generic(row, pstr, ' ', ' ')
|
||||||
|
#define lcd_implementation_drawmenu_function_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, '>', ' ')
|
||||||
|
#define lcd_implementation_drawmenu_function(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', ' ')
|
||||||
|
|
||||||
|
static void lcd_implementation_quick_feedback()
|
||||||
|
{
|
||||||
|
#if BEEPER > -1
|
||||||
|
SET_OUTPUT(BEEPER);
|
||||||
|
for(int8_t i=0;i<10;i++)
|
||||||
|
{
|
||||||
|
WRITE(BEEPER,HIGH);
|
||||||
|
delay(3);
|
||||||
|
WRITE(BEEPER,LOW);
|
||||||
|
delay(3);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif//ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
141
Marlin/wiring.h
141
Marlin/wiring.h
|
@ -1,141 +0,0 @@
|
||||||
/*
|
|
||||||
* fixed by this patch:
|
|
||||||
* http://code.google.com/p/arduino/issues/detail?id=604
|
|
||||||
* */
|
|
||||||
/*
|
|
||||||
wiring.h - Partial implementation of the Wiring API for the ATmega8.
|
|
||||||
Part of Arduino - http://www.arduino.cc/
|
|
||||||
|
|
||||||
Copyright (c) 2005-2006 David A. Mellis
|
|
||||||
|
|
||||||
This library is free software; you can redistribute it and/or
|
|
||||||
modify it under the terms of the GNU Lesser General Public
|
|
||||||
License as published by the Free Software Foundation; either
|
|
||||||
version 2.1 of the License, or (at your option) any later version.
|
|
||||||
|
|
||||||
This library is distributed in the hope that it will be useful,
|
|
||||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
|
||||||
Lesser General Public License for more details.
|
|
||||||
|
|
||||||
You should have received a copy of the GNU Lesser General
|
|
||||||
Public License along with this library; if not, write to the
|
|
||||||
Free Software Foundation, Inc., 59 Temple Place, Suite 330,
|
|
||||||
Boston, MA 02111-1307 USA
|
|
||||||
|
|
||||||
$Id$
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef Wiring_h
|
|
||||||
#define Wiring_h
|
|
||||||
|
|
||||||
#include <avr/io.h>
|
|
||||||
#include <stdlib.h>
|
|
||||||
#include "binary.h"
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
|
||||||
extern "C"{
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define HIGH 0x1
|
|
||||||
#define LOW 0x0
|
|
||||||
|
|
||||||
#define INPUT 0x0
|
|
||||||
#define OUTPUT 0x1
|
|
||||||
|
|
||||||
#define true 0x1
|
|
||||||
#define false 0x0
|
|
||||||
|
|
||||||
#define PI 3.1415926535897932384626433832795
|
|
||||||
#define HALF_PI 1.5707963267948966192313216916398
|
|
||||||
#define TWO_PI 6.283185307179586476925286766559
|
|
||||||
#define DEG_TO_RAD 0.017453292519943295769236907684886
|
|
||||||
#define RAD_TO_DEG 57.295779513082320876798154814105
|
|
||||||
|
|
||||||
#define SERIAL 0x0
|
|
||||||
#define DISPLAY 0x1
|
|
||||||
|
|
||||||
#define LSBFIRST 0
|
|
||||||
#define MSBFIRST 1
|
|
||||||
|
|
||||||
#define CHANGE 1
|
|
||||||
#define FALLING 2
|
|
||||||
#define RISING 3
|
|
||||||
|
|
||||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
|
||||||
#define INTERNAL1V1 2
|
|
||||||
#define INTERNAL2V56 3
|
|
||||||
#else
|
|
||||||
#define INTERNAL 3
|
|
||||||
#endif
|
|
||||||
#define DEFAULT 1
|
|
||||||
#define EXTERNAL 0
|
|
||||||
|
|
||||||
// undefine stdlib's abs if encountered
|
|
||||||
#ifdef abs
|
|
||||||
#undef abs
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define min(a,b) ((a)<(b)?(a):(b))
|
|
||||||
#define max(a,b) ((a)>(b)?(a):(b))
|
|
||||||
#define abs(x) ((x)>0?(x):-(x))
|
|
||||||
#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
|
|
||||||
#if __AVR_LIBC_VERSION__ < 10701UL
|
|
||||||
#define round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5))
|
|
||||||
#endif
|
|
||||||
#define radians(deg) ((deg)*DEG_TO_RAD)
|
|
||||||
#define degrees(rad) ((rad)*RAD_TO_DEG)
|
|
||||||
#define sq(x) ((x)*(x))
|
|
||||||
|
|
||||||
#define interrupts() sei()
|
|
||||||
#define noInterrupts() cli()
|
|
||||||
|
|
||||||
#define clockCyclesPerMicrosecond() ( F_CPU / 1000000L )
|
|
||||||
#define clockCyclesToMicroseconds(a) ( ((a) * 1000L) / (F_CPU / 1000L) )
|
|
||||||
#define microsecondsToClockCycles(a) ( ((a) * (F_CPU / 1000L)) / 1000L )
|
|
||||||
|
|
||||||
#define lowByte(w) ((uint8_t) ((w) & 0xff))
|
|
||||||
#define highByte(w) ((uint8_t) ((w) >> 8))
|
|
||||||
|
|
||||||
#define bitRead(value, bit) (((value) >> (bit)) & 0x01)
|
|
||||||
#define bitSet(value, bit) ((value) |= (1UL << (bit)))
|
|
||||||
#define bitClear(value, bit) ((value) &= ~(1UL << (bit)))
|
|
||||||
#define bitWrite(value, bit, bitvalue) (bitvalue ? bitSet(value, bit) : bitClear(value, bit))
|
|
||||||
|
|
||||||
|
|
||||||
typedef unsigned int word;
|
|
||||||
|
|
||||||
#define bit(b) (1UL << (b))
|
|
||||||
|
|
||||||
typedef uint8_t boolean;
|
|
||||||
typedef uint8_t byte;
|
|
||||||
|
|
||||||
void init(void);
|
|
||||||
|
|
||||||
void pinMode(uint8_t, uint8_t);
|
|
||||||
void digitalWrite(uint8_t, uint8_t);
|
|
||||||
int digitalRead(uint8_t);
|
|
||||||
int analogRead(uint8_t);
|
|
||||||
void analogReference(uint8_t mode);
|
|
||||||
void analogWrite(uint8_t, int);
|
|
||||||
|
|
||||||
unsigned long millis(void);
|
|
||||||
unsigned long micros(void);
|
|
||||||
void delay(unsigned long);
|
|
||||||
void delayMicroseconds(unsigned int us);
|
|
||||||
unsigned long pulseIn(uint8_t pin, uint8_t state, unsigned long timeout);
|
|
||||||
|
|
||||||
void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, uint8_t val);
|
|
||||||
uint8_t shiftIn(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder);
|
|
||||||
|
|
||||||
void attachInterrupt(uint8_t, void (*)(void), int mode);
|
|
||||||
void detachInterrupt(uint8_t);
|
|
||||||
|
|
||||||
void setup(void);
|
|
||||||
void loop(void);
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
|
||||||
} // extern "C"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif
|
|
|
@ -184,11 +184,11 @@ MISC:
|
||||||
Configuring and compilation:
|
Configuring and compilation:
|
||||||
============================
|
============================
|
||||||
|
|
||||||
Install the arduino software IDE/toolset v22
|
Install the arduino software IDE/toolset v23 (Some configurations also work with 1.x.x)
|
||||||
http://www.arduino.cc/en/Main/Software
|
http://www.arduino.cc/en/Main/Software
|
||||||
|
|
||||||
For gen6 and sanguinololu the Sanguino directory in the Marlin dir needs to be copied to the arduino environment.
|
For gen6/gen7 and sanguinololu the Sanguino directory in the Marlin dir needs to be copied to the arduino environment.
|
||||||
copy Marlin\sanguino <arduino home>\hardware\Sanguino
|
copy ArduinoAddons\Arduino_x.x.x\sanguino <arduino home>\hardware\Sanguino
|
||||||
|
|
||||||
Install Ultimaker's RepG 25 build
|
Install Ultimaker's RepG 25 build
|
||||||
http://software.ultimaker.com
|
http://software.ultimaker.com
|
||||||
|
|
Reference in a new issue