Merge remote-tracking branch 'remotes/upstream/Development' into Development

master
domonoky 10 years ago
commit 4a7aca2736

@ -33,7 +33,7 @@ rambo.build.variant=rambo
########################################
sanguino.name=Sanguino
sanguino.upload.tool=ardunio:avrdude
sanguino.upload.tool=arduino:avrdude
sanguino.upload.protocol=stk500
sanguino.upload.maximum_size=131072
sanguino.upload.speed=57600

@ -5,16 +5,9 @@
#include "Marlin.h"
#ifdef BLINKM
#if (ARDUINO >= 100)
# include "Arduino.h"
#else
# include "WProgram.h"
#endif
#include "BlinkM.h"
void SendColors(byte red, byte grn, byte blu)
{
void SendColors(byte red, byte grn, byte blu) {
Wire.begin();
Wire.beginTransmission(0x09);
Wire.write('o'); //to disable ongoing script, only needs to be used once

@ -2,13 +2,12 @@
BlinkM.h
Library header file for BlinkM library
*/
#if (ARDUINO >= 100)
# include "Arduino.h"
#if ARDUINO >= 100
#include "Arduino.h"
#else
# include "WProgram.h"
#include "WProgram.h"
#endif
#include "Wire.h"
void SendColors(byte red, byte grn, byte blu);

@ -118,7 +118,10 @@ Here are some standard links for getting your machine calibrated:
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 999 is a Dummy Table. It will ALWAYS read 25C.. Use it for Testing or Development purposes. NEVER for production machine.
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
#define TEMP_SENSOR_0 -1
#define TEMP_SENSOR_1 -1
@ -582,6 +585,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
@ -640,6 +647,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#if defined (PANEL_ONE)
#define SDSUPPORT
#define ULTIMAKERCONTROLLER
#endif
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
#define DOGLCD

@ -1,5 +1,5 @@
#ifndef CONFIG_STORE_H
#define CONFIG_STORE_H
#ifndef CONFIGURATIONSTORE_H
#define CONFIGURATIONSTORE_H
#include "Configuration.h"
@ -19,4 +19,4 @@ void Config_ResetDefault();
FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); }
#endif
#endif // __CONFIG_STORE_H
#endif //CONFIGURATIONSTORE_H

@ -181,7 +181,7 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#endif
enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5};
//X_HEAD and Y_HEAD is used for systems that don't have a 1:1 relationship between X_AXIS and X Head movement, like CoreXY bots.
void FlushSerialRequestResend();
void ClearToSend();

@ -1720,6 +1720,7 @@ void process_commands()
#ifdef ENABLE_AUTO_BED_LEVELING
case 29: // G29 Detailed Z-Probe, probes the bed at 3 or more points.
// Override probing area by providing [F]ront [B]ack [L]eft [R]ight Grid[P]oints values
{
#if Z_MIN_PIN == -1
#error "You must have a Z_MIN endstop in order to enable Auto Bed Leveling feature!!! Z_MIN_PIN must point to a valid hardware pin."
@ -1753,9 +1754,19 @@ void process_commands()
feedrate = homing_feedrate[Z_AXIS];
#ifdef AUTO_BED_LEVELING_GRID
// probe at the points of a lattice grid
int left_probe_bed_position=LEFT_PROBE_BED_POSITION;
int right_probe_bed_position=RIGHT_PROBE_BED_POSITION;
int back_probe_bed_position=BACK_PROBE_BED_POSITION;
int front_probe_bed_position=FRONT_PROBE_BED_POSITION;
int auto_bed_leveling_grid_points=AUTO_BED_LEVELING_GRID_POINTS;
if (code_seen('L')) left_probe_bed_position=(int)code_value();
if (code_seen('R')) right_probe_bed_position=(int)code_value();
if (code_seen('B')) back_probe_bed_position=(int)code_value();
if (code_seen('F')) front_probe_bed_position=(int)code_value();
if (code_seen('P')) auto_bed_leveling_grid_points=(int)code_value();
int xGridSpacing = (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
int yGridSpacing = (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
int xGridSpacing = (right_probe_bed_position - left_probe_bed_position) / (auto_bed_leveling_grid_points-1);
int yGridSpacing = (back_probe_bed_position - front_probe_bed_position) / (auto_bed_leveling_grid_points-1);
// solve the plane equation ax + by + d = z
@ -1765,32 +1776,35 @@ void process_commands()
// so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z
// "A" matrix of the linear system of equations
double eqnAMatrix[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS*3];
double eqnAMatrix[auto_bed_leveling_grid_points*auto_bed_leveling_grid_points*3];
// "B" vector of Z points
double eqnBVector[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS];
double eqnBVector[auto_bed_leveling_grid_points*auto_bed_leveling_grid_points];
int probePointCounter = 0;
bool zig = true;
for (int yProbe=FRONT_PROBE_BED_POSITION; yProbe <= BACK_PROBE_BED_POSITION; yProbe += yGridSpacing)
for (int yProbe=front_probe_bed_position; yProbe <= back_probe_bed_position; yProbe += yGridSpacing)
{
int xProbe, xInc;
if (zig)
{
xProbe = LEFT_PROBE_BED_POSITION;
//xEnd = RIGHT_PROBE_BED_POSITION;
xProbe = left_probe_bed_position;
//xEnd = right_probe_bed_position;
xInc = xGridSpacing;
zig = false;
} else // zag
{
xProbe = RIGHT_PROBE_BED_POSITION;
//xEnd = LEFT_PROBE_BED_POSITION;
xProbe = right_probe_bed_position;
//xEnd = left_probe_bed_position;
xInc = -xGridSpacing;
zig = true;
}
for (int xCount=0; xCount < AUTO_BED_LEVELING_GRID_POINTS; xCount++)
for (int xCount=0; xCount < auto_bed_leveling_grid_points; xCount++)
{
float z_before;
if (probePointCounter == 0)
@ -1822,9 +1836,9 @@ void process_commands()
eqnBVector[probePointCounter] = measured_z;
eqnAMatrix[probePointCounter + 0*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = xProbe;
eqnAMatrix[probePointCounter + 1*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = yProbe;
eqnAMatrix[probePointCounter + 2*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = 1;
eqnAMatrix[probePointCounter + 0*auto_bed_leveling_grid_points*auto_bed_leveling_grid_points] = xProbe;
eqnAMatrix[probePointCounter + 1*auto_bed_leveling_grid_points*auto_bed_leveling_grid_points] = yProbe;
eqnAMatrix[probePointCounter + 2*auto_bed_leveling_grid_points*auto_bed_leveling_grid_points] = 1;
probePointCounter++;
xProbe += xInc;
}
@ -1832,7 +1846,7 @@ void process_commands()
clean_up_after_endstop_move();
// solve lsq problem
double *plane_equation_coefficients = qr_solve(AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS, 3, eqnAMatrix, eqnBVector);
double *plane_equation_coefficients = qr_solve(auto_bed_leveling_grid_points*auto_bed_leveling_grid_points, 3, eqnAMatrix, eqnBVector);
SERIAL_PROTOCOLPGM("Eqn coefficients: a: ");
SERIAL_PROTOCOL(plane_equation_coefficients[0]);
@ -4695,21 +4709,12 @@ bool setTargetedHotend(int code){
float calculate_volumetric_multiplier(float diameter) {
float area = .0;
float radius = .0;
radius = diameter * .5;
if (! volumetric_enabled || radius == 0) {
area = 1;
}
else {
area = M_PI * pow(radius, 2);
}
return 1.0 / area;
if (!volumetric_enabled || diameter == 0) return 1.0;
float d2 = diameter * 0.5;
return 1.0 / (M_PI * d2 * d2);
}
void calculate_volumetric_multipliers() {
for (int i=0; i<EXTRUDERS; i++)
volumetric_multiplier[i] = calculate_volumetric_multiplier(filament_size[i]);
volumetric_multiplier[i] = calculate_volumetric_multiplier(filament_size[i]);
}

@ -7,256 +7,194 @@
#ifdef SDSUPPORT
CardReader::CardReader() {
filesize = 0;
sdpos = 0;
sdprinting = false;
cardOK = false;
saving = false;
logging = false;
workDirDepth = 0;
file_subcall_ctr = 0;
memset(workDirParents, 0, sizeof(workDirParents));
CardReader::CardReader()
{
filesize = 0;
sdpos = 0;
sdprinting = false;
cardOK = false;
saving = false;
logging = false;
autostart_atmillis=0;
workDirDepth = 0;
file_subcall_ctr=0;
memset(workDirParents, 0, sizeof(workDirParents));
autostart_stilltocheck=true; //the SD start is delayed, because otherwise the serial cannot answer fast enough to make contact with the host software.
autostart_index=0;
autostart_stilltocheck = true; //the SD start is delayed, because otherwise the serial cannot answer fast enough to make contact with the host software.
autostart_index = 0;
//power to SD reader
#if SDPOWER > -1
SET_OUTPUT(SDPOWER);
WRITE(SDPOWER,HIGH);
WRITE(SDPOWER, HIGH);
#endif //SDPOWER
autostart_atmillis=millis()+5000;
autostart_atmillis = millis() + 5000;
}
char *createFilename(char *buffer,const dir_t &p) //buffer>12characters
{
char *pos=buffer;
for (uint8_t i = 0; i < 11; i++)
{
if (p.name[i] == ' ')continue;
if (i == 8)
{
*pos++='.';
}
*pos++=p.name[i];
char *createFilename(char *buffer, const dir_t &p) { //buffer > 12characters
char *pos = buffer;
for (uint8_t i = 0; i < 11; i++) {
if (p.name[i] == ' ') continue;
if (i == 8) *pos++ = '.';
*pos++ = p.name[i];
}
*pos++=0;
*pos++ = 0;
return buffer;
}
void CardReader::lsDive(const char *prepend, SdFile parent, const char * const match/*=NULL*/)
{
void CardReader::lsDive(const char *prepend, SdFile parent, const char * const match/*=NULL*/) {
dir_t p;
uint8_t cnt=0;
while (parent.readDir(p, longFilename) > 0)
{
if( DIR_IS_SUBDIR(&p) && lsAction!=LS_Count && lsAction!=LS_GetFilename) // hence LS_SerialPrint
{
uint8_t cnt = 0;
while (parent.readDir(p, longFilename) > 0) {
if (DIR_IS_SUBDIR(&p) && lsAction != LS_Count && lsAction != LS_GetFilename) { // hence LS_SerialPrint
char path[FILENAME_LENGTH*2];
char lfilename[FILENAME_LENGTH];
createFilename(lfilename,p);
createFilename(lfilename, p);
path[0]=0;
if(prepend[0]==0) //avoid leading / if already in prepend
{
strcat(path,"/");
}
strcat(path,prepend);
strcat(path,lfilename);
strcat(path,"/");
path[0] = 0;
if (prepend[0] == 0) strcat(path, "/"); //avoid leading / if already in prepend
strcat(path, prepend);
strcat(path, lfilename);
strcat(path, "/");
//Serial.print(path);
SdFile dir;
if(!dir.open(parent,lfilename, O_READ))
{
if(lsAction==LS_SerialPrint)
{
if (!dir.open(parent, lfilename, O_READ)) {
if (lsAction == LS_SerialPrint) {
SERIAL_ECHO_START;
SERIAL_ECHOLN(MSG_SD_CANT_OPEN_SUBDIR);
SERIAL_ECHOLN(lfilename);
}
}
lsDive(path,dir);
lsDive(path, dir);
//close done automatically by destructor of SdFile
}
else
{
else {
char pn0 = p.name[0];
if (pn0 == DIR_NAME_FREE) break;
if (pn0 == DIR_NAME_DELETED || pn0 == '.' || pn0 == '_') continue;
if (pn0 == DIR_NAME_DELETED || pn0 == '.') continue;
char lf0 = longFilename[0];
if (lf0 == '.' || lf0 == '_') continue;
if (lf0 == '.') continue;
if (!DIR_IS_FILE_OR_SUBDIR(&p)) continue;
filenameIsDir=DIR_IS_SUBDIR(&p);
filenameIsDir = DIR_IS_SUBDIR(&p);
if(!filenameIsDir)
{
if(p.name[8]!='G') continue;
if(p.name[9]=='~') continue;
}
//if(cnt++!=nr) continue;
createFilename(filename,p);
if(lsAction==LS_SerialPrint)
{
if (!filenameIsDir && (p.name[8] != 'G' || p.name[9] == '~')) continue;
//if (cnt++ != nr) continue;
createFilename(filename, p);
if (lsAction == LS_SerialPrint) {
SERIAL_PROTOCOL(prepend);
SERIAL_PROTOCOLLN(filename);
}
else if(lsAction==LS_Count)
{
else if (lsAction == LS_Count) {
nrFiles++;
}
else if(lsAction==LS_GetFilename)
{
else if (lsAction == LS_GetFilename) {
if (match != NULL) {
if (strcasecmp(match, filename) == 0) return;
}
else if (cnt == nrFiles) return;
cnt++;
}
}
}
}
void CardReader::ls()
{
lsAction=LS_SerialPrint;
if(lsAction==LS_Count)
nrFiles=0;
void CardReader::ls() {
lsAction = LS_SerialPrint;
root.rewind();
lsDive("",root);
lsDive("", root);
}
void CardReader::initsd()
{
void CardReader::initsd() {
cardOK = false;
if(root.isOpen())
root.close();
#ifdef SDSLOW
if (!card.init(SPI_HALF_SPEED,SDSS)
#if defined(LCD_SDSS) && (LCD_SDSS != SDSS)
&& !card.init(SPI_HALF_SPEED,LCD_SDSS)
#endif
)
#else
if (!card.init(SPI_FULL_SPEED,SDSS)
#if defined(LCD_SDSS) && (LCD_SDSS != SDSS)
&& !card.init(SPI_FULL_SPEED,LCD_SDSS)
if (root.isOpen()) root.close();
#ifdef SDSLOW
#define SPI_SPEED SPI_HALF_SPEED
#else
#define SPI_SPEED SPI_FULL_SPEED
#endif
)
#endif
{
if (!card.init(SPI_SPEED,SDSS)
#if defined(LCD_SDSS) && (LCD_SDSS != SDSS)
&& !card.init(SPI_SPEED, LCD_SDSS)
#endif
) {
//if (!card.init(SPI_HALF_SPEED,SDSS))
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_SD_INIT_FAIL);
}
else if (!volume.init(&card))
{
else if (!volume.init(&card)) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_SD_VOL_INIT_FAIL);
}
else if (!root.openRoot(&volume))
{
else if (!root.openRoot(&volume)) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_SD_OPENROOT_FAIL);
}
else
{
else {
cardOK = true;
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_SD_CARD_OK);
}
workDir=root;
curDir=&root;
workDir = root;
curDir = &root;
/*
if(!workDir.openRoot(&volume))
{
if (!workDir.openRoot(&volume)) {
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
}
*/
}
void CardReader::setroot()
{
/*if(!workDir.openRoot(&volume))
{
void CardReader::setroot() {
/*if (!workDir.openRoot(&volume)) {
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
}*/
workDir=root;
curDir=&workDir;
workDir = root;
curDir = &workDir;
}
void CardReader::release()
{
void CardReader::release() {
sdprinting = false;
cardOK = false;
}
void CardReader::startFileprint()
{
if(cardOK)
{
void CardReader::startFileprint() {
if (cardOK) {
sdprinting = true;
}
}
void CardReader::pauseSDPrint()
{
if(sdprinting)
{
sdprinting = false;
}
void CardReader::pauseSDPrint() {
if (sdprinting) sdprinting = false;
}
void CardReader::openLogFile(char* name)
{
void CardReader::openLogFile(char* name) {
logging = true;
openFile(name, false);
}
void CardReader::getAbsFilename(char *t)
{
uint8_t cnt=0;
*t='/';t++;cnt++;
for(uint8_t i=0;i<workDirDepth;i++)
{
void CardReader::getAbsFilename(char *t) {
uint8_t cnt = 0;
*t = '/'; t++; cnt++;
for (uint8_t i = 0; i < workDirDepth; i++) {
workDirParents[i].getFilename(t); //SDBaseFile.getfilename!
while(*t!=0 && cnt< MAXPATHNAMELENGTH)
{t++;cnt++;} //crawl counter forward.
while(*t && cnt < MAXPATHNAMELENGTH) { t++; cnt++; } //crawl counter forward.
}
if(cnt<MAXPATHNAMELENGTH-FILENAME_LENGTH)
if (cnt < MAXPATHNAMELENGTH - FILENAME_LENGTH)
file.getFilename(t);
else
t[0]=0;
t[0] = 0;
}
void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
{
if(!cardOK)
return;
if(file.isOpen()) //replacing current file by new file, or subfile call
{
if(!replace_current)
{
if((int)file_subcall_ctr>(int)SD_PROCEDURE_DEPTH-1)
{
void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/) {
if (!cardOK) return;
if (file.isOpen()) { //replacing current file by new file, or subfile call
if (!replace_current) {
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
SERIAL_ERROR_START;
SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
SERIAL_ERRORLN(SD_PROCEDURE_DEPTH);
@ -275,79 +213,67 @@ void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
SERIAL_ECHO(filenames[file_subcall_ctr]);
SERIAL_ECHOPGM("\" pos");
SERIAL_ECHOLN(sdpos);
filespos[file_subcall_ctr]=sdpos;
filespos[file_subcall_ctr] = sdpos;
file_subcall_ctr++;
}
else
{
else {
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Now doing file: ");
SERIAL_ECHOLN(name);
}
file.close();
}
else //opening fresh file
{
file_subcall_ctr=0; //resetting procedure depth in case user cancels print while in procedure
else { //opening fresh file
file_subcall_ctr = 0; //resetting procedure depth in case user cancels print while in procedure
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Now fresh file: ");
SERIAL_ECHOLN(name);
}
sdprinting = false;
SdFile myDir;
curDir=&root;
char *fname=name;
char *dirname_start,*dirname_end;
if(name[0]=='/')
{
dirname_start=strchr(name,'/')+1;
while(dirname_start>0)
{
dirname_end=strchr(dirname_start,'/');
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start-name));
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end-name));
if(dirname_end>0 && dirname_end>dirname_start)
{
curDir = &root;
char *fname = name;
char *dirname_start, *dirname_end;
if (name[0] == '/') {
dirname_start = &name[1];
while(dirname_start > 0) {
dirname_end = strchr(dirname_start, '/');
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start - name));
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end - name));
if (dirname_end > 0 && dirname_end > dirname_start) {
char subdirname[FILENAME_LENGTH];
strncpy(subdirname, dirname_start, dirname_end-dirname_start);
subdirname[dirname_end-dirname_start]=0;
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
subdirname[dirname_end - dirname_start] = 0;
SERIAL_ECHOLN(subdirname);
if(!myDir.open(curDir,subdirname,O_READ))
{
if (!myDir.open(curDir, subdirname, O_READ)) {
SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
SERIAL_PROTOCOL(subdirname);
SERIAL_PROTOCOLLNPGM(".");
return;
}
else
{
else {
//SERIAL_ECHOLN("dive ok");
}
curDir=&myDir;
dirname_start=dirname_end+1;
curDir = &myDir;
dirname_start = dirname_end + 1;
}
else // the reminder after all /fsa/fdsa/ is the filename
{
fname=dirname_start;
//SERIAL_ECHOLN("remaider");
else { // the remainder after all /fsa/fdsa/ is the filename
fname = dirname_start;
//SERIAL_ECHOLN("remainder");
//SERIAL_ECHOLN(fname);
break;
}
}
}
else //relative path
{
curDir=&workDir;
else { //relative path
curDir = &workDir;
}
if(read)
{
if (file.open(curDir, fname, O_READ))
{
if (read) {
if (file.open(curDir, fname, O_READ)) {
filesize = file.fileSize();
SERIAL_PROTOCOLPGM(MSG_SD_FILE_OPENED);
SERIAL_PROTOCOL(fname);
@ -359,124 +285,105 @@ void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
getfilename(0, fname);
lcd_setstatus(longFilename[0] ? longFilename : fname);
}
else
{
else {
SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
SERIAL_PROTOCOL(fname);
SERIAL_PROTOCOLLNPGM(".");
}
}
else
{ //write
if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC))
{
else { //write
if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) {
SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
SERIAL_PROTOCOL(fname);
SERIAL_PROTOCOLLNPGM(".");
}
else
{
else {
saving = true;
SERIAL_PROTOCOLPGM(MSG_SD_WRITE_TO_FILE);
SERIAL_PROTOCOLLN(name);
lcd_setstatus(fname);
}
}
}
void CardReader::removeFile(char* name)
{
if(!cardOK)
return;
void CardReader::removeFile(char* name) {
if (!cardOK) return;
file.close();
sdprinting = false;
SdFile myDir;
curDir=&root;
char *fname=name;
char *dirname_start,*dirname_end;
if(name[0]=='/')
{
dirname_start=strchr(name,'/')+1;
while(dirname_start>0)
{
dirname_end=strchr(dirname_start,'/');
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start-name));
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end-name));
if(dirname_end>0 && dirname_end>dirname_start)
{
curDir = &root;
char *fname = name;
char *dirname_start, *dirname_end;
if (name[0] == '/') {
dirname_start = strchr(name, '/') + 1;
while (dirname_start > 0) {
dirname_end = strchr(dirname_start, '/');
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start - name));
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end - name));
if (dirname_end > 0 && dirname_end > dirname_start) {
char subdirname[FILENAME_LENGTH];
strncpy(subdirname, dirname_start, dirname_end-dirname_start);
subdirname[dirname_end-dirname_start]=0;
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
subdirname[dirname_end - dirname_start] = 0;
SERIAL_ECHOLN(subdirname);
if(!myDir.open(curDir,subdirname,O_READ))
{
if (!myDir.open(curDir, subdirname, O_READ)) {
SERIAL_PROTOCOLPGM("open failed, File: ");
SERIAL_PROTOCOL(subdirname);
SERIAL_PROTOCOLLNPGM(".");
return;
}
else
{
else {
//SERIAL_ECHOLN("dive ok");
}
curDir=&myDir;
dirname_start=dirname_end+1;
curDir = &myDir;
dirname_start = dirname_end + 1;
}
else // the reminder after all /fsa/fdsa/ is the filename
{
fname=dirname_start;
//SERIAL_ECHOLN("remaider");
else { // the remainder after all /fsa/fdsa/ is the filename
fname = dirname_start;
//SERIAL_ECHOLN("remainder");
//SERIAL_ECHOLN(fname);
break;
}
}
}
else //relative path
{
curDir=&workDir;
else { // relative path
curDir = &workDir;
}
if (file.remove(curDir, fname))
{
SERIAL_PROTOCOLPGM("File deleted:");
SERIAL_PROTOCOLLN(fname);
sdpos = 0;
}
else
{
SERIAL_PROTOCOLPGM("Deletion failed, File: ");
SERIAL_PROTOCOL(fname);
SERIAL_PROTOCOLLNPGM(".");
}
if (file.remove(curDir, fname)) {
SERIAL_PROTOCOLPGM("File deleted:");
SERIAL_PROTOCOLLN(fname);
sdpos = 0;
}
else {
SERIAL_PROTOCOLPGM("Deletion failed, File: ");
SERIAL_PROTOCOL(fname);
SERIAL_PROTOCOLLNPGM(".");
}
}
void CardReader::getStatus()
{
if(cardOK){
void CardReader::getStatus() {
if (cardOK) {
SERIAL_PROTOCOLPGM(MSG_SD_PRINTING_BYTE);
SERIAL_PROTOCOL(sdpos);
SERIAL_PROTOCOLPGM("/");
SERIAL_PROTOCOLLN(filesize);
}
else{
else {
SERIAL_PROTOCOLLNPGM(MSG_SD_NOT_PRINTING);
}
}
void CardReader::write_command(char *buf)
{
void CardReader::write_command(char *buf) {
char* begin = buf;
char* npos = 0;
char* end = buf + strlen(buf) - 1;
file.writeError = false;
if((npos = strchr(buf, 'N')) != NULL)
{
if ((npos = strchr(buf, 'N')) != NULL) {
begin = strchr(npos, ' ') + 1;
end = strchr(npos, '*') - 1;
}
@ -484,162 +391,129 @@ void CardReader::write_command(char *buf)
end[2] = '\n';
end[3] = '\0';
file.write(begin);
if (file.writeError)
{
if (file.writeError) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(MSG_SD_ERR_WRITE_TO_FILE);
}
}
void CardReader::checkautostart(bool force) {
if (!force && (!autostart_stilltocheck || autostart_atmillis < millis()))
return;
void CardReader::checkautostart(bool force)
{
if(!force)
{
if(!autostart_stilltocheck)
return;
if(autostart_atmillis<millis())
return;
}
autostart_stilltocheck=false;
if(!cardOK)
{
autostart_stilltocheck = false;
if (!cardOK) {
initsd();
if(!cardOK) //fail
return;
if (!cardOK) return; // fail
}
char autoname[30];
sprintf_P(autoname, PSTR("auto%i.g"), autostart_index);
for(int8_t i=0;i<(int8_t)strlen(autoname);i++)
autoname[i]=tolower(autoname[i]);
for (int8_t i = 0; i < (int8_t)strlen(autoname); i++) autoname[i] = tolower(autoname[i]);
dir_t p;
root.rewind();
bool found=false;
while (root.readDir(p, NULL) > 0)
{
for(int8_t i=0;i<(int8_t)strlen((char*)p.name);i++)
p.name[i]=tolower(p.name[i]);
//Serial.print((char*)p.name);
//Serial.print(" ");
//Serial.println(autoname);
if(p.name[9]!='~') //skip safety copies
if(strncmp((char*)p.name,autoname,5)==0)
{
bool found = false;
while (root.readDir(p, NULL) > 0) {
for (int8_t i = 0; i < (int8_t)strlen((char*)p.name); i++) p.name[i] = tolower(p.name[i]);
if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) {
char cmd[30];
sprintf_P(cmd, PSTR("M23 %s"), autoname);
enquecommand(cmd);
enquecommands_P(PSTR("M24"));
found=true;
found = true;
}
}
if(!found)
autostart_index=-1;
if (!found)
autostart_index = -1;
else
autostart_index++;
}
void CardReader::closefile(bool store_location)
{
void CardReader::closefile(bool store_location) {
file.sync();
file.close();
saving = false;
logging = false;
saving = logging = false;
if(store_location)
{
if (store_location) {
//future: store printer state, filename and position for continuing a stopped print
// so one can unplug the printer and continue printing the next day.
}
}
void CardReader::getfilename(uint16_t nr, const char * const match/*=NULL*/)
{
curDir=&workDir;
lsAction=LS_GetFilename;
nrFiles=nr;
/**
* Get the name of a file in the current directory by index
*/
void CardReader::getfilename(uint16_t nr, const char * const match/*=NULL*/) {
curDir = &workDir;
lsAction = LS_GetFilename;
nrFiles = nr;
curDir->rewind();
lsDive("",*curDir,match);
lsDive("", *curDir, match);
}
uint16_t CardReader::getnrfilenames()
{
curDir=&workDir;
lsAction=LS_Count;
nrFiles=0;
uint16_t CardReader::getnrfilenames() {
curDir = &workDir;
lsAction = LS_Count;
nrFiles = 0;
curDir->rewind();
lsDive("",*curDir);
lsDive("", *curDir);
//SERIAL_ECHOLN(nrFiles);
return nrFiles;
}
void CardReader::chdir(const char * relpath)
{
void CardReader::chdir(const char * relpath) {
SdFile newfile;
SdFile *parent=&root;
SdFile *parent = &root;
if(workDir.isOpen())
parent=&workDir;
if (workDir.isOpen()) parent = &workDir;
if(!newfile.open(*parent,relpath, O_READ))
{
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
SERIAL_ECHOLN(relpath);
if (!newfile.open(*parent, relpath, O_READ)) {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
SERIAL_ECHOLN(relpath);
}
else
{
else {
if (workDirDepth < MAX_DIR_DEPTH) {
for (int d = ++workDirDepth; d--;)
workDirParents[d+1] = workDirParents[d];
workDirParents[0]=*parent;
++workDirDepth;
for (int d = workDirDepth; d--;) workDirParents[d + 1] = workDirParents[d];
workDirParents[0] = *parent;
}
workDir=newfile;
workDir = newfile;
}
}
void CardReader::updir()
{
if(workDirDepth > 0)
{
void CardReader::updir() {
if (workDirDepth > 0) {
--workDirDepth;
workDir = workDirParents[0];
int d;
for (int d = 0; d < workDirDepth; d++)
workDirParents[d] = workDirParents[d+1];
}
}
void CardReader::printingHasFinished()
{
st_synchronize();
if(file_subcall_ctr>0) //heading up to a parent file that called current as a procedure.
{
file.close();
file_subcall_ctr--;
openFile(filenames[file_subcall_ctr],true,true);
setIndex(filespos[file_subcall_ctr]);
startFileprint();
}
else
{
quickStop();
file.close();
sdprinting = false;
if(SD_FINISHED_STEPPERRELEASE)
{
//finishAndDisableSteppers();
enquecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
}
autotempShutdown();
void CardReader::printingHasFinished() {
st_synchronize();
if (file_subcall_ctr > 0) { // Heading up to a parent file that called current as a procedure.
file.close();
file_subcall_ctr--;
openFile(filenames[file_subcall_ctr], true, true);
setIndex(filespos[file_subcall_ctr]);
startFileprint();
}
else {
quickStop();
file.close();
sdprinting = false;
if (SD_FINISHED_STEPPERRELEASE) {
//finishAndDisableSteppers();
enquecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
}
autotempShutdown();
}
}
#endif //SDSUPPORT

@ -3,12 +3,12 @@
#ifdef SDSUPPORT
#define MAX_DIR_DEPTH 10
#define MAX_DIR_DEPTH 10 // Maximum folder depth
#include "SdFile.h"
enum LsAction {LS_SerialPrint,LS_Count,LS_GetFilename};
class CardReader
{
enum LsAction { LS_SerialPrint, LS_Count, LS_GetFilename };
class CardReader {
public:
CardReader();
@ -33,7 +33,6 @@ public:
void getAbsFilename(char *t);
void ls();
void chdir(const char * relpath);
void updir();
@ -41,56 +40,52 @@ public:
FORCE_INLINE bool isFileOpen() { return file.isOpen(); }
FORCE_INLINE bool eof() { return sdpos>=filesize ;};
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 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 bool eof() { return sdpos >= filesize; }
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 uint8_t percentDone() { return (isFileOpen() && filesize) ? sdpos / ((filesize + 99) / 100) : 0; }
FORCE_INLINE char* getWorkDirName() { workDir.getFilename(filename); return filename; }
public:
bool saving;
bool logging;
bool sdprinting;
bool cardOK;
char filename[FILENAME_LENGTH];
char longFilename[LONG_FILENAME_LENGTH];
bool filenameIsDir;
bool saving, logging, sdprinting, cardOK, filenameIsDir;
char filename[FILENAME_LENGTH], longFilename[LONG_FILENAME_LENGTH];
int autostart_index;
private:
SdFile root,*curDir,workDir,workDirParents[MAX_DIR_DEPTH];
SdFile root, *curDir, workDir, workDirParents[MAX_DIR_DEPTH];
uint16_t workDirDepth;
Sd2Card card;
SdVolume volume;
SdFile file;
#define SD_PROCEDURE_DEPTH 1
#define MAXPATHNAMELENGTH (FILENAME_LENGTH*MAX_DIR_DEPTH+MAX_DIR_DEPTH+1)
#define MAXPATHNAMELENGTH (FILENAME_LENGTH*MAX_DIR_DEPTH + MAX_DIR_DEPTH + 1)
uint8_t file_subcall_ctr;
uint32_t filespos[SD_PROCEDURE_DEPTH];
char filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH];
uint32_t filesize;
//int16_t n;
unsigned long autostart_atmillis;
uint32_t sdpos ;
uint32_t sdpos;
bool autostart_stilltocheck; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
LsAction lsAction; //stored for recursion.
int16_t nrFiles; //counter for the files in the current directory and recycled as position counter for getting the nrFiles'th name in the directory.
uint16_t nrFiles; //counter for the files in the current directory and recycled as position counter for getting the nrFiles'th name in the directory.
char* diveDirName;
void lsDive(const char *prepend, SdFile parent, const char * const match=NULL);
};
extern CardReader card;
#define IS_SD_PRINTING (card.sdprinting)
#if (SDCARDDETECT > -1)
# ifdef SDCARDDETECTINVERTED
# define IS_SD_INSERTED (READ(SDCARDDETECT)!=0)
# else
# define IS_SD_INSERTED (READ(SDCARDDETECT)==0)
# endif //SDCARDTETECTINVERTED
#ifdef SDCARDDETECTINVERTED
#define IS_SD_INSERTED (READ(SDCARDDETECT) != 0)
#else
#define IS_SD_INSERTED (READ(SDCARDDETECT) == 0)
#endif
#else
//If we don't have a card detect line, aways asume the card is inserted
# define IS_SD_INSERTED true
//No card detect line? Assume the card is inserted.
#define IS_SD_INSERTED true
#endif
#else
@ -98,4 +93,5 @@ extern CardReader card;
#define IS_SD_PRINTING (false)
#endif //SDSUPPORT
#endif
#endif //__CARDREADER_H

@ -1,59 +1,58 @@
#include "Configuration.h"
#ifdef DIGIPOT_I2C
#include "Stream.h"
#include "utility/twi.h"
#include "Wire.h"
// Settings for the I2C based DIGIPOT (MCP4451) on Azteeg X3 Pro
#if MB(5DPRINT)
#define DIGIPOT_I2C_FACTOR 117.96
#define DIGIPOT_I2C_MAX_CURRENT 1.736
#define DIGIPOT_I2C_FACTOR 117.96
#define DIGIPOT_I2C_MAX_CURRENT 1.736
#else
#define DIGIPOT_I2C_FACTOR 106.7
#define DIGIPOT_I2C_MAX_CURRENT 2.5
#define DIGIPOT_I2C_FACTOR 106.7
#define DIGIPOT_I2C_MAX_CURRENT 2.5
#endif
static byte current_to_wiper( float current ){
return byte(ceil(float((DIGIPOT_I2C_FACTOR*current))));
static byte current_to_wiper(float current) {
return byte(ceil(float((DIGIPOT_I2C_FACTOR*current))));
}
static void i2c_send(byte addr, byte a, byte b)
{
Wire.beginTransmission(addr);
Wire.write(a);
Wire.write(b);
Wire.endTransmission();
static void i2c_send(byte addr, byte a, byte b) {
Wire.beginTransmission(addr);
Wire.write(a);
Wire.write(b);
Wire.endTransmission();
}
// This is for the MCP4451 I2C based digipot
void digipot_i2c_set_current( int channel, float current )
{
current = min( (float) max( current, 0.0f ), DIGIPOT_I2C_MAX_CURRENT);
// these addresses are specific to Azteeg X3 Pro, can be set to others,
// In this case first digipot is at address A0=0, A1= 0, second one is at A0=0, A1= 1
byte addr= 0x2C; // channel 0-3
if(channel >= 4) {
addr= 0x2E; // channel 4-7
channel-= 4;
}
// Initial setup
i2c_send( addr, 0x40, 0xff );
i2c_send( addr, 0xA0, 0xff );
// Set actual wiper value
byte addresses[4] = { 0x00, 0x10, 0x60, 0x70 };
i2c_send( addr, addresses[channel], current_to_wiper(current) );
void digipot_i2c_set_current(int channel, float current) {
current = min( (float) max( current, 0.0f ), DIGIPOT_I2C_MAX_CURRENT);
// these addresses are specific to Azteeg X3 Pro, can be set to others,
// In this case first digipot is at address A0=0, A1= 0, second one is at A0=0, A1= 1
byte addr = 0x2C; // channel 0-3
if (channel >= 4) {
addr = 0x2E; // channel 4-7
channel -= 4;
}
// Initial setup
i2c_send(addr, 0x40, 0xff);
i2c_send(addr, 0xA0, 0xff);
// Set actual wiper value
byte addresses[4] = { 0x00, 0x10, 0x60, 0x70 };
i2c_send(addr, addresses[channel], current_to_wiper(current));
}
void digipot_i2c_init()
{
const float digipot_motor_current[] = DIGIPOT_I2C_MOTOR_CURRENTS;
Wire.begin();
// setup initial currents as defined in Configuration_adv.h
for(int i=0;i<=sizeof(digipot_motor_current)/sizeof(float);i++) {
digipot_i2c_set_current(i, digipot_motor_current[i]);
}
void digipot_i2c_init() {
const float digipot_motor_current[] = DIGIPOT_I2C_MOTOR_CURRENTS;
Wire.begin();
// setup initial currents as defined in Configuration_adv.h
for(int i = 0; i <= sizeof(digipot_motor_current) / sizeof(float); i++) {
digipot_i2c_set_current(i, digipot_motor_current[i]);
}
}
#endif
#endif //DIGIPOT_I2C

@ -587,6 +587,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
@ -645,6 +649,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#if defined (PANEL_ONE)
#define SDSUPPORT
#define ULTIMAKERCONTROLLER
#endif
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
#define DOGLCD

@ -597,6 +597,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
@ -655,6 +659,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#if defined (PANEL_ONE)
#define SDSUPPORT
#define ULTIMAKERCONTROLLER
#endif
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
#define DOGLCD

@ -590,6 +590,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
@ -648,6 +652,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#if defined (PANEL_ONE)
#define SDSUPPORT
#define ULTIMAKERCONTROLLER
#endif
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
#define DOGLCD

@ -591,6 +591,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
@ -649,6 +653,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#if defined (PANEL_ONE)
#define SDSUPPORT
#define ULTIMAKERCONTROLLER
#endif
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
#define DOGLCD

@ -495,6 +495,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
@ -560,6 +564,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#if defined (PANEL_ONE)
#define SDSUPPORT
#define ULTIMAKERCONTROLLER
#endif
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
#define DOGLCD

@ -565,6 +565,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
@ -623,6 +627,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#if defined (PANEL_ONE)
#define SDSUPPORT
#define ULTIMAKERCONTROLLER
#endif
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
#define DOGLCD

@ -578,6 +578,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
@ -636,6 +640,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#if defined (PANEL_ONE)
#define SDSUPPORT
#define ULTIMAKERCONTROLLER
#endif
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
#define DOGLCD

@ -159,6 +159,43 @@
#define MSG_ERR_EEPROM_WRITE "Error writing to EEPROM!"
// temperature.cpp strings
#define MSG_PID_AUTOTUNE "PID Autotune"
#define MSG_PID_AUTOTUNE_START MSG_PID_AUTOTUNE " start"
#define MSG_PID_AUTOTUNE_FAILED MSG_PID_AUTOTUNE " failed!"
#define MSG_PID_BAD_EXTRUDER_NUM MSG_PID_AUTOTUNE_FAILED " Bad extruder number"
#define MSG_PID_TEMP_TOO_HIGH MSG_PID_AUTOTUNE_FAILED " Temperature too high"
#define MSG_PID_TIMEOUT MSG_PID_AUTOTUNE_FAILED " timeout"
#define MSG_BIAS " bias: "
#define MSG_D " d: "
#define MSG_MIN " min: "
#define MSG_MAX " max: "
#define MSG_KU " Ku: "
#define MSG_TU " Tu: "
#define MSG_CLASSIC_PID " Classic PID "
#define MSG_KP " Kp: "
#define MSG_KI " Ki: "
#define MSG_KD " Kd: "
#define MSG_OK_B "ok B:"
#define MSG_OK_T "ok T:"
#define MSG_AT " @:"
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from above into Configuration.h"
#define MSG_PID_DEBUG " PID_DEBUG "
#define MSG_PID_DEBUG_INPUT ": Input "
#define MSG_PID_DEBUG_OUTPUT " Output "
#define MSG_PID_DEBUG_PTERM " pTerm "
#define MSG_PID_DEBUG_ITERM " iTerm "
#define MSG_PID_DEBUG_DTERM " dTerm "
#define MSG_HEATING_FAILED "Heating failed"
#define MSG_EXTRUDER_SWITCHED_OFF "Extruder switched off. Temperature difference between temp sensors is too high !"
#define MSG_INVALID_EXTRUDER_NUM " - Invalid extruder number !"
#define MSG_THERMAL_RUNAWAY_STOP "Thermal Runaway, system stopped! Heater_ID: "
#define MSG_SWITCHED_OFF_MAX " switched off. MAXTEMP triggered !!"
#define MSG_MINTEMP_EXTRUDER_OFF ": Extruder switched off. MINTEMP triggered !"
#define MSG_MAXTEMP_EXTRUDER_OFF ": Extruder" MSG_SWITCHED_OFF_MAX
#define MSG_MAXTEMP_BED_OFF "Heated bed" MSG_SWITCHED_OFF_MAX
// LCD Menu Messages
// Add your own character. Reference: https://github.com/MarlinFirmware/Marlin/pull/1434 photos

@ -65,6 +65,18 @@
#ifndef MSG_PREHEAT_ABS_SETTINGS
#define MSG_PREHEAT_ABS_SETTINGS MSG_PREHEAT_ABS " conf"
#endif
#ifndef MSG_H1
#define MSG_H1 "1"
#endif
#ifndef MSG_H2
#define MSG_H2 "2"
#endif
#ifndef MSG_H3
#define MSG_H3 "3"
#endif
#ifndef MSG_H4
#define MSG_H4 "4"
#endif
#ifndef MSG_COOLDOWN
#define MSG_COOLDOWN "Cooldown"
#endif
@ -110,6 +122,15 @@
#ifndef MSG_NOZZLE
#define MSG_NOZZLE "Nozzle"
#endif
#ifndef MSG_N2
#define MSG_N2 " 2"
#endif
#ifndef MSG_N3
#define MSG_N3 " 3"
#endif
#ifndef MSG_N4
#define MSG_N4 " 4"
#endif
#ifndef MSG_BED
#define MSG_BED "Bed"
#endif
@ -119,6 +140,18 @@
#ifndef MSG_FLOW
#define MSG_FLOW "Flow"
#endif
#ifndef MSG_F0
#define MSG_F0 " 0"
#endif
#ifndef MSG_F1
#define MSG_F1 " 1"
#endif
#ifndef MSG_F2
#define MSG_F2 " 2"
#endif
#ifndef MSG_F3
#define MSG_F3 " 3"
#endif
#ifndef MSG_CONTROL
#define MSG_CONTROL "Control"
#endif
@ -152,6 +185,15 @@
#ifndef MSG_PID_C
#define MSG_PID_C "PID-C"
#endif
#ifndef MSG_E2
#define MSG_E2 " E2"
#endif
#ifndef MSG_E3
#define MSG_E3 " E3"
#endif
#ifndef MSG_E4
#define MSG_E4 " E4"
#endif
#ifndef MSG_ACC
#define MSG_ACC "Accel"
#endif
@ -213,7 +255,7 @@
#define MSG_VOLUMETRIC "Filament"
#endif
#ifndef MSG_VOLUMETRIC_ENABLED
#define MSG_VOLUMETRIC_ENABLED "E in mm" STR_h3
#define MSG_VOLUMETRIC_ENABLED "E in mm" STR_h3
#endif
#ifndef MSG_FILAMENT_SIZE_EXTRUDER_0
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Fil. Dia. 1"
@ -341,23 +383,41 @@
#ifndef MSG_ENDSTOP_ABORT
#define MSG_ENDSTOP_ABORT "Endstop abort"
#endif
#ifndef MSG_HEATING_FAILED_LCD
#define MSG_HEATING_FAILED_LCD "Heating failed"
#endif
#ifndef MSG_ERR_REDUNDANT_TEMP
#define MSG_ERR_REDUNDANT_TEMP "Err: REDUNDANT TEMP ERROR"
#endif
#ifndef MSG_THERMAL_RUNAWAY
#define MSG_THERMAL_RUNAWAY "THERMAL RUNAWAY"
#endif
#ifndef MSG_ERR_MAXTEMP
#define MSG_ERR_MAXTEMP "Err: MAXTEMP"
#endif
#ifndef MSG_ERR_MINTEMP
#define MSG_ERR_MINTEMP "Err: MINTEMP"
#endif
#ifndef MSG_ERR_MAXTEMP_BED
#define MSG_ERR_MAXTEMP_BED "Err: MAXTEMP BED"
#endif
#ifdef DELTA_CALIBRATION_MENU
#ifndef MSG_DELTA_CALIBRATE
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#endif
#ifndef MSG_DELTA_CALIBRATE_X
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#endif
#ifndef MSG_DELTA_CALIBRATE_Y
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#endif
#ifndef MSG_DELTA_CALIBRATE_Z
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#endif
#ifndef MSG_DELTA_CALIBRATE_CENTER
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif
#ifndef MSG_DELTA_CALIBRATE
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#endif
#ifndef MSG_DELTA_CALIBRATE_X
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#endif
#ifndef MSG_DELTA_CALIBRATE_Y
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#endif
#ifndef MSG_DELTA_CALIBRATE_Z
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#endif
#ifndef MSG_DELTA_CALIBRATE_CENTER
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_EN_H

@ -122,12 +122,22 @@
#ifdef ULTRA_LCD
#ifdef NEWPANEL
#define LCD_PINS_RS 16
#define LCD_PINS_ENABLE 17
#define LCD_PINS_D4 23
#define LCD_PINS_D5 25
#define LCD_PINS_D6 27
#define LCD_PINS_D7 29
#ifdef PANEL_ONE
#define LCD_PINS_RS 40
#define LCD_PINS_ENABLE 42
#define LCD_PINS_D4 65
#define LCD_PINS_D5 66
#define LCD_PINS_D6 44
#define LCD_PINS_D7 64
#else
#define LCD_PINS_RS 16
#define LCD_PINS_ENABLE 17
#define LCD_PINS_D4 23
#define LCD_PINS_D5 25
#define LCD_PINS_D6 27
#define LCD_PINS_D7 29
#endif
#ifdef REPRAP_DISCOUNT_SMART_CONTROLLER
#define BEEPER 37
@ -162,6 +172,10 @@
#define SHIFT_OUT 40 // shift register
#define SHIFT_CLK 44 // shift register
#define SHIFT_LD 42 // shift register
#elif defined(PANEL_ONE)
#define BTN_EN1 59 // AUX2 PIN 3
#define BTN_EN2 63 // AUX2 PIN 4
#define BTN_ENC 49 // AUX3 PIN 7
#else
#define BTN_EN1 37
#define BTN_EN2 35

@ -6,6 +6,10 @@
#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
#endif
#if EXTRUDERS > 3
#error RUMBA supports up to 3 extruders. Comment this line to keep going.
#endif
#define X_STEP_PIN 17
#define X_DIR_PIN 16
#define X_ENABLE_PIN 48

@ -399,89 +399,84 @@ ISR(TIMER1_COMPA_vect)
count_direction[Y_AXIS]=1;
}
// Set direction en check limit switches
#ifndef COREXY
if ((out_bits & (1<<X_AXIS)) != 0) // stepping along -X axis
#else
if ((out_bits & (1<<X_HEAD)) != 0) //AlexBorro: Head direction in -X axis for CoreXY bots.
#endif
if(check_endstops) // check X and Y Endstops
{
CHECK_ENDSTOPS
{
#ifdef DUAL_X_CARRIAGE
// with 2 x-carriages, endstops are only checked in the homing direction for the active extruder
if ((current_block->active_extruder == 0 && X_HOME_DIR == -1)
|| (current_block->active_extruder != 0 && X2_HOME_DIR == -1))
#ifndef COREXY
if ((out_bits & (1<<X_AXIS)) != 0) // stepping along -X axis (regular cartesians bot)
#else
if (!((current_block->steps_x == current_block->steps_y) && ((out_bits & (1<<X_AXIS))>>X_AXIS != (out_bits & (1<<Y_AXIS))>>Y_AXIS))) // AlexBorro: If DeltaX == -DeltaY, the movement is only in Y axis
if ((out_bits & (1<<X_HEAD)) != 0) //AlexBorro: Head direction in -X axis for CoreXY bots.
#endif
{
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
bool x_min_endstop=(READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true;
step_events_completed = current_block->step_event_count;
{ // -direction
#ifdef DUAL_X_CARRIAGE
// with 2 x-carriages, endstops are only checked in the homing direction for the active extruder
if ((current_block->active_extruder == 0 && X_HOME_DIR == -1) || (current_block->active_extruder != 0 && X2_HOME_DIR == -1))
#endif
{
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
bool x_min_endstop=(READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0))
{
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true;
step_events_completed = current_block->step_event_count;
}
old_x_min_endstop = x_min_endstop;
#endif
}
old_x_min_endstop = x_min_endstop;
#endif
}
}
}
else
{ // +direction
CHECK_ENDSTOPS
{
#ifdef DUAL_X_CARRIAGE
// with 2 x-carriages, endstops are only checked in the homing direction for the active extruder
if ((current_block->active_extruder == 0 && X_HOME_DIR == 1)
|| (current_block->active_extruder != 0 && X2_HOME_DIR == 1))
#endif
{
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
bool x_max_endstop=(READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true;
step_events_completed = current_block->step_event_count;
else
{ // +direction
#ifdef DUAL_X_CARRIAGE
// with 2 x-carriages, endstops are only checked in the homing direction for the active extruder
if ((current_block->active_extruder == 0 && X_HOME_DIR == 1) || (current_block->active_extruder != 0 && X2_HOME_DIR == 1))
#endif
{
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
bool x_max_endstop=(READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0))
{
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true;
step_events_completed = current_block->step_event_count;
}
old_x_max_endstop = x_max_endstop;
#endif
}
old_x_max_endstop = x_max_endstop;
#endif
}
}
}
#ifndef COREXY
if ((out_bits & (1<<Y_AXIS)) != 0) // -direction
#else
if ((out_bits & (1<<Y_HEAD)) != 0) //AlexBorro: Head direction in -Y axis for CoreXY bots.
#endif
{
CHECK_ENDSTOPS
{
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
bool y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true;
step_events_completed = current_block->step_event_count;
}
old_y_min_endstop = y_min_endstop;
#endif
}
}
else
{ // +direction
CHECK_ENDSTOPS
{
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
bool y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true;
step_events_completed = current_block->step_event_count;
}
old_y_max_endstop = y_max_endstop;
#ifndef COREXY
if ((out_bits & (1<<Y_AXIS)) != 0) // -direction
#else
if (!((current_block->steps_x == current_block->steps_y) && ((out_bits & (1<<X_AXIS))>>X_AXIS == (out_bits & (1<<Y_AXIS))>>Y_AXIS))) // AlexBorro: If DeltaX == DeltaY, the movement is only in X axis
if ((out_bits & (1<<Y_HEAD)) != 0) //AlexBorro: Head direction in -Y axis for CoreXY bots.
#endif
}
{ // -direction
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
bool y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0))
{
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true;
step_events_completed = current_block->step_event_count;
}
old_y_min_endstop = y_min_endstop;
#endif
}
else
{ // +direction
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
bool y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0))
{
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true;
step_events_completed = current_block->step_event_count;
}
old_y_max_endstop = y_max_endstop;
#endif
}
}
if ((out_bits & (1<<Z_AXIS)) != 0) { // -direction

File diff suppressed because it is too large Load Diff

@ -85,55 +85,25 @@ extern float current_temperature_bed;
//inline so that there is no performance decrease.
//deg=degreeCelsius
FORCE_INLINE float degHotend(uint8_t extruder) {
return current_temperature[extruder];
};
FORCE_INLINE float degHotend(uint8_t extruder) { return current_temperature[extruder]; }
FORCE_INLINE float degBed() { return current_temperature_bed; }
#ifdef SHOW_TEMP_ADC_VALUES
FORCE_INLINE float rawHotendTemp(uint8_t extruder) {
return current_temperature_raw[extruder];
};
FORCE_INLINE float rawBedTemp() {
return current_temperature_bed_raw;
};
FORCE_INLINE float rawHotendTemp(uint8_t extruder) { return current_temperature_raw[extruder]; }
FORCE_INLINE float rawBedTemp() { return current_temperature_bed_raw; }
#endif
FORCE_INLINE float degBed() {
return current_temperature_bed;
};
FORCE_INLINE float degTargetHotend(uint8_t extruder) {
return target_temperature[extruder];
};
FORCE_INLINE float degTargetBed() {
return target_temperature_bed;
};
FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) {
target_temperature[extruder] = celsius;
};
FORCE_INLINE void setTargetBed(const float &celsius) {
target_temperature_bed = celsius;
};
FORCE_INLINE float degTargetHotend(uint8_t extruder) { return target_temperature[extruder]; }
FORCE_INLINE float degTargetBed() { return target_temperature_bed; }
FORCE_INLINE bool isHeatingHotend(uint8_t extruder){
return target_temperature[extruder] > current_temperature[extruder];
};
FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) { target_temperature[extruder] = celsius; }
FORCE_INLINE void setTargetBed(const float &celsius) { target_temperature_bed = celsius; }
FORCE_INLINE bool isHeatingBed() {
return target_temperature_bed > current_temperature_bed;
};
FORCE_INLINE bool isHeatingHotend(uint8_t extruder) { return target_temperature[extruder] > current_temperature[extruder]; }
FORCE_INLINE bool isHeatingBed() { return target_temperature_bed > current_temperature_bed; }
FORCE_INLINE bool isCoolingHotend(uint8_t extruder) {
return target_temperature[extruder] < current_temperature[extruder];
};
FORCE_INLINE bool isCoolingBed() {
return target_temperature_bed < current_temperature_bed;
};
FORCE_INLINE bool isCoolingHotend(uint8_t extruder) { return target_temperature[extruder] < current_temperature[extruder]; }
FORCE_INLINE bool isCoolingBed() { return target_temperature_bed < current_temperature_bed; }
#define degHotend0() degHotend(0)
#define degTargetHotend0() degTargetHotend(0)
@ -141,38 +111,36 @@ FORCE_INLINE bool isCoolingBed() {
#define isHeatingHotend0() isHeatingHotend(0)
#define isCoolingHotend0() isCoolingHotend(0)
#if EXTRUDERS > 1
#define degHotend1() degHotend(1)
#define degTargetHotend1() degTargetHotend(1)
#define setTargetHotend1(_celsius) setTargetHotend((_celsius), 1)
#define isHeatingHotend1() isHeatingHotend(1)
#define isCoolingHotend1() isCoolingHotend(1)
#define degHotend1() degHotend(1)
#define degTargetHotend1() degTargetHotend(1)
#define setTargetHotend1(_celsius) setTargetHotend((_celsius), 1)
#define isHeatingHotend1() isHeatingHotend(1)
#define isCoolingHotend1() isCoolingHotend(1)
#else
#define setTargetHotend1(_celsius) do{}while(0)
#define setTargetHotend1(_celsius) do{}while(0)
#endif
#if EXTRUDERS > 2
#define degHotend2() degHotend(2)
#define degTargetHotend2() degTargetHotend(2)
#define setTargetHotend2(_celsius) setTargetHotend((_celsius), 2)
#define isHeatingHotend2() isHeatingHotend(2)
#define isCoolingHotend2() isCoolingHotend(2)
#define degHotend2() degHotend(2)
#define degTargetHotend2() degTargetHotend(2)
#define setTargetHotend2(_celsius) setTargetHotend((_celsius), 2)
#define isHeatingHotend2() isHeatingHotend(2)
#define isCoolingHotend2() isCoolingHotend(2)
#else
#define setTargetHotend2(_celsius) do{}while(0)
#define setTargetHotend2(_celsius) do{}while(0)
#endif
#if EXTRUDERS > 3
#define degHotend3() degHotend(3)
#define degTargetHotend3() degTargetHotend(3)
#define setTargetHotend3(_celsius) setTargetHotend((_celsius), 3)
#define isHeatingHotend3() isHeatingHotend(3)
#define isCoolingHotend3() isCoolingHotend(3)
#define degHotend3() degHotend(3)
#define degTargetHotend3() degTargetHotend(3)
#define setTargetHotend3(_celsius) setTargetHotend((_celsius), 3)
#define isHeatingHotend3() isHeatingHotend(3)
#define isCoolingHotend3() isCoolingHotend(3)
#else
#define setTargetHotend3(_celsius) do{}while(0)
#define setTargetHotend3(_celsius) do{}while(0)
#endif
#if EXTRUDERS > 4
#error Invalid number of extruders
#error Invalid number of extruders
#endif
int getHeaterPower(int heater);
void disable_heater();
void setWatch();
@ -189,15 +157,14 @@ static bool thermal_runaway = false;
#endif
#endif
FORCE_INLINE void autotempShutdown(){
#ifdef AUTOTEMP
if(autotemp_enabled)
{
autotemp_enabled=false;
if(degTargetHotend(active_extruder)>autotemp_min)
setTargetHotend(0,active_extruder);
}
#endif
FORCE_INLINE void autotempShutdown() {
#ifdef AUTOTEMP
if (autotemp_enabled) {
autotemp_enabled = false;
if (degTargetHotend(active_extruder) > autotemp_min)
setTargetHotend(0, active_extruder);
}
#endif
}
void PID_autotune(float temp, int extruder, int ncycles);

@ -1096,13 +1096,26 @@ const short temptable_1047[][2] PROGMEM = {
#endif
#if (THERMISTORHEATER_0 == 999) || (THERMISTORHEATER_1 == 999) || (THERMISTORHEATER_2 == 999) || (THERMISTORHEATER_3 == 999) || (THERMISTORBED == 999) //User defined table
// Dummy Thermistor table.. It will ALWAYS read 25C.
const short temptable_999[][2] PROGMEM = {
{1*OVERSAMPLENR, 25},
{1023*OVERSAMPLENR, 25}
// Dummy Thermistor table.. It will ALWAYS read a fixed value.
#ifndef DUMMY_THERMISTOR_999_VALUE
#define DUMMY_THERMISTOR_999_VALUE 25
#endif
const short temptable_999[][2] PROGMEM = {
{1*OVERSAMPLENR, DUMMY_THERMISTOR_999_VALUE},
{1023*OVERSAMPLENR, DUMMY_THERMISTOR_999_VALUE}
};
#endif
#if (THERMISTORHEATER_0 == 998) || (THERMISTORHEATER_1 == 998) || (THERMISTORHEATER_2 == 998) || (THERMISTORHEATER_3 == 998) || (THERMISTORBED == 998) //User defined table
// Dummy Thermistor table.. It will ALWAYS read a fixed value.
#ifndef DUMMY_THERMISTOR_998_VALUE
#define DUMMY_THERMISTOR_998_VALUE 25
#endif
const short temptable_998[][2] PROGMEM = {
{1*OVERSAMPLENR, DUMMY_THERMISTOR_998_VALUE},
{1023*OVERSAMPLENR, DUMMY_THERMISTOR_998_VALUE}
};
#endif
#define _TT_NAME(_N) temptable_ ## _N

@ -262,15 +262,15 @@ static void lcd_status_screen()
#endif
#endif //LCD_PROGRESS_BAR
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 */
}
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
@ -346,86 +346,82 @@ 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)
{
enquecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
}
autotempShutdown();
static void lcd_sdcard_stop() {
card.sdprinting = false;
card.closefile();
quickStop();
if (SD_FINISHED_STEPPERRELEASE) {
enquecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
}
autotempShutdown();
cancel_heatup = true;
cancel_heatup = true;
lcd_setstatus(MSG_PRINT_ABORTED);
lcd_setstatus(MSG_PRINT_ABORTED);
}
/* Menu implementation */
static void lcd_main_menu()
{
START_MENU();
MENU_ITEM(back, MSG_WATCH, lcd_status_screen);
if (movesplanned() || IS_SD_PRINTING)
{
MENU_ITEM(submenu, MSG_TUNE, lcd_tune_menu);
}else{
MENU_ITEM(submenu, MSG_PREPARE, lcd_prepare_menu);
#ifdef DELTA_CALIBRATION_MENU
MENU_ITEM(submenu, MSG_DELTA_CALIBRATE, lcd_delta_calibrate_menu);
#endif // DELTA_CALIBRATION_MENU
static void lcd_main_menu() {
START_MENU();
MENU_ITEM(back, MSG_WATCH, lcd_status_screen);
if (movesplanned() || IS_SD_PRINTING) {
MENU_ITEM(submenu, MSG_TUNE, lcd_tune_menu);
}
else {
MENU_ITEM(submenu, MSG_PREPARE, lcd_prepare_menu);
#ifdef DELTA_CALIBRATION_MENU
MENU_ITEM(submenu, MSG_DELTA_CALIBRATE, lcd_delta_calibrate_menu);
#endif
}
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);
#if SDCARDDETECT < 1
MENU_ITEM(gcode, MSG_CNG_SDCARD, PSTR("M21")); // SD-card changed by user
#endif
}
}
/*JFR TEST*/ MENU_ITEM(gcode, "test multiline", PSTR("G4 S3\nM104 S50\nG4 S1\nM104 S200\nG4 S2\nM104 S0")); // SD-card changed by user
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);
#if SDCARDDETECT < 1
MENU_ITEM(gcode, MSG_CNG_SDCARD, PSTR("M21")); // SD-card changed by user
#endif
}
}else{
MENU_ITEM(submenu, MSG_NO_CARD, lcd_sdcard_menu);
#if SDCARDDETECT < 1
else {
MENU_ITEM(submenu, MSG_NO_CARD, lcd_sdcard_menu);
#if SDCARDDETECT < 1
MENU_ITEM(gcode, MSG_INIT_SDCARD, PSTR("M21")); // Manually initialize the SD-card via user interface
#endif
#endif
}
#endif
END_MENU();
#endif //SDSUPPORT
END_MENU();
}
#ifdef SDSUPPORT
static void lcd_autostart_sd()
{
card.autostart_index=0;
static void lcd_autostart_sd() {
card.autostart_index = 0;
card.setroot();
card.checkautostart(true);
}
}
#endif
void lcd_set_home_offsets()
{
for(int8_t i=0; i < NUM_AXIS; i++) {
if (i != E_AXIS) {
add_homing[i] -= current_position[i];
current_position[i] = 0.0;
}
void lcd_set_home_offsets() {
for(int8_t i=0; i < NUM_AXIS; i++) {
if (i != E_AXIS) {
add_homing[i] -= current_position[i];
current_position[i] = 0.0;
}
plan_set_position(0.0, 0.0, 0.0, current_position[E_AXIS]);
}
plan_set_position(0.0, 0.0, 0.0, current_position[E_AXIS]);
// Audio feedback
enquecommands_P(PSTR("M300 S659 P200\nM300 S698 P200"));
lcd_return_to_status();
// Audio feedback
enquecommands_P(PSTR("M300 S659 P200\nM300 S698 P200"));
lcd_return_to_status();
}
@ -446,274 +442,181 @@ void lcd_set_home_offsets()
#endif //BABYSTEPPING
static void lcd_tune_menu()
{
START_MENU();
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
MENU_ITEM_EDIT(int3, MSG_SPEED, &feedmultiply, 10, 999);
#if TEMP_SENSOR_0 != 0
static void lcd_tune_menu() {
START_MENU();
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
MENU_ITEM_EDIT(int3, MSG_SPEED, &feedmultiply, 10, 999);
#if TEMP_SENSOR_0 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_1 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE " 2", &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_2 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE " 3", &target_temperature[2], 0, HEATER_2_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_3 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE " 4", &target_temperature[3], 0, HEATER_3_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0
#endif
#if TEMP_SENSOR_1 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE MSG_N2, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_2 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE MSG_N3, &target_temperature[2], 0, HEATER_2_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_3 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE MSG_N4, &target_temperature[3], 0, HEATER_3_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15);
#endif
#endif
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
MENU_ITEM_EDIT(int3, MSG_FLOW, &extrudemultiply, 10, 999);
MENU_ITEM_EDIT(int3, MSG_FLOW " 0", &extruder_multiply[0], 10, 999);
#if TEMP_SENSOR_1 != 0
MENU_ITEM_EDIT(int3, MSG_FLOW " 1", &extruder_multiply[1], 10, 999);
#endif
#if TEMP_SENSOR_2 != 0
MENU_ITEM_EDIT(int3, MSG_FLOW " 2", &extruder_multiply[2], 10, 999);
#endif
#if TEMP_SENSOR_3 != 0
MENU_ITEM_EDIT(int3, MSG_FLOW " 3", &extruder_multiply[3], 10, 999);
#endif
MENU_ITEM_EDIT(int3, MSG_FLOW MSG_F0, &extruder_multiply[0], 10, 999);
#if TEMP_SENSOR_1 != 0
MENU_ITEM_EDIT(int3, MSG_FLOW MSG_F1, &extruder_multiply[1], 10, 999);
#endif
#if TEMP_SENSOR_2 != 0
MENU_ITEM_EDIT(int3, MSG_FLOW MSG_F2, &extruder_multiply[2], 10, 999);
#endif
#if TEMP_SENSOR_3 != 0
MENU_ITEM_EDIT(int3, MSG_FLOW MSG_F3, &extruder_multiply[3], 10, 999);
#endif
#ifdef BABYSTEPPING
#ifdef BABYSTEPPING
#ifdef BABYSTEP_XY
MENU_ITEM(submenu, MSG_BABYSTEP_X, lcd_babystep_x);
MENU_ITEM(submenu, MSG_BABYSTEP_Y, lcd_babystep_y);
#endif //BABYSTEP_XY
MENU_ITEM(submenu, MSG_BABYSTEP_Z, lcd_babystep_z);
#endif
#ifdef FILAMENTCHANGEENABLE
#endif
#ifdef FILAMENTCHANGEENABLE
MENU_ITEM(gcode, MSG_FILAMENTCHANGE, PSTR("M600"));
#endif
END_MENU();
}
void lcd_preheat_pla0()
{
setTargetHotend0(plaPreheatHotendTemp);
setTargetBed(plaPreheatHPBTemp);
fanSpeed = plaPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
#endif
END_MENU();
}
void lcd_preheat_abs0()
{
setTargetHotend0(absPreheatHotendTemp);
setTargetBed(absPreheatHPBTemp);
fanSpeed = absPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
void _lcd_preheat(int endnum, const float temph, const float tempb, const int fan) {
if (temph > 0) setTargetHotend(temph, endnum);
setTargetBed(tempb);
fanSpeed = fan;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_pla0() { _lcd_preheat(0, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs0() { _lcd_preheat(0, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
#if TEMP_SENSOR_1 != 0 //2nd extruder preheat
void lcd_preheat_pla1()
{
setTargetHotend1(plaPreheatHotendTemp);
setTargetBed(plaPreheatHPBTemp);
fanSpeed = plaPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_abs1()
{
setTargetHotend1(absPreheatHotendTemp);
setTargetBed(absPreheatHPBTemp);
fanSpeed = absPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_pla1() { _lcd_preheat(1, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs1() { _lcd_preheat(1, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
#endif //2nd extruder preheat
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
void lcd_preheat_pla2()
{
setTargetHotend2(plaPreheatHotendTemp);
setTargetBed(plaPreheatHPBTemp);
fanSpeed = plaPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_abs2()
{
setTargetHotend2(absPreheatHotendTemp);
setTargetBed(absPreheatHPBTemp);
fanSpeed = absPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_pla2() { _lcd_preheat(2, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs2() { _lcd_preheat(2, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
#endif //3 extruder preheat
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
void lcd_preheat_pla3()
{
setTargetHotend3(plaPreheatHotendTemp);
setTargetBed(plaPreheatHPBTemp);
fanSpeed = plaPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_abs3()
{
setTargetHotend3(absPreheatHotendTemp);
setTargetBed(absPreheatHPBTemp);
fanSpeed = absPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_pla3() { _lcd_preheat(3, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs3() { _lcd_preheat(3, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
#endif //4 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //more than one extruder present
void lcd_preheat_pla0123()
{
void lcd_preheat_pla0123() {
setTargetHotend0(plaPreheatHotendTemp);
setTargetHotend1(plaPreheatHotendTemp);
setTargetHotend2(plaPreheatHotendTemp);
setTargetHotend3(plaPreheatHotendTemp);
setTargetBed(plaPreheatHPBTemp);
fanSpeed = plaPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_abs0123()
{
_lcd_preheat(3, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed);
}
void lcd_preheat_abs0123() {
setTargetHotend0(absPreheatHotendTemp);
setTargetHotend1(absPreheatHotendTemp);
setTargetHotend2(absPreheatHotendTemp);
setTargetHotend3(absPreheatHotendTemp);
setTargetBed(absPreheatHPBTemp);
fanSpeed = absPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
_lcd_preheat(3, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed);
}
#endif //more than one extruder present
void lcd_preheat_pla_bedonly()
{
setTargetBed(plaPreheatHPBTemp);
fanSpeed = plaPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_abs_bedonly()
{
setTargetBed(absPreheatHPBTemp);
fanSpeed = absPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_pla_bedonly() { _lcd_preheat(0, 0, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs_bedonly() { _lcd_preheat(0, 0, absPreheatHPBTemp, absPreheatFanSpeed); }
static void lcd_preheat_pla_menu()
{
static void lcd_preheat_pla_menu() {
START_MENU();
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
MENU_ITEM(function, MSG_PREHEAT_PLA_N "1", lcd_preheat_pla0);
#if TEMP_SENSOR_1 != 0 //2 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA_N "2", lcd_preheat_pla1);
#endif //2 extruder preheat
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA_N "3", lcd_preheat_pla2);
#endif //3 extruder preheat
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA_N "4", lcd_preheat_pla3);
#endif //4 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //all extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA_ALL, lcd_preheat_pla0123);
#endif //all extruder preheat
#if TEMP_SENSOR_BED != 0
MENU_ITEM(function, MSG_PREHEAT_PLA_BEDONLY, lcd_preheat_pla_bedonly);
#endif
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H1, lcd_preheat_pla0);
#if TEMP_SENSOR_1 != 0 //2 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H2, lcd_preheat_pla1);
#endif //2 extruder preheat
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H3, lcd_preheat_pla2);
#endif //3 extruder preheat
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA_N MSG_H4, lcd_preheat_pla3);
#endif //4 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //all extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA_ALL, lcd_preheat_pla0123);
#endif //all extruder preheat
#if TEMP_SENSOR_BED != 0
MENU_ITEM(function, MSG_PREHEAT_PLA_BEDONLY, lcd_preheat_pla_bedonly);
#endif
END_MENU();
}
static void lcd_preheat_abs_menu()
{
static void lcd_preheat_abs_menu() {
START_MENU();
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
MENU_ITEM(function, MSG_PREHEAT_ABS_N "1", lcd_preheat_abs0);
#if TEMP_SENSOR_1 != 0 //2 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS_N "2", lcd_preheat_abs1);
#endif //2 extruder preheat
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS_N "3", lcd_preheat_abs2);
#endif //3 extruder preheat
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS_N "4", lcd_preheat_abs3);
#endif //4 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //all extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS_ALL, lcd_preheat_abs0123);
#endif //all extruder preheat
#if TEMP_SENSOR_BED != 0
MENU_ITEM(function, MSG_PREHEAT_ABS_BEDONLY, lcd_preheat_abs_bedonly);
#endif
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H1, lcd_preheat_abs0);
#if TEMP_SENSOR_1 != 0 //2 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H2, lcd_preheat_abs1);
#endif //2 extruder preheat
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H3, lcd_preheat_abs2);
#endif //3 extruder preheat
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS_N MSG_H4, lcd_preheat_abs3);
#endif //4 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //all extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS_ALL, lcd_preheat_abs0123);
#endif //all extruder preheat
#if TEMP_SENSOR_BED != 0
MENU_ITEM(function, MSG_PREHEAT_ABS_BEDONLY, lcd_preheat_abs_bedonly);
#endif
END_MENU();
}
void lcd_cooldown()
{
setTargetHotend0(0);
setTargetHotend1(0);
setTargetHotend2(0);
setTargetHotend3(0);
setTargetBed(0);
fanSpeed = 0;
lcd_return_to_status();
void lcd_cooldown() {
setTargetHotend0(0);
setTargetHotend1(0);
setTargetHotend2(0);
setTargetHotend3(0);
setTargetBed(0);
fanSpeed = 0;
lcd_return_to_status();
}
static void lcd_prepare_menu()
{
START_MENU();
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
#ifdef SDSUPPORT
static void lcd_prepare_menu() {
START_MENU();
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
#ifdef SDSUPPORT
#ifdef MENU_ADDAUTOSTART
MENU_ITEM(function, MSG_AUTOSTART, lcd_autostart_sd);
#endif
#endif
MENU_ITEM(gcode, MSG_DISABLE_STEPPERS, PSTR("M84"));
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
MENU_ITEM(function, MSG_SET_HOME_OFFSETS, lcd_set_home_offsets);
//MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0"));
#if TEMP_SENSOR_0 != 0
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_BED != 0
MENU_ITEM(submenu, MSG_PREHEAT_PLA, lcd_preheat_pla_menu);
MENU_ITEM(submenu, MSG_PREHEAT_ABS, lcd_preheat_abs_menu);
#else
MENU_ITEM(function, MSG_PREHEAT_PLA, lcd_preheat_pla0);
MENU_ITEM(function, MSG_PREHEAT_ABS, lcd_preheat_abs0);
#endif
#endif
MENU_ITEM(function, MSG_COOLDOWN, lcd_cooldown);
#if PS_ON_PIN > -1
if (powersupply)
{
MENU_ITEM(gcode, MSG_SWITCH_PS_OFF, PSTR("M81"));
}else{
MENU_ITEM(gcode, MSG_SWITCH_PS_ON, PSTR("M80"));
MENU_ITEM(gcode, MSG_DISABLE_STEPPERS, PSTR("M84"));
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
MENU_ITEM(function, MSG_SET_HOME_OFFSETS, lcd_set_home_offsets);
//MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0"));
#if TEMP_SENSOR_0 != 0
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_BED != 0
MENU_ITEM(submenu, MSG_PREHEAT_PLA, lcd_preheat_pla_menu);
MENU_ITEM(submenu, MSG_PREHEAT_ABS, lcd_preheat_abs_menu);
#else
MENU_ITEM(function, MSG_PREHEAT_PLA, lcd_preheat_pla0);
MENU_ITEM(function, MSG_PREHEAT_ABS, lcd_preheat_abs0);
#endif
#endif
MENU_ITEM(function, MSG_COOLDOWN, lcd_cooldown);
#if defined(POWER_SUPPLY) && POWER_SUPPLY > 0 && defined(PS_ON_PIN) && PS_ON_PIN > -1
if (powersupply) {
MENU_ITEM(gcode, MSG_SWITCH_PS_OFF, PSTR("M81"));
}
#endif
MENU_ITEM(submenu, MSG_MOVE_AXIS, lcd_move_menu);
// JFR for RMud delta printer
MENU_ITEM(gcode, "Calibrate bed", PSTR("M702\nG28\nG1 X-77.94 Y-45 Z36 F8000\nG4 S3\nM701 P0\nG1 X77.94 Y-45 Z36\nG4 S3\nM701 P1\nG1 X0 Y90 Z36\nG4 S3\nM701 P2\nM700\nG1 X0 Y0 Z100 F8000"));
MENU_ITEM(gcode, "Check level", PSTR("G28\nG1 X0 Y0 Z1 F4000\nG1 X-77.94 Y-45 Z1\nG1 X77.94 Y-45\nG1 X0 Y90\nG1 X-77.94 Y-45\nG4 S2\nG1 X-77.94 Y-45 Z0.3 F2000\nG1 X-77.94 Y-45\nG1 X77.94 Y-45\nG1 X0 Y90\nG1 X-77.94 Y-45\nG1 X0 Y0 Z0"));
MENU_ITEM(gcode, "Retract filament", PSTR("M302\nM82\nG92 E0\nG1 F4000 E-800"));
MENU_ITEM(gcode, "Insert filament", PSTR("M302\nM82\nG92 E0\nG1 F4000 E60"));
MENU_ITEM(gcode, "Finalize filament", PSTR("G1 F4000 E790"));
END_MENU();
else {
MENU_ITEM(gcode, MSG_SWITCH_PS_ON, PSTR("M80"));
}
#endif
MENU_ITEM(submenu, MSG_MOVE_AXIS, lcd_move_menu);
END_MENU();
}
#ifdef DELTA_CALIBRATION_MENU
@ -755,89 +658,77 @@ static void lcd_move_x() { _lcd_move(PSTR("X"), X_AXIS, X_MIN_POS, X_MAX_POS); }
static void lcd_move_y() { _lcd_move(PSTR("Y"), Y_AXIS, Y_MIN_POS, Y_MAX_POS); }
static void lcd_move_z() { _lcd_move(PSTR("Z"), Z_AXIS, Z_MIN_POS, Z_MAX_POS); }
static void lcd_move_e()
{
if (encoderPosition != 0)
{
current_position[E_AXIS] += float((int)encoderPosition) * move_menu_scale;
encoderPosition = 0;
#ifdef DELTA
calculate_delta(current_position);
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS], manual_feedrate[E_AXIS]/60, active_extruder);
#else
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], manual_feedrate[E_AXIS]/60, active_extruder);
#endif
lcdDrawUpdate = 1;
}
if (lcdDrawUpdate)
{
lcd_implementation_drawedit(PSTR("Extruder"), ftostr31(current_position[E_AXIS]));
}
if (LCD_CLICKED) lcd_goto_menu(lcd_move_menu_axis);
static void lcd_move_e() {
if (encoderPosition != 0) {
current_position[E_AXIS] += float((int)encoderPosition) * move_menu_scale;
encoderPosition = 0;
#ifdef DELTA
calculate_delta(current_position);
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS], manual_feedrate[E_AXIS]/60, active_extruder);
#else
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], manual_feedrate[E_AXIS]/60, active_extruder);
#endif
lcdDrawUpdate = 1;
}
if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR("Extruder"), ftostr31(current_position[E_AXIS]));
if (LCD_CLICKED) lcd_goto_menu(lcd_move_menu_axis);
}
static void lcd_move_menu_axis()
{
START_MENU();
MENU_ITEM(back, MSG_MOVE_AXIS, lcd_move_menu);
MENU_ITEM(submenu, MSG_MOVE_X, lcd_move_x);
MENU_ITEM(submenu, MSG_MOVE_Y, lcd_move_y);
if (move_menu_scale < 10.0)
{
MENU_ITEM(submenu, MSG_MOVE_Z, lcd_move_z);
MENU_ITEM(submenu, MSG_MOVE_E, lcd_move_e);
}
END_MENU();
static void lcd_move_menu_axis() {
START_MENU();
MENU_ITEM(back, MSG_MOVE_AXIS, lcd_move_menu);
MENU_ITEM(submenu, MSG_MOVE_X, lcd_move_x);
MENU_ITEM(submenu, MSG_MOVE_Y, lcd_move_y);
if (move_menu_scale < 10.0) {
MENU_ITEM(submenu, MSG_MOVE_Z, lcd_move_z);
MENU_ITEM(submenu, MSG_MOVE_E, 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_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_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_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, MSG_MOVE_10MM, lcd_move_menu_10mm);
MENU_ITEM(submenu, MSG_MOVE_1MM, lcd_move_menu_1mm);
MENU_ITEM(submenu, MSG_MOVE_01MM, lcd_move_menu_01mm);
//TODO:X,Y,Z,E
END_MENU();
static void lcd_move_menu() {
START_MENU();
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
MENU_ITEM(submenu, MSG_MOVE_10MM, lcd_move_menu_10mm);
MENU_ITEM(submenu, MSG_MOVE_1MM, lcd_move_menu_1mm);
MENU_ITEM(submenu, MSG_MOVE_01MM, 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);
MENU_ITEM(submenu, MSG_VOLUMETRIC, lcd_control_volumetric_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);
MENU_ITEM(submenu, MSG_VOLUMETRIC, lcd_control_volumetric_menu);
#ifdef DOGLCD
// MENU_ITEM_EDIT(int3, MSG_CONTRAST, &lcd_contrast, 0, 63);
#ifdef DOGLCD
//MENU_ITEM_EDIT(int3, MSG_CONTRAST, &lcd_contrast, 0, 63);
MENU_ITEM(submenu, MSG_CONTRAST, lcd_set_contrast);
#endif
#ifdef FWRETRACT
#endif
#ifdef FWRETRACT
MENU_ITEM(submenu, MSG_RETRACT, lcd_control_retract_menu);
#endif
#ifdef EEPROM_SETTINGS
#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();
#endif
MENU_ITEM(function, MSG_RESTORE_FAILSAFE, Config_ResetDefault);
END_MENU();
}
#ifdef PIDTEMP
@ -871,8 +762,7 @@ static void lcd_control_menu()
#endif //PIDTEMP
static void lcd_control_temperature_menu()
{
static void lcd_control_temperature_menu() {
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
#if TEMP_SENSOR_0 != 0
@ -880,19 +770,19 @@ static void lcd_control_temperature_menu()
#endif
#if EXTRUDERS > 1
#if TEMP_SENSOR_1 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE " 2", &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE MSG_N2, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
#endif
#if EXTRUDERS > 2
#if TEMP_SENSOR_2 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE " 3", &target_temperature[2], 0, HEATER_2_MAXTEMP - 15);
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE MSG_N3, &target_temperature[2], 0, HEATER_2_MAXTEMP - 15);
#endif
#if EXTRUDERS > 3
#if TEMP_SENSOR_3 != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE " 4", &target_temperature[3], 0, HEATER_3_MAXTEMP - 15);
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_NOZZLE MSG_N4, &target_temperature[3], 0, HEATER_3_MAXTEMP - 15);
#endif
#endif
#endif
#endif
#endif // EXTRUDERS > 3
#endif // EXTRUDERS > 2
#endif // EXTRUDERS > 1
#if TEMP_SENSOR_BED != 0
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15);
#endif
@ -919,36 +809,36 @@ static void lcd_control_temperature_menu()
// set up temp variables - undo the default scaling
raw_Ki = unscalePID_i(PID_PARAM(Ki,1));
raw_Kd = unscalePID_d(PID_PARAM(Kd,1));
MENU_ITEM_EDIT(float52, MSG_PID_P " E2", &PID_PARAM(Kp,1), 1, 9990);
MENU_ITEM_EDIT(float52, MSG_PID_P MSG_E2, &PID_PARAM(Kp,1), 1, 9990);
// i is typically a small value so allows values below 1
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_I " E2", &raw_Ki, 0.01, 9990, copy_and_scalePID_i_E2);
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_D " E2", &raw_Kd, 1, 9990, copy_and_scalePID_d_E2);
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_I MSG_E2, &raw_Ki, 0.01, 9990, copy_and_scalePID_i_E2);
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_D MSG_E2, &raw_Kd, 1, 9990, copy_and_scalePID_d_E2);
#ifdef PID_ADD_EXTRUSION_RATE
MENU_ITEM_EDIT(float3, MSG_PID_C " E2", &PID_PARAM(Kc,1), 1, 9990);
MENU_ITEM_EDIT(float3, MSG_PID_C MSG_E2, &PID_PARAM(Kc,1), 1, 9990);
#endif//PID_ADD_EXTRUSION_RATE
#if EXTRUDERS > 2
// set up temp variables - undo the default scaling
raw_Ki = unscalePID_i(PID_PARAM(Ki,2));
raw_Kd = unscalePID_d(PID_PARAM(Kd,2));
MENU_ITEM_EDIT(float52, MSG_PID_P " E3", &PID_PARAM(Kp,2), 1, 9990);
MENU_ITEM_EDIT(float52, MSG_PID_P MSG_E3, &PID_PARAM(Kp,2), 1, 9990);
// i is typically a small value so allows values below 1
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_I " E3", &raw_Ki, 0.01, 9990, copy_and_scalePID_i_E3);
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_D " E3", &raw_Kd, 1, 9990, copy_and_scalePID_d_E3);
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_I MSG_E3, &raw_Ki, 0.01, 9990, copy_and_scalePID_i_E3);
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_D MSG_E3, &raw_Kd, 1, 9990, copy_and_scalePID_d_E3);
#ifdef PID_ADD_EXTRUSION_RATE
MENU_ITEM_EDIT(float3, MSG_PID_C " E3", &PID_PARAM(Kc,2), 1, 9990);
MENU_ITEM_EDIT(float3, MSG_PID_C MSG_E3, &PID_PARAM(Kc,2), 1, 9990);
#endif//PID_ADD_EXTRUSION_RATE
#if EXTRUDERS > 3
// set up temp variables - undo the default scaling
raw_Ki = unscalePID_i(PID_PARAM(Ki,3));
raw_Kd = unscalePID_d(PID_PARAM(Kd,3));
MENU_ITEM_EDIT(float52, MSG_PID_P " E4", &PID_PARAM(Kp,3), 1, 9990);
MENU_ITEM_EDIT(float52, MSG_PID_P MSG_E4, &PID_PARAM(Kp,3), 1, 9990);
// i is typically a small value so allows values below 1
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_I " E4", &raw_Ki, 0.01, 9990, copy_and_scalePID_i_E4);
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_D " E4", &raw_Kd, 1, 9990, copy_and_scalePID_d_E4);
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_I MSG_E4, &raw_Ki, 0.01, 9990, copy_and_scalePID_i_E4);
MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_D MSG_E4, &raw_Kd, 1, 9990, copy_and_scalePID_d_E4);
#ifdef PID_ADD_EXTRUSION_RATE
MENU_ITEM_EDIT(float3, MSG_PID_C " E4", &PID_PARAM(Kc,3), 1, 9990);
MENU_ITEM_EDIT(float3, MSG_PID_C MSG_E4, &PID_PARAM(Kc,3), 1, 9990);
#endif//PID_ADD_EXTRUSION_RATE
#endif//EXTRUDERS > 3
#endif//EXTRUDERS > 2
@ -960,84 +850,80 @@ static void lcd_control_temperature_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);
#if TEMP_SENSOR_0 != 0
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);
#if TEMP_SENSOR_0 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &plaPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0
#endif
#if TEMP_SENSOR_BED != 0
MENU_ITEM_EDIT(int3, MSG_BED, &plaPreheatHPBTemp, 0, BED_MAXTEMP - 15);
#endif
#ifdef EEPROM_SETTINGS
#endif
#ifdef EEPROM_SETTINGS
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
#endif
END_MENU();
#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);
#if TEMP_SENSOR_0 != 0
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);
#if TEMP_SENSOR_0 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &absPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0
#endif
#if TEMP_SENSOR_BED != 0
MENU_ITEM_EDIT(int3, MSG_BED, &absPreheatHPBTemp, 0, BED_MAXTEMP - 15);
#endif
#ifdef EEPROM_SETTINGS
#endif
#ifdef EEPROM_SETTINGS
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
#endif
END_MENU();
#endif
END_MENU();
}
static void lcd_control_motion_menu()
{
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
#ifdef ENABLE_AUTO_BED_LEVELING
static void lcd_control_motion_menu() {
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
#ifdef ENABLE_AUTO_BED_LEVELING
MENU_ITEM_EDIT(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, 0.5, 50);
#endif
MENU_ITEM_EDIT(float5, MSG_ACC, &acceleration, 500, 99000);
MENU_ITEM_EDIT(float3, MSG_VXY_JERK, &max_xy_jerk, 1, 990);
MENU_ITEM_EDIT(float52, MSG_VZ_JERK, &max_z_jerk, 0.1, 990);
MENU_ITEM_EDIT(float3, MSG_VE_JERK, &max_e_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_CALLBACK(long5, MSG_AMAX MSG_X, &max_acceleration_units_per_sq_second[X_AXIS], 100, 99000, reset_acceleration_rates);
MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Y, &max_acceleration_units_per_sq_second[Y_AXIS], 100, 99000, reset_acceleration_rates);
MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Z, &max_acceleration_units_per_sq_second[Z_AXIS], 100, 99000, reset_acceleration_rates);
MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E, &max_acceleration_units_per_sq_second[E_AXIS], 100, 99000, reset_acceleration_rates);
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);
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
#endif
MENU_ITEM_EDIT(float5, MSG_ACC, &acceleration, 500, 99000);
MENU_ITEM_EDIT(float3, MSG_VXY_JERK, &max_xy_jerk, 1, 990);
MENU_ITEM_EDIT(float52, MSG_VZ_JERK, &max_z_jerk, 0.1, 990);
MENU_ITEM_EDIT(float3, MSG_VE_JERK, &max_e_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_CALLBACK(long5, MSG_AMAX MSG_X, &max_acceleration_units_per_sq_second[X_AXIS], 100, 99000, reset_acceleration_rates);
MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Y, &max_acceleration_units_per_sq_second[Y_AXIS], 100, 99000, reset_acceleration_rates);
MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Z, &max_acceleration_units_per_sq_second[Z_AXIS], 100, 99000, reset_acceleration_rates);
MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E, &max_acceleration_units_per_sq_second[E_AXIS], 100, 99000, reset_acceleration_rates);
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);
#ifdef ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
MENU_ITEM_EDIT(bool, MSG_ENDSTOP_ABORT, &abort_on_endstop_hit);
#endif
#ifdef SCARA
#endif
#ifdef SCARA
MENU_ITEM_EDIT(float74, MSG_XSCALE, &axis_scaling[X_AXIS],0.5,2);
MENU_ITEM_EDIT(float74, MSG_YSCALE, &axis_scaling[Y_AXIS],0.5,2);
#endif
END_MENU();
#endif
END_MENU();
}
static void lcd_control_volumetric_menu()
{
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
static void lcd_control_volumetric_menu() {
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
MENU_ITEM_EDIT_CALLBACK(bool, MSG_VOLUMETRIC_ENABLED, &volumetric_enabled, calculate_volumetric_multipliers);
MENU_ITEM_EDIT_CALLBACK(bool, MSG_VOLUMETRIC_ENABLED, &volumetric_enabled, calculate_volumetric_multipliers);
if (volumetric_enabled) {
if (volumetric_enabled) {
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_SIZE_EXTRUDER_0, &filament_size[0], 1.5, 3.25, calculate_volumetric_multipliers);
#if EXTRUDERS > 1
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_SIZE_EXTRUDER_1, &filament_size[1], 1.5, 3.25, calculate_volumetric_multipliers);
@ -1048,149 +934,133 @@ static void lcd_control_volumetric_menu()
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
}
}
END_MENU();
END_MENU();
}
#ifdef DOGLCD
static void lcd_set_contrast()
{
if (encoderPosition != 0)
{
lcd_contrast -= encoderPosition;
if (lcd_contrast < 0) lcd_contrast = 0;
else if (lcd_contrast > 63) lcd_contrast = 63;
encoderPosition = 0;
lcdDrawUpdate = 1;
u8g.setContrast(lcd_contrast);
}
if (lcdDrawUpdate)
{
lcd_implementation_drawedit(PSTR(MSG_CONTRAST), itostr2(lcd_contrast));
}
if (LCD_CLICKED) lcd_goto_menu(lcd_control_menu);
static void lcd_set_contrast() {
if (encoderPosition != 0) {
lcd_contrast -= encoderPosition;
if (lcd_contrast < 0) lcd_contrast = 0;
else if (lcd_contrast > 63) lcd_contrast = 63;
encoderPosition = 0;
lcdDrawUpdate = 1;
u8g.setContrast(lcd_contrast);
}
if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_CONTRAST), itostr2(lcd_contrast));
if (LCD_CLICKED) lcd_goto_menu(lcd_control_menu);
}
#endif
#endif //DOGLCD
#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);
#if EXTRUDERS > 1
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_SWAP, &retract_length_swap, 0, 100);
#endif
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);
#if EXTRUDERS > 1
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_RECOVER_SWAP, &retract_recover_length_swap, 0, 100);
#endif
MENU_ITEM_EDIT(float3, MSG_CONTROL_RETRACT_RECOVERF, &retract_recover_feedrate, 1, 999);
END_MENU();
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);
#if EXTRUDERS > 1
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_SWAP, &retract_length_swap, 0, 100);
#endif
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);
#if EXTRUDERS > 1
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_RECOVER_SWAP, &retract_recover_length_swap, 0, 100);
#endif
MENU_ITEM_EDIT(float3, MSG_CONTROL_RETRACT_RECOVERF, &retract_recover_feedrate, 1, 999);
END_MENU();
}
#endif //FWRETRACT
#if SDCARDDETECT == -1
static void lcd_sd_refresh()
{
static void lcd_sd_refresh() {
card.initsd();
currentMenuViewOffset = 0;
}
}
#endif
static void lcd_sd_updir()
{
card.updir();
currentMenuViewOffset = 0;
static void lcd_sd_updir() {
card.updir();
currentMenuViewOffset = 0;
}
void lcd_sdcard_menu()
{
if (lcdDrawUpdate == 0 && LCD_CLICKED == 0)
return; // nothing to do (so don't thrash the SD card)
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);
}
void lcd_sdcard_menu() {
if (lcdDrawUpdate == 0 && LCD_CLICKED == 0) return; // nothing to do (so don't thrash the SD card)
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)
{
#ifndef SDCARD_RATHERRECENTFIRST
card.getfilename(i);
#else
card.getfilename(fileCnt-1-i);
#endif
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();
}
for(uint16_t i = 0; i < fileCnt; i++) {
if (_menuItemNr == _lineNr) {
#ifndef SDCARD_RATHERRECENTFIRST
card.getfilename(i);
#else
card.getfilename(fileCnt-1-i);
#endif
if (card.filenameIsDir)
MENU_ITEM(sddirectory, MSG_CARD_MENU, card.filename, card.longFilename);
else
MENU_ITEM(sdfile, MSG_CARD_MENU, card.filename, card.longFilename);
}
END_MENU();
else {
MENU_ITEM_DUMMY();
}
}
END_MENU();
}
#define menu_edit_type(_type, _name, _strFunc, scale) \
void menu_edit_ ## _name () \
{ \
if ((int32_t)encoderPosition < 0) encoderPosition = 0; \
if ((int32_t)encoderPosition > maxEditValue) encoderPosition = maxEditValue; \
if (lcdDrawUpdate) \
lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) / scale)); \
if (LCD_CLICKED) \
{ \
*((_type*)editValue) = ((_type)((int32_t)encoderPosition + minEditValue)) / scale; \
lcd_goto_menu(prevMenu, prevEncoderPosition); \
} \
} \
void menu_edit_callback_ ## _name () { \
menu_edit_ ## _name (); \
if (LCD_CLICKED) (*callbackFunc)(); \
bool _menu_edit_ ## _name () { \
bool isClicked = LCD_CLICKED; \
if ((int32_t)encoderPosition < 0) encoderPosition = 0; \
if ((int32_t)encoderPosition > maxEditValue) encoderPosition = maxEditValue; \
if (lcdDrawUpdate) \
lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) / scale)); \
if (isClicked) { \
*((_type*)editValue) = ((_type)((int32_t)encoderPosition + minEditValue)) / scale; \
lcd_goto_menu(prevMenu, 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 - minEditValue; \
encoderPosition = (*ptr) * scale - minEditValue; \
}\
static void menu_action_setting_edit_callback_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue, menuFunc_t callback) \
{ \
prevMenu = currentMenu; \
prevEncoderPosition = encoderPosition; \
\
lcdDrawUpdate = 2; \
currentMenu = menu_edit_callback_ ## _name; \
\
editLabel = pstr; \
editValue = ptr; \
minEditValue = minValue * scale; \
maxEditValue = maxValue * scale - minEditValue; \
encoderPosition = (*ptr) * scale - minEditValue; \
callbackFunc = callback;\
}
return isClicked; \
} \
void menu_edit_ ## _name () { _menu_edit_ ## _name(); } \
void menu_edit_callback_ ## _name () { if (_menu_edit_ ## _name ()) (*callbackFunc)(); } \
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 - minEditValue; \
encoderPosition = (*ptr) * scale - minEditValue; \
} \
static void menu_action_setting_edit_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue) { \
_menu_action_setting_edit_ ## _name(pstr, ptr, minValue, maxValue); \
currentMenu = menu_edit_ ## _name; \
}\
static void menu_action_setting_edit_callback_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue, menuFunc_t callback) { \
_menu_action_setting_edit_ ## _name(pstr, ptr, minValue, maxValue); \
currentMenu = menu_edit_callback_ ## _name; \
callbackFunc = callback; \
}
menu_edit_type(int, int3, itostr3, 1)
menu_edit_type(float, float3, ftostr3, 1)
menu_edit_type(float, float32, ftostr32, 100)
@ -1201,94 +1071,81 @@ menu_edit_type(float, float52, ftostr52, 100)
menu_edit_type(unsigned long, long5, ftostr5, 0.01)
#ifdef REPRAPWORLD_KEYPAD
static void reprapworld_keypad_move_z_up() {
static void reprapworld_keypad_move_z_up() {
encoderPosition = 1;
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
lcd_move_z();
lcd_move_z();
}
static void reprapworld_keypad_move_z_down() {
static void reprapworld_keypad_move_z_down() {
encoderPosition = -1;
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
lcd_move_z();
lcd_move_z();
}
static void reprapworld_keypad_move_x_left() {
static void reprapworld_keypad_move_x_left() {
encoderPosition = -1;
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
lcd_move_x();
lcd_move_x();
}
static void reprapworld_keypad_move_x_right() {
static void reprapworld_keypad_move_x_right() {
encoderPosition = 1;
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
lcd_move_x();
}
static void reprapworld_keypad_move_y_down() {
lcd_move_x();
}
static void reprapworld_keypad_move_y_down() {
encoderPosition = 1;
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
lcd_move_y();
}
static void reprapworld_keypad_move_y_up() {
encoderPosition = -1;
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
lcd_move_y();
}
static void reprapworld_keypad_move_home() {
enquecommands_P((PSTR("G28"))); // move all axis home
}
#endif
}
static void reprapworld_keypad_move_y_up() {
encoderPosition = -1;
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
lcd_move_y();
}
static void reprapworld_keypad_move_home() {
enquecommands_P((PSTR("G28"))); // move all axis home
}
#endif //REPRAPWORLD_KEYPAD
/** End of menus **/
static void lcd_quick_feedback()
{
lcdDrawUpdate = 2;
blocking_enc = millis() + 500;
lcd_implementation_quick_feedback();
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) { lcd_goto_menu(data); }
static void menu_action_submenu(menuFunc_t data) { lcd_goto_menu(data); }
static void menu_action_gcode(const char* pgcode)
{
enquecommands_P(pgcode);
}
static void menu_action_gcode(const char* pgcode) { enquecommands_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);
enquecommands_P(PSTR("M24"));
lcd_return_to_status();
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);
enquecommands_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_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);
static void menu_action_setting_edit_bool(const char* pstr, bool* ptr) { *ptr = !(*ptr); }
static void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, menuFunc_t callback) {
menu_action_setting_edit_bool(pstr, ptr);
(*callback)();
}
static void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, menuFunc_t callback)
{
menu_action_setting_edit_bool(pstr, ptr);
(*callback)();
}
#endif//ULTIPANEL
#endif //ULTIPANEL
/** LCD API **/
void lcd_init()
{
lcd_implementation_init();
void lcd_init() {
lcd_implementation_init();
#ifdef NEWPANEL
#ifdef NEWPANEL
SET_INPUT(BTN_EN1);
SET_INPUT(BTN_EN2);
WRITE(BTN_EN1,HIGH);
@ -1323,182 +1180,166 @@ void lcd_init()
#endif // SR_LCD_2W_NL
#endif//!NEWPANEL
#if defined (SDSUPPORT) && defined(SDCARDDETECT) && (SDCARDDETECT > 0)
pinMode(SDCARDDETECT,INPUT);
#if defined(SDSUPPORT) && defined(SDCARDDETECT) && (SDCARDDETECT > 0)
pinMode(SDCARDDETECT, INPUT);
WRITE(SDCARDDETECT, HIGH);
lcd_oldcardstatus = IS_SD_INSERTED;
#endif//(SDCARDDETECT > 0)
#ifdef LCD_HAS_SLOW_BUTTONS
#endif //(SDCARDDETECT > 0)
#ifdef LCD_HAS_SLOW_BUTTONS
slow_buttons = 0;
#endif
lcd_buttons_update();
#ifdef ULTIPANEL
#endif
lcd_buttons_update();
#ifdef ULTIPANEL
encoderDiff = 0;
#endif
#endif
}
int lcd_strlen(char *s) {
int i = 0, j = 0;
while (s[i]) {
if ((s[i] & 0xc0) != 0x80) j++;
i++;
}
return j;
int i = 0, j = 0;
while (s[i]) {
if ((s[i] & 0xc0) != 0x80) j++;
i++;
}
return j;
}
int lcd_strlen_P(const char *s) {
int j = 0;
while (pgm_read_byte(s)) {
if ((pgm_read_byte(s) & 0xc0) != 0x80) j++;
s++;
}
return j;
int j = 0;
while (pgm_read_byte(s)) {
if ((pgm_read_byte(s) & 0xc0) != 0x80) j++;
s++;
}
return j;
}
void lcd_update() {
static unsigned long timeoutToStatus = 0;
void lcd_update()
{
static unsigned long timeoutToStatus = 0;
#ifdef LCD_HAS_SLOW_BUTTONS
#ifdef LCD_HAS_SLOW_BUTTONS
slow_buttons = lcd_implementation_read_slow_buttons(); // buttons which take too long to read in interrupt context
#endif
#endif
lcd_buttons_update();
lcd_buttons_update();
#if (SDCARDDETECT > 0)
if((IS_SD_INSERTED != lcd_oldcardstatus && lcd_detected()))
{
lcdDrawUpdate = 2;
lcd_oldcardstatus = IS_SD_INSERTED;
lcd_implementation_init( // to maybe revive the LCD if static electricity killed it.
#if defined(LCD_PROGRESS_BAR) && defined(SDSUPPORT) && !defined(DOGLCD)
currentMenu == lcd_status_screen
#endif
);
#if (SDCARDDETECT > 0)
if (IS_SD_INSERTED != lcd_oldcardstatus && lcd_detected()) {
lcdDrawUpdate = 2;
lcd_oldcardstatus = IS_SD_INSERTED;
lcd_implementation_init( // to maybe revive the LCD if static electricity killed it.
#if defined(LCD_PROGRESS_BAR) && defined(SDSUPPORT) && !defined(DOGLCD)
currentMenu == lcd_status_screen
#endif
);
if(lcd_oldcardstatus)
{
card.initsd();
LCD_MESSAGEPGM(MSG_SD_INSERTED);
}
else
{
card.release();
LCD_MESSAGEPGM(MSG_SD_REMOVED);
}
if (lcd_oldcardstatus) {
card.initsd();
LCD_MESSAGEPGM(MSG_SD_INSERTED);
}
else {
card.release();
LCD_MESSAGEPGM(MSG_SD_REMOVED);
}
}
#endif//CARDINSERTED
#endif//CARDINSERTED
if (lcd_next_update_millis < millis())
{
#ifdef ULTIPANEL
#ifdef REPRAPWORLD_KEYPAD
if (REPRAPWORLD_KEYPAD_MOVE_Z_UP) {
reprapworld_keypad_move_z_up();
}
if (REPRAPWORLD_KEYPAD_MOVE_Z_DOWN) {
reprapworld_keypad_move_z_down();
}
if (REPRAPWORLD_KEYPAD_MOVE_X_LEFT) {
reprapworld_keypad_move_x_left();
}
if (REPRAPWORLD_KEYPAD_MOVE_X_RIGHT) {
reprapworld_keypad_move_x_right();
}
if (REPRAPWORLD_KEYPAD_MOVE_Y_DOWN) {
reprapworld_keypad_move_y_down();
}
if (REPRAPWORLD_KEYPAD_MOVE_Y_UP) {
reprapworld_keypad_move_y_up();
}
if (REPRAPWORLD_KEYPAD_MOVE_HOME) {
reprapworld_keypad_move_home();
}
#endif
if (abs(encoderDiff) >= ENCODER_PULSES_PER_STEP)
{
int32_t encoderMultiplier = 1;
#ifdef ENCODER_RATE_MULTIPLIER
if (encoderRateMultiplierEnabled) {
int32_t encoderMovementSteps = abs(encoderDiff) / ENCODER_PULSES_PER_STEP;
if (lastEncoderMovementMillis != 0) {
// Note that the rate is always calculated between to passes through the
// loop and that the abs of the encoderDiff value is tracked.
float encoderStepRate =
(float)(encoderMovementSteps) / ((float)(millis() - lastEncoderMovementMillis)) * 1000.0;
if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100;
else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10;
#ifdef ENCODER_RATE_MULTIPLIER_DEBUG
SERIAL_ECHO_START;
SERIAL_ECHO("Enc Step Rate: ");
SERIAL_ECHO(encoderStepRate);
SERIAL_ECHO(" Multiplier: ");
SERIAL_ECHO(encoderMultiplier);
SERIAL_ECHO(" ENCODER_10X_STEPS_PER_SEC: ");
SERIAL_ECHO(ENCODER_10X_STEPS_PER_SEC);
SERIAL_ECHO(" ENCODER_100X_STEPS_PER_SEC: ");
SERIAL_ECHOLN(ENCODER_100X_STEPS_PER_SEC);
#endif //ENCODER_RATE_MULTIPLIER_DEBUG
}
long ms = millis();
if (ms > lcd_next_update_millis) {
lastEncoderMovementMillis = millis();
}
#endif //ENCODER_RATE_MULTIPLIER
#ifdef ULTIPANEL
#ifdef REPRAPWORLD_KEYPAD
if (REPRAPWORLD_KEYPAD_MOVE_Z_UP) reprapworld_keypad_move_z_up();
if (REPRAPWORLD_KEYPAD_MOVE_Z_DOWN) reprapworld_keypad_move_z_down();
if (REPRAPWORLD_KEYPAD_MOVE_X_LEFT) reprapworld_keypad_move_x_left();
if (REPRAPWORLD_KEYPAD_MOVE_X_RIGHT) reprapworld_keypad_move_x_right();
if (REPRAPWORLD_KEYPAD_MOVE_Y_DOWN) reprapworld_keypad_move_y_down();
if (REPRAPWORLD_KEYPAD_MOVE_Y_UP) reprapworld_keypad_move_y_up();
if (REPRAPWORLD_KEYPAD_MOVE_HOME) reprapworld_keypad_move_home();
#endif
lcdDrawUpdate = 1;
encoderPosition += (encoderDiff * encoderMultiplier) / ENCODER_PULSES_PER_STEP;
encoderDiff = 0;
timeoutToStatus = millis() + LCD_TIMEOUT_TO_STATUS;
bool encoderPastThreshold = (abs(encoderDiff) >= ENCODER_PULSES_PER_STEP);
if (encoderPastThreshold || LCD_CLICKED) {
if (encoderPastThreshold) {
int32_t encoderMultiplier = 1;
#ifdef ENCODER_RATE_MULTIPLIER
if (encoderRateMultiplierEnabled) {
int32_t encoderMovementSteps = abs(encoderDiff) / ENCODER_PULSES_PER_STEP;
if (lastEncoderMovementMillis != 0) {
// Note that the rate is always calculated between to passes through the
// loop and that the abs of the encoderDiff value is tracked.
float encoderStepRate = (float)(encoderMovementSteps) / ((float)(ms - lastEncoderMovementMillis)) * 1000.0;
if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100;
else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10;
#ifdef ENCODER_RATE_MULTIPLIER_DEBUG
SERIAL_ECHO_START;
SERIAL_ECHO("Enc Step Rate: ");
SERIAL_ECHO(encoderStepRate);
SERIAL_ECHO(" Multiplier: ");
SERIAL_ECHO(encoderMultiplier);
SERIAL_ECHO(" ENCODER_10X_STEPS_PER_SEC: ");
SERIAL_ECHO(ENCODER_10X_STEPS_PER_SEC);
SERIAL_ECHO(" ENCODER_100X_STEPS_PER_SEC: ");
SERIAL_ECHOLN(ENCODER_100X_STEPS_PER_SEC);
#endif //ENCODER_RATE_MULTIPLIER_DEBUG
}
lastEncoderMovementMillis = ms;
}
#endif //ENCODER_RATE_MULTIPLIER
lcdDrawUpdate = 1;
encoderPosition += (encoderDiff * encoderMultiplier) / ENCODER_PULSES_PER_STEP;
encoderDiff = 0;
}
if (LCD_CLICKED)
timeoutToStatus = millis() + LCD_TIMEOUT_TO_STATUS;
#endif//ULTIPANEL
#ifdef DOGLCD // Changes due to different driver architecture of the DOGM display
blink++; // Variable for fan animation and alive dot
u8g.firstPage();
do
{
u8g.setFont(FONT_MENU);
u8g.setPrintPos(125,0);
if (blink % 2) u8g.setColorIndex(1); else u8g.setColorIndex(0); // Set color for the alive dot
u8g.drawPixel(127,63); // draw alive dot
u8g.setColorIndex(1); // black on white
(*currentMenu)();
if (!lcdDrawUpdate) break; // Terminate display update, when nothing new to draw. This must be done before the last dogm.next()
} while( u8g.nextPage() );
#else
timeoutToStatus = ms + LCD_TIMEOUT_TO_STATUS;
}
#endif //ULTIPANEL
#ifdef DOGLCD // Changes due to different driver architecture of the DOGM display
blink++; // Variable for fan animation and alive dot
u8g.firstPage();
do {
u8g.setFont(FONT_MENU);
u8g.setPrintPos(125, 0);
if (blink % 2) u8g.setColorIndex(1); else u8g.setColorIndex(0); // Set color for the alive dot
u8g.drawPixel(127, 63); // draw alive dot
u8g.setColorIndex(1); // black on white
(*currentMenu)();
#endif
if (!lcdDrawUpdate) break; // Terminate display update, when nothing new to draw. This must be done before the last dogm.next()
} while( u8g.nextPage() );
#else
(*currentMenu)();
#endif
#ifdef LCD_HAS_STATUS_INDICATORS
lcd_implementation_update_indicators();
#endif
#ifdef LCD_HAS_STATUS_INDICATORS
lcd_implementation_update_indicators();
#endif
#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() + LCD_UPDATE_INTERVAL;
}
#ifdef ULTIPANEL
if (currentMenu != lcd_status_screen && millis() > timeoutToStatus) {
lcd_return_to_status();
lcdDrawUpdate = 2;
}
#endif //ULTIPANEL
if (lcdDrawUpdate == 2) lcd_implementation_clear();
if (lcdDrawUpdate) lcdDrawUpdate--;
lcd_next_update_millis = millis() + LCD_UPDATE_INTERVAL;
}
}
void lcd_ignore_click(bool b)
{
ignore_click = b;
wait_for_unclick = false;
void lcd_ignore_click(bool b) {
ignore_click = b;
wait_for_unclick = false;
}
void lcd_finishstatus() {
@ -1521,145 +1362,122 @@ void lcd_finishstatus() {
message_millis = millis(); //get status message to show up for a while
#endif
}
void lcd_setstatus(const char* message)
{
if (lcd_status_message_level > 0)
return;
strncpy(lcd_status_message, message, LCD_WIDTH);
lcd_finishstatus();
void lcd_setstatus(const char* message) {
if (lcd_status_message_level > 0) return;
strncpy(lcd_status_message, message, LCD_WIDTH);
lcd_finishstatus();
}
void lcd_setstatuspgm(const char* message)
{
if (lcd_status_message_level > 0)
return;
strncpy_P(lcd_status_message, message, LCD_WIDTH);
lcd_finishstatus();
void lcd_setstatuspgm(const char* message) {
if (lcd_status_message_level > 0) return;
strncpy_P(lcd_status_message, message, LCD_WIDTH);
lcd_finishstatus();
}
void lcd_setalertstatuspgm(const char* message)
{
lcd_setstatuspgm(message);
lcd_status_message_level = 1;
#ifdef ULTIPANEL
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;
#endif
}
void lcd_reset_alert_level() { lcd_status_message_level = 0; }
#ifdef DOGLCD
void lcd_setcontrast(uint8_t value)
{
void lcd_setcontrast(uint8_t value) {
lcd_contrast = value & 63;
u8g.setContrast(lcd_contrast);
}
}
#endif
#ifdef ULTIPANEL
/* Warning: This function is called from interrupt context */
void lcd_buttons_update()
{
#ifdef NEWPANEL
uint8_t newbutton=0;
if(READ(BTN_EN1)==0) newbutton|=EN_A;
if(READ(BTN_EN2)==0) newbutton|=EN_B;
#if BTN_ENC > 0
if((blocking_enc<millis()) && (READ(BTN_ENC)==0))
newbutton |= EN_C;
#endif
void lcd_buttons_update() {
#ifdef NEWPANEL
uint8_t newbutton = 0;
if (READ(BTN_EN1) == 0) newbutton |= EN_A;
if (READ(BTN_EN2) == 0) newbutton |= EN_B;
#if BTN_ENC > 0
if (millis() > blocking_enc && READ(BTN_ENC) == 0) newbutton |= EN_C;
#endif
buttons = newbutton;
#ifdef LCD_HAS_SLOW_BUTTONS
buttons |= slow_buttons;
buttons |= slow_buttons;
#endif
#ifdef REPRAPWORLD_KEYPAD
// for the reprapworld_keypad
uint8_t newbutton_reprapworld_keypad=0;
WRITE(SHIFT_LD,LOW);
WRITE(SHIFT_LD,HIGH);
for(int8_t i=0;i<8;i++) {
newbutton_reprapworld_keypad = newbutton_reprapworld_keypad>>1;
if(READ(SHIFT_OUT))
newbutton_reprapworld_keypad|=(1<<7);
WRITE(SHIFT_CLK,HIGH);
WRITE(SHIFT_CLK,LOW);
WRITE(SHIFT_LD, LOW);
WRITE(SHIFT_LD, HIGH);
for(int8_t i = 0; i < 8; i++) {
newbutton_reprapworld_keypad >>= 1;
if (READ(SHIFT_OUT)) newbutton_reprapworld_keypad |= (1 << 7);
WRITE(SHIFT_CLK, HIGH);
WRITE(SHIFT_CLK, LOW);
}
buttons_reprapworld_keypad=~newbutton_reprapworld_keypad; //invert it, because a pressed switch produces a logical 0
#endif
#else //read it from the shift register
uint8_t newbutton=0;
WRITE(SHIFT_LD,LOW);
WRITE(SHIFT_LD,HIGH);
unsigned char tmp_buttons=0;
for(int8_t i=0;i<8;i++)
{
newbutton = newbutton>>1;
if(READ(SHIFT_OUT))
newbutton|=(1<<7);
WRITE(SHIFT_CLK,HIGH);
WRITE(SHIFT_CLK,LOW);
#endif
#else //read it from the shift register
uint8_t newbutton = 0;
WRITE(SHIFT_LD, LOW);
WRITE(SHIFT_LD, HIGH);
unsigned char tmp_buttons = 0;
for(int8_t i=0; i<8; i++) {
newbutton >>= 1;
if (READ(SHIFT_OUT)) newbutton |= (1 << 7);
WRITE(SHIFT_CLK, HIGH);
WRITE(SHIFT_CLK, LOW);
}
buttons=~newbutton; //invert it, because a pressed switch produces a logical 0
#endif//!NEWPANEL
//manage encoder rotation
uint8_t enc=0;
if (buttons & EN_A) enc |= B01;
if (buttons & EN_B) enc |= B10;
if(enc != lastEncoderBits)
{
switch(enc)
{
case encrot0:
if(lastEncoderBits==encrot3)
encoderDiff++;
else if(lastEncoderBits==encrot1)
encoderDiff--;
break;
case encrot1:
if(lastEncoderBits==encrot0)
encoderDiff++;
else if(lastEncoderBits==encrot2)
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;
}
buttons = ~newbutton; //invert it, because a pressed switch produces a logical 0
#endif //!NEWPANEL
//manage encoder rotation
uint8_t enc=0;
if (buttons & EN_A) enc |= B01;
if (buttons & EN_B) enc |= B10;
if (enc != lastEncoderBits) {
switch(enc) {
case encrot0:
if (lastEncoderBits==encrot3) encoderDiff++;
else if (lastEncoderBits==encrot1) encoderDiff--;
break;
case encrot1:
if (lastEncoderBits==encrot0) encoderDiff++;
else if (lastEncoderBits==encrot2) 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;
}
lastEncoderBits = enc;
}
lastEncoderBits = enc;
}
bool lcd_detected(void)
{
#if (defined(LCD_I2C_TYPE_MCP23017) || defined(LCD_I2C_TYPE_MCP23008)) && defined(DETECT_DEVICE)
return lcd.LcdDetected() == 1;
#else
return true;
#endif
bool lcd_detected(void) {
#if (defined(LCD_I2C_TYPE_MCP23017) || defined(LCD_I2C_TYPE_MCP23008)) && defined(DETECT_DEVICE)
return lcd.LcdDetected() == 1;
#else
return true;
#endif
}
void lcd_buzz(long duration, uint16_t freq)
{
#ifdef LCD_USE_I2C_BUZZER
lcd.buzz(duration,freq);
#endif
void lcd_buzz(long duration, uint16_t freq) {
#ifdef LCD_USE_I2C_BUZZER
lcd.buzz(duration,freq);
#endif
}
bool lcd_clicked()
{
return LCD_CLICKED;
}
#endif//ULTIPANEL
bool lcd_clicked() { return LCD_CLICKED; }
#endif //ULTIPANEL
/********************************/
/** Float conversion utilities **/

Loading…
Cancel
Save