Initial upload
Initial uploading of firmware to seemecnc git
This commit is contained in:
commit
46729d116b
24 changed files with 26070 additions and 0 deletions
22
.gitattributes
vendored
Normal file
22
.gitattributes
vendored
Normal file
|
|
@ -0,0 +1,22 @@
|
|||
# Auto detect text files and perform LF normalization
|
||||
* text=auto
|
||||
|
||||
# Custom for Visual Studio
|
||||
*.cs diff=csharp
|
||||
*.sln merge=union
|
||||
*.csproj merge=union
|
||||
*.vbproj merge=union
|
||||
*.fsproj merge=union
|
||||
*.dbproj merge=union
|
||||
|
||||
# Standard to msysgit
|
||||
*.doc diff=astextplain
|
||||
*.DOC diff=astextplain
|
||||
*.docx diff=astextplain
|
||||
*.DOCX diff=astextplain
|
||||
*.dot diff=astextplain
|
||||
*.DOT diff=astextplain
|
||||
*.pdf diff=astextplain
|
||||
*.PDF diff=astextplain
|
||||
*.rtf diff=astextplain
|
||||
*.RTF diff=astextplain
|
||||
163
.gitignore
vendored
Normal file
163
.gitignore
vendored
Normal file
|
|
@ -0,0 +1,163 @@
|
|||
#################
|
||||
## Eclipse
|
||||
#################
|
||||
|
||||
*.pydevproject
|
||||
.project
|
||||
.metadata
|
||||
bin/
|
||||
tmp/
|
||||
*.tmp
|
||||
*.bak
|
||||
*.swp
|
||||
*~.nib
|
||||
local.properties
|
||||
.classpath
|
||||
.settings/
|
||||
.loadpath
|
||||
|
||||
# External tool builders
|
||||
.externalToolBuilders/
|
||||
|
||||
# Locally stored "Eclipse launch configurations"
|
||||
*.launch
|
||||
|
||||
# CDT-specific
|
||||
.cproject
|
||||
|
||||
# PDT-specific
|
||||
.buildpath
|
||||
|
||||
|
||||
#################
|
||||
## Visual Studio
|
||||
#################
|
||||
|
||||
## Ignore Visual Studio temporary files, build results, and
|
||||
## files generated by popular Visual Studio add-ons.
|
||||
|
||||
# User-specific files
|
||||
*.suo
|
||||
*.user
|
||||
*.sln.docstates
|
||||
|
||||
# Build results
|
||||
[Dd]ebug/
|
||||
[Rr]elease/
|
||||
*_i.c
|
||||
*_p.c
|
||||
*.ilk
|
||||
*.meta
|
||||
*.obj
|
||||
*.pch
|
||||
*.pdb
|
||||
*.pgc
|
||||
*.pgd
|
||||
*.rsp
|
||||
*.sbr
|
||||
*.tlb
|
||||
*.tli
|
||||
*.tlh
|
||||
*.tmp
|
||||
*.vspscc
|
||||
.builds
|
||||
*.dotCover
|
||||
|
||||
## TODO: If you have NuGet Package Restore enabled, uncomment this
|
||||
#packages/
|
||||
|
||||
# Visual C++ cache files
|
||||
ipch/
|
||||
*.aps
|
||||
*.ncb
|
||||
*.opensdf
|
||||
*.sdf
|
||||
|
||||
# Visual Studio profiler
|
||||
*.psess
|
||||
*.vsp
|
||||
|
||||
# ReSharper is a .NET coding add-in
|
||||
_ReSharper*
|
||||
|
||||
# Installshield output folder
|
||||
[Ee]xpress
|
||||
|
||||
# DocProject is a documentation generator add-in
|
||||
DocProject/buildhelp/
|
||||
DocProject/Help/*.HxT
|
||||
DocProject/Help/*.HxC
|
||||
DocProject/Help/*.hhc
|
||||
DocProject/Help/*.hhk
|
||||
DocProject/Help/*.hhp
|
||||
DocProject/Help/Html2
|
||||
DocProject/Help/html
|
||||
|
||||
# Click-Once directory
|
||||
publish
|
||||
|
||||
# Others
|
||||
[Bb]in
|
||||
[Oo]bj
|
||||
sql
|
||||
TestResults
|
||||
*.Cache
|
||||
ClientBin
|
||||
stylecop.*
|
||||
~$*
|
||||
*.dbmdl
|
||||
Generated_Code #added for RIA/Silverlight projects
|
||||
|
||||
# Backup & report files from converting an old project file to a newer
|
||||
# Visual Studio version. Backup files are not needed, because we have git ;-)
|
||||
_UpgradeReport_Files/
|
||||
Backup*/
|
||||
UpgradeLog*.XML
|
||||
|
||||
|
||||
|
||||
############
|
||||
## Windows
|
||||
############
|
||||
|
||||
# Windows image file caches
|
||||
Thumbs.db
|
||||
|
||||
# Folder config file
|
||||
Desktop.ini
|
||||
|
||||
|
||||
#############
|
||||
## Python
|
||||
#############
|
||||
|
||||
*.py[co]
|
||||
|
||||
# Packages
|
||||
*.egg
|
||||
*.egg-info
|
||||
dist
|
||||
build
|
||||
eggs
|
||||
parts
|
||||
bin
|
||||
var
|
||||
sdist
|
||||
develop-eggs
|
||||
.installed.cfg
|
||||
|
||||
# Installer logs
|
||||
pip-log.txt
|
||||
|
||||
# Unit test / coverage reports
|
||||
.coverage
|
||||
.tox
|
||||
|
||||
#Translations
|
||||
*.mo
|
||||
|
||||
#Mr Developer
|
||||
.mr.developer.cfg
|
||||
|
||||
# Mac crap
|
||||
.DS_Store
|
||||
8
README.md
Normal file
8
README.md
Normal file
|
|
@ -0,0 +1,8 @@
|
|||
##############################################################
|
||||
###### Repetier Firmware for the Rostock MAX ######
|
||||
##############################################################
|
||||
|
||||
|
||||
This firmware is a fork from Repetier (https://github.com/repetier)
|
||||
It is maintained to work with the SeeMeCNC Rostock MAX
|
||||
|
||||
1129
Repetier/Commands.cpp
Normal file
1129
Repetier/Commands.cpp
Normal file
File diff suppressed because it is too large
Load diff
1107
Repetier/Configuration.h
Normal file
1107
Repetier/Configuration.h
Normal file
File diff suppressed because it is too large
Load diff
726
Repetier/Eeprom.cpp
Normal file
726
Repetier/Eeprom.cpp
Normal file
|
|
@ -0,0 +1,726 @@
|
|||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Repetier-Firmware is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
|
||||
Functions in this file are used to communicate using ascii or repetier protocol.
|
||||
*/
|
||||
|
||||
#include "Reptier.h"
|
||||
|
||||
#if EEPROM_MODE!=0
|
||||
#include "Eeprom.h"
|
||||
extern void epr_eeprom_to_data();
|
||||
|
||||
byte epr_compute_checksum() {
|
||||
int i;
|
||||
byte checksum=0;
|
||||
for(i=0;i<2048;i++) {
|
||||
if(i==EEPROM_OFFSET+EPR_INTEGRITY_BYTE) continue;
|
||||
checksum += eeprom_read_byte ((unsigned char *)(i));
|
||||
}
|
||||
return checksum;
|
||||
}
|
||||
|
||||
|
||||
|
||||
inline void epr_set_byte(uint pos,byte value) {
|
||||
eeprom_write_byte((unsigned char *)(EEPROM_OFFSET+pos), value);
|
||||
}
|
||||
inline void epr_set_int(uint pos,int value) {
|
||||
eeprom_write_word((unsigned int*)(EEPROM_OFFSET+pos),value);
|
||||
}
|
||||
inline void epr_set_long(uint pos,long value) {
|
||||
eeprom_write_dword((unsigned long*)(EEPROM_OFFSET+pos),value);
|
||||
}
|
||||
inline void epr_set_float(uint pos,float value) {
|
||||
eeprom_write_block(&value,(void*)(EEPROM_OFFSET+pos), 4);
|
||||
}
|
||||
void epr_out_prefix(uint pos) {
|
||||
if(pos<EEPROM_EXTRUDER_OFFSET) return;
|
||||
int n = (pos-EEPROM_EXTRUDER_OFFSET)/EEPROM_EXTRUDER_LENGTH+1;
|
||||
OUT_P_I("Extr.",n);
|
||||
out.print(' ');
|
||||
}
|
||||
void epr_out_float(uint pos,PGM_P text) {
|
||||
OUT_P("EPR:3 ");
|
||||
OUT(pos);
|
||||
OUT(' ');
|
||||
OUT(epr_get_float(pos));
|
||||
OUT(' ');
|
||||
epr_out_prefix(pos);
|
||||
out.println_P(text);
|
||||
}
|
||||
void epr_out_long(uint pos,PGM_P text) {
|
||||
OUT_P("EPR:2 ");
|
||||
OUT(pos);
|
||||
OUT(' ');
|
||||
OUT(epr_get_long(pos));
|
||||
OUT(' ');
|
||||
epr_out_prefix(pos);
|
||||
out.println_P(text);
|
||||
}
|
||||
void epr_out_int(uint pos,PGM_P text) {
|
||||
OUT_P("EPR:1 ");
|
||||
OUT(pos);
|
||||
OUT(' ');
|
||||
OUT(epr_get_int(pos));
|
||||
OUT(' ');
|
||||
epr_out_prefix(pos);
|
||||
out.println_P(text);
|
||||
}
|
||||
void epr_out_byte(uint pos,PGM_P text) {
|
||||
OUT_P("EPR:0 ");
|
||||
OUT(pos);
|
||||
OUT(' ');
|
||||
OUT((int)epr_get_byte(pos));
|
||||
OUT(' ');
|
||||
epr_out_prefix(pos);
|
||||
out.println_P(text);
|
||||
}
|
||||
|
||||
void epr_update(GCode *com) {
|
||||
if(GCODE_HAS_T(com) && GCODE_HAS_P(com)) switch(com->T) {
|
||||
case 0:
|
||||
if(GCODE_HAS_S(com)) epr_set_byte(com->P,(byte)com->S);
|
||||
break;
|
||||
case 1:
|
||||
if(GCODE_HAS_S(com)) epr_set_int(com->P,(int)com->S);
|
||||
break;
|
||||
case 2:
|
||||
if(GCODE_HAS_S(com)) epr_set_long(com->P,(long)com->S);
|
||||
break;
|
||||
case 3:
|
||||
if(GCODE_HAS_X(com)) epr_set_float(com->P,com->X);
|
||||
break;
|
||||
}
|
||||
byte newcheck = epr_compute_checksum();
|
||||
if(newcheck!=epr_get_byte(EPR_INTEGRITY_BYTE))
|
||||
epr_set_byte(EPR_INTEGRITY_BYTE,newcheck);
|
||||
epr_eeprom_to_data();
|
||||
}
|
||||
|
||||
/** \brief Copy data from EEPROM to variables.
|
||||
*/
|
||||
void epr_eeprom_reset() {
|
||||
byte version = EEPROM_PROTOCOL_VERSION;
|
||||
baudrate = BAUDRATE;
|
||||
max_inactive_time = MAX_INACTIVE_TIME*1000L;
|
||||
stepper_inactive_time = STEPPER_INACTIVE_TIME*1000L;
|
||||
axis_steps_per_unit[0] = XAXIS_STEPS_PER_MM;
|
||||
axis_steps_per_unit[1] = YAXIS_STEPS_PER_MM;
|
||||
axis_steps_per_unit[2] = ZAXIS_STEPS_PER_MM;
|
||||
axis_steps_per_unit[3] = 1;
|
||||
max_feedrate[0] = MAX_FEEDRATE_X;
|
||||
max_feedrate[1] = MAX_FEEDRATE_Y;
|
||||
max_feedrate[2] = MAX_FEEDRATE_Z;
|
||||
homing_feedrate[0] = HOMING_FEEDRATE_X;
|
||||
homing_feedrate[1] = HOMING_FEEDRATE_Y;
|
||||
homing_feedrate[2] = HOMING_FEEDRATE_Z;
|
||||
printer_state.maxJerk = MAX_JERK;
|
||||
printer_state.maxZJerk = MAX_ZJERK;
|
||||
#ifdef RAMP_ACCELERATION
|
||||
max_acceleration_units_per_sq_second[0] = MAX_ACCELERATION_UNITS_PER_SQ_SECOND_X;
|
||||
max_acceleration_units_per_sq_second[1] = MAX_ACCELERATION_UNITS_PER_SQ_SECOND_Y;
|
||||
max_acceleration_units_per_sq_second[2] = MAX_ACCELERATION_UNITS_PER_SQ_SECOND_Z;
|
||||
max_travel_acceleration_units_per_sq_second[0] = MAX_TRAVEL_ACCELERATION_UNITS_PER_SQ_SECOND_X;
|
||||
max_travel_acceleration_units_per_sq_second[1] = MAX_TRAVEL_ACCELERATION_UNITS_PER_SQ_SECOND_X;
|
||||
max_travel_acceleration_units_per_sq_second[2] = MAX_TRAVEL_ACCELERATION_UNITS_PER_SQ_SECOND_X;
|
||||
#endif
|
||||
#if USE_OPS==1
|
||||
printer_state.opsMode = OPS_MODE;
|
||||
printer_state.opsMinDistance = OPS_MIN_DISTANCE;
|
||||
printer_state.opsRetractDistance = OPS_RETRACT_DISTANCE;
|
||||
printer_state.opsRetractBacklash = OPS_RETRACT_BACKLASH;
|
||||
printer_state.opsMoveAfter = 0;
|
||||
#endif
|
||||
#if HAVE_HEATED_BED
|
||||
heatedBedController.heatManager= HEATED_BED_HEAT_MANAGER;
|
||||
#ifdef TEMP_PID
|
||||
heatedBedController.pidDriveMax = HEATED_BED_PID_INTEGRAL_DRIVE_MAX;
|
||||
heatedBedController.pidDriveMin = HEATED_BED_PID_INTEGRAL_DRIVE_MIN;
|
||||
heatedBedController.pidPGain = HEATED_BED_PID_PGAIN;
|
||||
heatedBedController.pidIGain = HEATED_BED_PID_IGAIN;
|
||||
heatedBedController.pidDGain = HEATED_BED_PID_DGAIN;
|
||||
heatedBedController.pidMax = HEATED_BED_PID_MAX;
|
||||
#endif
|
||||
#endif
|
||||
printer_state.xLength = X_MAX_LENGTH;
|
||||
printer_state.yLength = Y_MAX_LENGTH;
|
||||
printer_state.zLength = Z_MAX_LENGTH;
|
||||
printer_state.xMin = X_MIN_POS;
|
||||
printer_state.yMin = Y_MIN_POS;
|
||||
printer_state.zMin = Z_MIN_POS;
|
||||
#if ENABLE_BACKLASH_COMPENSATION
|
||||
printer_state.backlashX = X_BACKLASH;
|
||||
printer_state.backlashY = Y_BACKLASH;
|
||||
printer_state.backlashZ = Z_BACKLASH;
|
||||
#endif
|
||||
Extruder *e;
|
||||
#if NUM_EXTRUDER>0
|
||||
e = &extruder[0];
|
||||
e->stepsPerMM = EXT0_STEPS_PER_MM;
|
||||
e->maxFeedrate = EXT0_MAX_FEEDRATE;
|
||||
e->maxStartFeedrate = EXT0_MAX_START_FEEDRATE;
|
||||
e->maxAcceleration = EXT0_MAX_ACCELERATION;
|
||||
e->tempControl.heatManager = EXT0_HEAT_MANAGER;
|
||||
#ifdef TEMP_PID
|
||||
e->tempControl.pidDriveMax = EXT0_PID_INTEGRAL_DRIVE_MAX;
|
||||
e->tempControl.pidDriveMin = EXT0_PID_INTEGRAL_DRIVE_MIN;
|
||||
e->tempControl.pidPGain = EXT0_PID_P;
|
||||
e->tempControl.pidIGain = EXT0_PID_I;
|
||||
e->tempControl.pidDGain = EXT0_PID_D;
|
||||
e->tempControl.pidMax = EXT0_PID_MAX;
|
||||
#endif
|
||||
e->yOffset = EXT0_Y_OFFSET;
|
||||
e->xOffset = EXT0_X_OFFSET;
|
||||
e->watchPeriod = EXT0_WATCHPERIOD;
|
||||
#if RETRACT_DURING_HEATUP
|
||||
e->waitRetractTemperature = EXT0_WAIT_RETRACT_TEMP;
|
||||
e->waitRetractUnits = EXT0_WAIT_RETRACT_UNITS;
|
||||
#endif
|
||||
e->coolerSpeed = EXT0_EXTRUDER_COOLER_SPEED;
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
e->advanceK = EXT0_ADVANCE_K;
|
||||
#endif
|
||||
e->advanceL = EXT0_ADVANCE_L;
|
||||
#endif
|
||||
#endif // NUM_EXTRUDER>0
|
||||
#if NUM_EXTRUDER>1
|
||||
e = &extruder[1];
|
||||
e->stepsPerMM = EXT1_STEPS_PER_MM;
|
||||
e->maxFeedrate = EXT1_MAX_FEEDRATE;
|
||||
e->maxStartFeedrate = EXT1_MAX_START_FEEDRATE;
|
||||
e->maxAcceleration = EXT1_MAX_ACCELERATION;
|
||||
e->tempControl.heatManager = EXT1_HEAT_MANAGER;
|
||||
#ifdef TEMP_PID
|
||||
e->tempControl.pidDriveMax = EXT1_PID_INTEGRAL_DRIVE_MAX;
|
||||
e->tempControl.pidDriveMin = EXT1_PID_INTEGRAL_DRIVE_MIN;
|
||||
e->tempControl.pidPGain = EXT1_PID_P;
|
||||
e->tempControl.pidIGain = EXT1_PID_I;
|
||||
e->tempControl.pidDGain = EXT1_PID_D;
|
||||
e->tempControl.pidMax = EXT1_PID_MAX;
|
||||
#endif
|
||||
e->yOffset = EXT1_Y_OFFSET;
|
||||
e->xOffset = EXT1_X_OFFSET;
|
||||
e->watchPeriod = EXT1_WATCHPERIOD;
|
||||
#if RETRACT_DURING_HEATUP
|
||||
e->waitRetractTemperature = EXT1_WAIT_RETRACT_TEMP;
|
||||
e->waitRetractUnits = EXT1_WAIT_RETRACT_UNITS;
|
||||
#endif
|
||||
e->coolerSpeed = EXT1_EXTRUDER_COOLER_SPEED;
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
e->advanceK = EXT1_ADVANCE_K;
|
||||
#endif
|
||||
e->advanceL = EXT1_ADVANCE_L;
|
||||
#endif
|
||||
#endif // NUM_EXTRUDER > 1
|
||||
#if NUM_EXTRUDER>2
|
||||
e = &extruder[2];
|
||||
e->stepsPerMM = EXT2_STEPS_PER_MM;
|
||||
e->maxFeedrate = EXT2_MAX_FEEDRATE;
|
||||
e->maxStartFeedrate = EXT2_MAX_START_FEEDRATE;
|
||||
e->maxAcceleration = EXT2_MAX_ACCELERATION;
|
||||
e->tempControl.heatManager = EXT2_HEAT_MANAGER;
|
||||
#ifdef TEMP_PID
|
||||
e->tempControl.pidDriveMax = EXT2_PID_INTEGRAL_DRIVE_MAX;
|
||||
e->tempControl.pidDriveMin = EXT2_PID_INTEGRAL_DRIVE_MIN;
|
||||
e->tempControl.pidPGain = EXT2_PID_P;
|
||||
e->tempControl.pidIGain = EXT2_PID_I;
|
||||
e->tempControl.pidDGain = EXT2_PID_D;
|
||||
e->tempControl.pidMax = EXT2_PID_MAX;
|
||||
#endif
|
||||
e->yOffset = EXT2_Y_OFFSET;
|
||||
e->xOffset = EXT2_X_OFFSET;
|
||||
e->watchPeriod = EXT2_WATCHPERIOD;
|
||||
#if RETRACT_DURING_HEATUP
|
||||
e->waitRetractTemperature = EXT2_WAIT_RETRACT_TEMP;
|
||||
e->waitRetractUnits = EXT2_WAIT_RETRACT_UNITS;
|
||||
#endif
|
||||
e->coolerSpeed = EXT2_EXTRUDER_COOLER_SPEED;
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
e->advanceK = EXT2_ADVANCE_K;
|
||||
#endif
|
||||
e->advanceL = EXT2_ADVANCE_L;
|
||||
#endif
|
||||
#endif // NUM_EXTRUDER > 2
|
||||
#if NUM_EXTRUDER>3
|
||||
e = &extruder[3];
|
||||
e->stepsPerMM = EXT3_STEPS_PER_MM;
|
||||
e->maxFeedrate = EXT3_MAX_FEEDRATE;
|
||||
e->maxStartFeedrate = EXT3_MAX_START_FEEDRATE;
|
||||
e->maxAcceleration = EXT3_MAX_ACCELERATION;
|
||||
e->tempControl.heatManager = EXT3_HEAT_MANAGER;
|
||||
#ifdef TEMP_PID
|
||||
e->tempControl.pidDriveMax = EXT3_PID_INTEGRAL_DRIVE_MAX;
|
||||
e->tempControl.pidDriveMin = EXT3_PID_INTEGRAL_DRIVE_MIN;
|
||||
e->tempControl.pidPGain = EXT3_PID_P;
|
||||
e->tempControl.pidIGain = EXT3_PID_I;
|
||||
e->tempControl.pidDGain = EXT3_PID_D;
|
||||
e->tempControl.pidMax = EXT3_PID_MAX;
|
||||
#endif
|
||||
e->yOffset = EXT3_Y_OFFSET;
|
||||
e->xOffset = EXT3_X_OFFSET;
|
||||
e->watchPeriod = EXT3_WATCHPERIOD;
|
||||
#if RETRACT_DURING_HEATUP
|
||||
e->waitRetractTemperature = EXT3_WAIT_RETRACT_TEMP;
|
||||
e->waitRetractUnits = EXT3_WAIT_RETRACT_UNITS;
|
||||
#endif
|
||||
e->coolerSpeed = EXT3_EXTRUDER_COOLER_SPEED;
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
e->advanceK = EXT3_ADVANCE_K;
|
||||
#endif
|
||||
e->advanceL = EXT3_ADVANCE_L;
|
||||
#endif
|
||||
#endif // NUM_EXTRUDER > 3
|
||||
#if NUM_EXTRUDER>4
|
||||
e = &extruder[4];
|
||||
e->stepsPerMM = EXT4_STEPS_PER_MM;
|
||||
e->maxFeedrate = EXT4_MAX_FEEDRATE;
|
||||
e->maxStartFeedrate = EXT4_MAX_START_FEEDRATE;
|
||||
e->maxAcceleration = EXT4_MAX_ACCELERATION;
|
||||
e->tempControl.heatManager = EXT4_HEAT_MANAGER;
|
||||
#ifdef TEMP_PID
|
||||
e->tempControl.pidDriveMax = EXT4_PID_INTEGRAL_DRIVE_MAX;
|
||||
e->tempControl.pidDriveMin = EXT4_PID_INTEGRAL_DRIVE_MIN;
|
||||
e->tempControl.pidPGain = EXT4_PID_P;
|
||||
e->tempControl.pidIGain = EXT4_PID_I;
|
||||
e->tempControl.pidDGain = EXT4_PID_D;
|
||||
e->tempControl.pidMax = EXT4_PID_MAX;
|
||||
#endif
|
||||
e->yOffset = EXT4_Y_OFFSET;
|
||||
e->xOffset = EXT4_X_OFFSET;
|
||||
e->watchPeriod = EXT4_WATCHPERIOD;
|
||||
#if RETRACT_DURING_HEATUP
|
||||
e->waitRetractTemperature = EXT4_WAIT_RETRACT_TEMP;
|
||||
e->waitRetractUnits = EXT4_WAIT_RETRACT_UNITS;
|
||||
#endif
|
||||
e->coolerSpeed = EXT4_EXTRUDER_COOLER_SPEED;
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
e->advanceK = EXT4_ADVANCE_K;
|
||||
#endif
|
||||
e->advanceL = EXT4_ADVANCE_L;
|
||||
#endif
|
||||
#endif // NUM_EXTRUDER > 4
|
||||
#if NUM_EXTRUDER>5
|
||||
e = &extruder[5];
|
||||
e->stepsPerMM = EXT5_STEPS_PER_MM;
|
||||
e->maxFeedrate = EXT5_MAX_FEEDRATE;
|
||||
e->maxStartFeedrate = EXT5_MAX_START_FEEDRATE;
|
||||
e->maxAcceleration = EXT5_MAX_ACCELERATION;
|
||||
e->tempControl.heatManager = EXT5_HEAT_MANAGER;
|
||||
#ifdef TEMP_PID
|
||||
e->tempControl.pidDriveMax = EXT5_PID_INTEGRAL_DRIVE_MAX;
|
||||
e->tempControl.pidDriveMin = EXT5_PID_INTEGRAL_DRIVE_MIN;
|
||||
e->tempControl.pidPGain = EXT5_PID_P;
|
||||
e->tempControl.pidIGain = EXT5_PID_I;
|
||||
e->tempControl.pidDGain = EXT5_PID_D;
|
||||
e->tempControl.pidMax = EXT5_PID_MAX;
|
||||
#endif
|
||||
e->yOffset = EXT5_Y_OFFSET;
|
||||
e->xOffset = EXT5_X_OFFSET;
|
||||
e->watchPeriod = EXT5_WATCHPERIOD;
|
||||
#if RETRACT_DURING_HEATUP
|
||||
e->waitRetractTemperature = EXT5_WAIT_RETRACT_TEMP;
|
||||
e->waitRetractUnits = EXT5_WAIT_RETRACT_UNITS;
|
||||
#endif
|
||||
e->coolerSpeed = EXT5_EXTRUDER_COOLER_SPEED;
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
e->advanceK = EXT5_ADVANCE_K;
|
||||
#endif
|
||||
e->advanceL = EXT5_ADVANCE_L;
|
||||
#endif
|
||||
#endif // NUM_EXTRUDER > 5
|
||||
extruder_select(current_extruder->id);
|
||||
update_ramps_parameter();
|
||||
initHeatedBed();
|
||||
}
|
||||
/** \brief Moves current settings to EEPROM.
|
||||
|
||||
The values the are currently set are used to fill the eeprom.*/
|
||||
void epr_data_to_eeprom(byte corrupted) {
|
||||
epr_set_long(EPR_BAUDRATE,baudrate);
|
||||
epr_set_long(EPR_MAX_INACTIVE_TIME,max_inactive_time);
|
||||
epr_set_long(EPR_STEPPER_INACTIVE_TIME,stepper_inactive_time);
|
||||
//#define EPR_ACCELERATION_TYPE 1
|
||||
epr_set_float(EPR_XAXIS_STEPS_PER_MM,axis_steps_per_unit[0]);
|
||||
epr_set_float(EPR_YAXIS_STEPS_PER_MM,axis_steps_per_unit[1]);
|
||||
epr_set_float(EPR_ZAXIS_STEPS_PER_MM,axis_steps_per_unit[2]);
|
||||
epr_set_float(EPR_X_MAX_FEEDRATE,max_feedrate[0]);
|
||||
epr_set_float(EPR_Y_MAX_FEEDRATE,max_feedrate[1]);
|
||||
epr_set_float(EPR_Z_MAX_FEEDRATE,max_feedrate[2]);
|
||||
epr_set_float(EPR_X_HOMING_FEEDRATE,homing_feedrate[0]);
|
||||
epr_set_float(EPR_Y_HOMING_FEEDRATE,homing_feedrate[1]);
|
||||
epr_set_float(EPR_Z_HOMING_FEEDRATE,homing_feedrate[2]);
|
||||
epr_set_float(EPR_MAX_JERK,printer_state.maxJerk);
|
||||
epr_set_float(EPR_MAX_ZJERK,printer_state.maxZJerk);
|
||||
#ifdef RAMP_ACCELERATION
|
||||
epr_set_float(EPR_X_MAX_ACCEL,max_acceleration_units_per_sq_second[0]);
|
||||
epr_set_float(EPR_Y_MAX_ACCEL,max_acceleration_units_per_sq_second[1]);
|
||||
epr_set_float(EPR_Z_MAX_ACCEL,max_acceleration_units_per_sq_second[2]);
|
||||
epr_set_float(EPR_X_MAX_TRAVEL_ACCEL,max_travel_acceleration_units_per_sq_second[0]);
|
||||
epr_set_float(EPR_Y_MAX_TRAVEL_ACCEL,max_travel_acceleration_units_per_sq_second[1]);
|
||||
epr_set_float(EPR_Z_MAX_TRAVEL_ACCEL,max_travel_acceleration_units_per_sq_second[2]);
|
||||
#endif
|
||||
#if USE_OPS==1
|
||||
epr_set_float(EPR_OPS_MIN_DISTANCE,printer_state.opsMinDistance);
|
||||
epr_set_byte(EPR_OPS_MODE,printer_state.opsMode);
|
||||
epr_set_float(EPR_OPS_MOVE_AFTER,printer_state.opsMoveAfter);
|
||||
epr_set_float(EPR_OPS_RETRACT_DISTANCE,printer_state.opsRetractDistance);
|
||||
epr_set_float(EPR_OPS_RETRACT_BACKLASH,printer_state.opsRetractBacklash);
|
||||
#else
|
||||
epr_set_float(EPR_OPS_MIN_DISTANCE,OPS_MIN_DISTANCE);
|
||||
epr_set_byte(EPR_OPS_MODE,OPS_MODE);
|
||||
epr_set_float(EPR_OPS_MOVE_AFTER,OPS_MOVE_AFTER);
|
||||
epr_set_float(EPR_OPS_RETRACT_DISTANCE,OPS_RETRACT_DISTANCE);
|
||||
epr_set_float(EPR_OPS_RETRACT_BACKLASH,OPS_RETRACT_BACKLASH);
|
||||
#endif
|
||||
#if HAVE_HEATED_BED
|
||||
epr_set_byte(EPR_BED_HEAT_MANAGER,heatedBedController.heatManager);
|
||||
#else
|
||||
epr_set_byte(EPR_BED_HEAT_MANAGER,HEATED_BED_HEAT_MANAGER);
|
||||
#endif
|
||||
#if defined(TEMP_PID) && HAVE_HEATED_BED
|
||||
epr_set_byte(EPR_BED_DRIVE_MAX,heatedBedController.pidDriveMax);
|
||||
epr_set_byte(EPR_BED_DRIVE_MIN,heatedBedController.pidDriveMin);
|
||||
epr_set_float(EPR_BED_PID_PGAIN,heatedBedController.pidPGain);
|
||||
epr_set_float(EPR_BED_PID_IGAIN,heatedBedController.pidIGain);
|
||||
epr_set_float(EPR_BED_PID_DGAIN,heatedBedController.pidDGain);
|
||||
epr_set_byte(EPR_BED_PID_MAX,heatedBedController.pidMax);
|
||||
#else
|
||||
epr_set_byte(EPR_BED_DRIVE_MAX,HEATED_BED_PID_INTEGRAL_DRIVE_MAX);
|
||||
epr_set_byte(EPR_BED_DRIVE_MIN,HEATED_BED_PID_INTEGRAL_DRIVE_MIN);
|
||||
epr_set_float(EPR_BED_PID_PGAIN,HEATED_BED_PID_PGAIN);
|
||||
epr_set_float(EPR_BED_PID_IGAIN,HEATED_BED_PID_IGAIN);
|
||||
epr_set_float(EPR_BED_PID_DGAIN,HEATED_BED_PID_DGAIN);
|
||||
epr_set_byte(EPR_BED_PID_MAX,HEATED_BED_PID_MAX);
|
||||
#endif
|
||||
epr_set_float(EPR_X_HOME_OFFSET,printer_state.xMin);
|
||||
epr_set_float(EPR_Y_HOME_OFFSET,printer_state.yMin);
|
||||
epr_set_float(EPR_Z_HOME_OFFSET,printer_state.zMin);
|
||||
epr_set_float(EPR_X_LENGTH,printer_state.xLength);
|
||||
epr_set_float(EPR_Y_LENGTH,printer_state.yLength);
|
||||
epr_set_float(EPR_Z_LENGTH,printer_state.zLength);
|
||||
#if ENABLE_BACKLASH_COMPENSATION
|
||||
epr_set_float(EPR_BACKLASH_X,printer_state.backlashX);
|
||||
epr_set_float(EPR_BACKLASH_Y,printer_state.backlashY);
|
||||
epr_set_float(EPR_BACKLASH_Z,printer_state.backlashZ);
|
||||
#else
|
||||
epr_set_float(EPR_BACKLASH_X,0);
|
||||
epr_set_float(EPR_BACKLASH_Y,0);
|
||||
epr_set_float(EPR_BACKLASH_Z,0);
|
||||
#endif
|
||||
|
||||
// now the extruder
|
||||
for(byte i=0;i<NUM_EXTRUDER;i++) {
|
||||
int o=i*EEPROM_EXTRUDER_LENGTH+EEPROM_EXTRUDER_OFFSET;
|
||||
Extruder *e = &extruder[i];
|
||||
epr_set_float(o+EPR_EXTRUDER_STEPS_PER_MM,e->stepsPerMM);
|
||||
epr_set_float(o+EPR_EXTRUDER_MAX_FEEDRATE,e->maxFeedrate);
|
||||
epr_set_float(o+EPR_EXTRUDER_MAX_START_FEEDRATE,e->maxStartFeedrate);
|
||||
epr_set_float(o+EPR_EXTRUDER_MAX_ACCELERATION,e->maxAcceleration);
|
||||
epr_set_byte(o+EPR_EXTRUDER_HEAT_MANAGER,e->tempControl.heatManager);
|
||||
#ifdef TEMP_PID
|
||||
epr_set_byte(o+EPR_EXTRUDER_DRIVE_MAX,e->tempControl.pidDriveMax);
|
||||
epr_set_byte(o+EPR_EXTRUDER_DRIVE_MIN,e->tempControl.pidDriveMin);
|
||||
epr_set_float(o+EPR_EXTRUDER_PID_PGAIN,e->tempControl.pidPGain);
|
||||
epr_set_float(o+EPR_EXTRUDER_PID_IGAIN,e->tempControl.pidIGain);
|
||||
epr_set_float(o+EPR_EXTRUDER_PID_DGAIN,e->tempControl.pidDGain);
|
||||
epr_set_byte(o+EPR_EXTRUDER_PID_MAX,e->tempControl.pidMax);
|
||||
#endif
|
||||
epr_set_long(o+EPR_EXTRUDER_X_OFFSET,e->xOffset);
|
||||
epr_set_long(o+EPR_EXTRUDER_Y_OFFSET,e->yOffset);
|
||||
epr_set_int(o+EPR_EXTRUDER_WATCH_PERIOD,e->watchPeriod);
|
||||
#if RETRACT_DURING_HEATUP
|
||||
epr_set_int(o+EPR_EXTRUDER_WAIT_RETRACT_TEMP,e->waitRetractTemperature);
|
||||
epr_set_int(o+EPR_EXTRUDER_WAIT_RETRACT_UNITS,e->waitRetractUnits);
|
||||
#else
|
||||
epr_set_int(o+EPR_EXTRUDER_WAIT_RETRACT_TEMP,EXT0_WAIT_RETRACT_TEMP);
|
||||
epr_set_int(o+EPR_EXTRUDER_WAIT_RETRACT_UNITS,EXT0_WAIT_RETRACT_UNITS);
|
||||
#endif
|
||||
epr_set_byte(o+EPR_EXTRUDER_COOLER_SPEED,e->coolerSpeed);
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
epr_set_float(o+EPR_EXTRUDER_ADVANCE_K,e->advanceK);
|
||||
#else
|
||||
epr_set_float(o+EPR_EXTRUDER_ADVANCE_K,0);
|
||||
#endif
|
||||
epr_set_float(o+EPR_EXTRUDER_ADVANCE_L,e->advanceL);
|
||||
#else
|
||||
epr_set_float(o+EPR_EXTRUDER_ADVANCE_K,0);
|
||||
epr_set_float(o+EPR_EXTRUDER_ADVANCE_L,0);
|
||||
#endif
|
||||
}
|
||||
if(corrupted) {
|
||||
epr_set_long(EPR_PRINTING_TIME,0);
|
||||
epr_set_float(EPR_PRINTING_DISTANCE,0);
|
||||
}
|
||||
// Save version and build checksum
|
||||
epr_set_byte(EPR_VERSION,EEPROM_PROTOCOL_VERSION);
|
||||
epr_set_byte(EPR_INTEGRITY_BYTE,epr_compute_checksum());
|
||||
}
|
||||
/** \brief Copy data from EEPROM to variables.
|
||||
*/
|
||||
void epr_eeprom_to_data() {
|
||||
byte version = epr_get_byte(EPR_VERSION); // This is the saved version. Don't copy data not set in older versions!
|
||||
baudrate = epr_get_long(EPR_BAUDRATE);
|
||||
max_inactive_time = epr_get_long(EPR_MAX_INACTIVE_TIME);
|
||||
stepper_inactive_time = epr_get_long(EPR_STEPPER_INACTIVE_TIME);
|
||||
//#define EPR_ACCELERATION_TYPE 1
|
||||
axis_steps_per_unit[0] = epr_get_float(EPR_XAXIS_STEPS_PER_MM);
|
||||
axis_steps_per_unit[1] = epr_get_float(EPR_YAXIS_STEPS_PER_MM);
|
||||
axis_steps_per_unit[2] = epr_get_float(EPR_ZAXIS_STEPS_PER_MM);
|
||||
max_feedrate[0] = epr_get_float(EPR_X_MAX_FEEDRATE);
|
||||
max_feedrate[1] = epr_get_float(EPR_Y_MAX_FEEDRATE);
|
||||
max_feedrate[2] = epr_get_float(EPR_Z_MAX_FEEDRATE);
|
||||
homing_feedrate[0] = epr_get_float(EPR_X_HOMING_FEEDRATE);
|
||||
homing_feedrate[1] = epr_get_float(EPR_Y_HOMING_FEEDRATE);
|
||||
homing_feedrate[2] = epr_get_float(EPR_Z_HOMING_FEEDRATE);
|
||||
printer_state.maxJerk = epr_get_float(EPR_MAX_JERK);
|
||||
printer_state.maxZJerk = epr_get_float(EPR_MAX_ZJERK);
|
||||
#ifdef RAMP_ACCELERATION
|
||||
max_acceleration_units_per_sq_second[0] = epr_get_float(EPR_X_MAX_ACCEL);
|
||||
max_acceleration_units_per_sq_second[1] = epr_get_float(EPR_Y_MAX_ACCEL);
|
||||
max_acceleration_units_per_sq_second[2] = epr_get_float(EPR_Z_MAX_ACCEL);
|
||||
max_travel_acceleration_units_per_sq_second[0] = epr_get_float(EPR_X_MAX_TRAVEL_ACCEL);
|
||||
max_travel_acceleration_units_per_sq_second[1] = epr_get_float(EPR_Y_MAX_TRAVEL_ACCEL);
|
||||
max_travel_acceleration_units_per_sq_second[2] = epr_get_float(EPR_Z_MAX_TRAVEL_ACCEL);
|
||||
#endif
|
||||
#if USE_OPS==1
|
||||
printer_state.opsMode = epr_get_byte(EPR_OPS_MODE);
|
||||
printer_state.opsMoveAfter = epr_get_float(EPR_OPS_MOVE_AFTER);
|
||||
printer_state.opsMinDistance = epr_get_float(EPR_OPS_MIN_DISTANCE);
|
||||
printer_state.opsRetractDistance = epr_get_float(EPR_OPS_RETRACT_DISTANCE);
|
||||
printer_state.opsRetractBacklash = epr_get_float(EPR_OPS_RETRACT_BACKLASH);
|
||||
#endif
|
||||
#if HAVE_HEATED_BED
|
||||
heatedBedController.heatManager= epr_get_byte(EPR_BED_HEAT_MANAGER);
|
||||
#ifdef TEMP_PID
|
||||
heatedBedController.pidDriveMax = epr_get_byte(EPR_BED_DRIVE_MAX);
|
||||
heatedBedController.pidDriveMin = epr_get_byte(EPR_BED_DRIVE_MIN);
|
||||
heatedBedController.pidPGain = epr_get_float(EPR_BED_PID_PGAIN);
|
||||
heatedBedController.pidIGain = epr_get_float(EPR_BED_PID_IGAIN);
|
||||
heatedBedController.pidDGain = epr_get_float(EPR_BED_PID_DGAIN);
|
||||
heatedBedController.pidMax = epr_get_byte(EPR_BED_PID_MAX);
|
||||
#endif
|
||||
#endif
|
||||
printer_state.xMin = epr_get_float(EPR_X_HOME_OFFSET);
|
||||
printer_state.yMin = epr_get_float(EPR_Y_HOME_OFFSET);
|
||||
printer_state.zMin = epr_get_float(EPR_Z_HOME_OFFSET);
|
||||
printer_state.xLength = epr_get_float(EPR_X_LENGTH);
|
||||
printer_state.yLength = epr_get_float(EPR_Y_LENGTH);
|
||||
printer_state.zLength = epr_get_float(EPR_Z_LENGTH);
|
||||
#if ENABLE_BACKLASH_COMPENSATION
|
||||
printer_state.backlashX = epr_get_float(EPR_BACKLASH_X);
|
||||
printer_state.backlashY = epr_get_float(EPR_BACKLASH_Y);
|
||||
printer_state.backlashZ = epr_get_float(EPR_BACKLASH_Z);
|
||||
#endif
|
||||
// now the extruder
|
||||
for(byte i=0;i<NUM_EXTRUDER;i++) {
|
||||
int o=i*EEPROM_EXTRUDER_LENGTH+EEPROM_EXTRUDER_OFFSET;
|
||||
Extruder *e = &extruder[i];
|
||||
e->stepsPerMM = epr_get_float(o+EPR_EXTRUDER_STEPS_PER_MM);
|
||||
e->maxFeedrate = epr_get_float(o+EPR_EXTRUDER_MAX_FEEDRATE);
|
||||
e->maxStartFeedrate = epr_get_float(o+EPR_EXTRUDER_MAX_START_FEEDRATE);
|
||||
e->maxAcceleration = epr_get_float(o+EPR_EXTRUDER_MAX_ACCELERATION);
|
||||
e->tempControl.heatManager = epr_get_byte(o+EPR_EXTRUDER_HEAT_MANAGER);
|
||||
#ifdef TEMP_PID
|
||||
e->tempControl.pidDriveMax = epr_get_byte(o+EPR_EXTRUDER_DRIVE_MAX);
|
||||
e->tempControl.pidDriveMin = epr_get_byte(o+EPR_EXTRUDER_DRIVE_MIN);
|
||||
e->tempControl.pidPGain = epr_get_float(o+EPR_EXTRUDER_PID_PGAIN);
|
||||
e->tempControl.pidIGain = epr_get_float(o+EPR_EXTRUDER_PID_IGAIN);
|
||||
e->tempControl.pidDGain = epr_get_float(o+EPR_EXTRUDER_PID_DGAIN);
|
||||
e->tempControl.pidMax = epr_get_byte(o+EPR_EXTRUDER_PID_MAX);
|
||||
#endif
|
||||
e->xOffset = epr_get_long(o+EPR_EXTRUDER_X_OFFSET);
|
||||
e->yOffset = epr_get_long(o+EPR_EXTRUDER_Y_OFFSET);
|
||||
e->watchPeriod = epr_get_int(o+EPR_EXTRUDER_WATCH_PERIOD);
|
||||
#if RETRACT_DURING_HEATUP
|
||||
e->waitRetractTemperature = epr_get_int(o+EPR_EXTRUDER_WAIT_RETRACT_TEMP);
|
||||
e->waitRetractUnits = epr_get_int(o+EPR_EXTRUDER_WAIT_RETRACT_UNITS);
|
||||
#endif
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
e->advanceK = epr_get_float(o+EPR_EXTRUDER_ADVANCE_K);
|
||||
#endif
|
||||
e->advanceL = epr_get_float(o+EPR_EXTRUDER_ADVANCE_L);
|
||||
#endif
|
||||
if(version>1)
|
||||
e->coolerSpeed = epr_get_byte(o+EPR_EXTRUDER_COOLER_SPEED);
|
||||
}
|
||||
if(version!=EEPROM_PROTOCOL_VERSION) {
|
||||
OUT_P_LN("Protocol version changed, upgrading");
|
||||
epr_data_to_eeprom(false); // Store new fields for changed version
|
||||
}
|
||||
extruder_select(current_extruder->id);
|
||||
update_ramps_parameter();
|
||||
initHeatedBed();
|
||||
}
|
||||
#endif
|
||||
void epr_init_baudrate() {
|
||||
#if EEPROM_MODE!=0
|
||||
if(epr_get_byte(EPR_MAGIC_BYTE)==EEPROM_MODE) {
|
||||
baudrate = epr_get_long(EPR_BAUDRATE);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
void epr_init() {
|
||||
#if EEPROM_MODE!=0
|
||||
byte check = epr_compute_checksum();
|
||||
byte storedcheck = epr_get_byte(EPR_INTEGRITY_BYTE);
|
||||
if(epr_get_byte(EPR_MAGIC_BYTE)==EEPROM_MODE && storedcheck==check) {
|
||||
epr_eeprom_to_data();
|
||||
} else {
|
||||
epr_set_byte(EPR_MAGIC_BYTE,EEPROM_MODE); // Make datachange permanent
|
||||
epr_data_to_eeprom(storedcheck!=check);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
/**
|
||||
*/
|
||||
void epr_update_usage() {
|
||||
#if EEPROM_MODE!=0
|
||||
if(printer_state.filamentPrinted==0) return; // No miles only enabled
|
||||
unsigned long seconds = (millis()-printer_state.msecondsPrinting)/1000;
|
||||
seconds += epr_get_long(EPR_PRINTING_TIME);
|
||||
epr_set_long(EPR_PRINTING_TIME,seconds);
|
||||
epr_set_float(EPR_PRINTING_DISTANCE,epr_get_float(EPR_PRINTING_DISTANCE)+printer_state.filamentPrinted*0.001);
|
||||
OUT_P_F_LN("Adding filament:",printer_state.filamentPrinted);
|
||||
printer_state.filamentPrinted = 0;
|
||||
printer_state.msecondsPrinting = millis();
|
||||
byte newcheck = epr_compute_checksum();
|
||||
if(newcheck!=epr_get_byte(EPR_INTEGRITY_BYTE))
|
||||
epr_set_byte(EPR_INTEGRITY_BYTE,newcheck);
|
||||
#endif
|
||||
}
|
||||
|
||||
/** \brief Writes all eeprom settings to serial console.
|
||||
|
||||
For each value stored, this function generates one line with syntax
|
||||
|
||||
EPR: pos type value description
|
||||
|
||||
With
|
||||
- pos = Position in EEPROM, the data starts.
|
||||
- type = Value type: 0 = byte, 1 = int, 2 = long, 3 = float
|
||||
- value = The value currently stored
|
||||
- description = Definition of the value
|
||||
*/
|
||||
void epr_output_settings() {
|
||||
#if EEPROM_MODE!=0
|
||||
epr_out_long(EPR_BAUDRATE,PSTR("Baudrate"));
|
||||
epr_out_float(EPR_PRINTING_DISTANCE,PSTR("Filament printed [m]"));
|
||||
epr_out_long(EPR_PRINTING_TIME,PSTR("Printer active [s]"));
|
||||
epr_out_long(EPR_MAX_INACTIVE_TIME,PSTR("Max. inactive time [ms,0=off]"));
|
||||
epr_out_long(EPR_STEPPER_INACTIVE_TIME,PSTR("Stop stepper after inactivity [ms,0=off]"));
|
||||
//#define EPR_ACCELERATION_TYPE 1
|
||||
epr_out_float(EPR_XAXIS_STEPS_PER_MM,PSTR("X-axis steps per mm"));
|
||||
epr_out_float(EPR_YAXIS_STEPS_PER_MM,PSTR("Y-axis steps per mm"));
|
||||
epr_out_float(EPR_ZAXIS_STEPS_PER_MM,PSTR("Z-axis steps per mm"));
|
||||
epr_out_float(EPR_X_MAX_FEEDRATE,PSTR("X-axis max. feedrate [mm/s]"));
|
||||
epr_out_float(EPR_Y_MAX_FEEDRATE,PSTR("Y-axis max. feedrate [mm/s]"));
|
||||
epr_out_float(EPR_Z_MAX_FEEDRATE,PSTR("Z-axis max. feedrate [mm/s]"));
|
||||
epr_out_float(EPR_X_HOMING_FEEDRATE,PSTR("X-axis homing feedrate [mm/s]"));
|
||||
epr_out_float(EPR_Y_HOMING_FEEDRATE,PSTR("Y-axis homing feedrate [mm/s]"));
|
||||
epr_out_float(EPR_Z_HOMING_FEEDRATE,PSTR("Z-axis homing feedrate [mm/s]"));
|
||||
epr_out_float(EPR_MAX_JERK,PSTR("Max. jerk [mm/s]"));
|
||||
epr_out_float(EPR_MAX_ZJERK,PSTR("Max. Z-jerk [mm/s]"));
|
||||
epr_out_float(EPR_X_HOME_OFFSET,PSTR("X home pos [mm]"));
|
||||
epr_out_float(EPR_Y_HOME_OFFSET,PSTR("Y home pos [mm]"));
|
||||
epr_out_float(EPR_Z_HOME_OFFSET,PSTR("Z home pos [mm]"));
|
||||
epr_out_float(EPR_X_LENGTH,PSTR("X max length [mm]"));
|
||||
epr_out_float(EPR_Y_LENGTH,PSTR("Y max length [mm]"));
|
||||
epr_out_float(EPR_Z_LENGTH,PSTR("Z max length [mm]"));
|
||||
#if ENABLE_BACKLASH_COMPENSATION
|
||||
epr_out_float(EPR_BACKLASH_X,PSTR("X backlash [mm]"));
|
||||
epr_out_float(EPR_BACKLASH_Y,PSTR("Y backlash [mm]"));
|
||||
epr_out_float(EPR_BACKLASH_Z,PSTR("Z backlash [mm]"));
|
||||
#endif
|
||||
|
||||
#ifdef RAMP_ACCELERATION
|
||||
//epr_out_float(EPR_X_MAX_START_SPEED,PSTR("X-axis start speed [mm/s]"));
|
||||
//epr_out_float(EPR_Y_MAX_START_SPEED,PSTR("Y-axis start speed [mm/s]"));
|
||||
//epr_out_float(EPR_Z_MAX_START_SPEED,PSTR("Z-axis start speed [mm/s]"));
|
||||
epr_out_float(EPR_X_MAX_ACCEL,PSTR("X-axis acceleration [mm/s^2]"));
|
||||
epr_out_float(EPR_Y_MAX_ACCEL,PSTR("Y-axis acceleration [mm/s^2]"));
|
||||
epr_out_float(EPR_Z_MAX_ACCEL,PSTR("Z-axis acceleration [mm/s^2]"));
|
||||
epr_out_float(EPR_X_MAX_TRAVEL_ACCEL,PSTR("X-axis travel acceleration [mm/s^2]"));
|
||||
epr_out_float(EPR_Y_MAX_TRAVEL_ACCEL,PSTR("Y-axis travel acceleration [mm/s^2]"));
|
||||
epr_out_float(EPR_Z_MAX_TRAVEL_ACCEL,PSTR("Z-axis travel acceleration [mm/s^2]"));
|
||||
#endif
|
||||
#if USE_OPS==1
|
||||
epr_out_byte(EPR_OPS_MODE,PSTR("OPS operation mode [0=Off,1=Classic,2=Fast]"));
|
||||
epr_out_float(EPR_OPS_MOVE_AFTER,PSTR("OPS move after x% retract [%]"));
|
||||
epr_out_float(EPR_OPS_MIN_DISTANCE,PSTR("OPS min. distance for fil. retraction [mm]"));
|
||||
epr_out_float(EPR_OPS_RETRACT_DISTANCE,PSTR("OPS retraction length [mm]"));
|
||||
epr_out_float(EPR_OPS_RETRACT_BACKLASH,PSTR("OPS retraction backlash [mm]"));
|
||||
#endif
|
||||
#if HAVE_HEATED_BED
|
||||
epr_out_byte(EPR_BED_HEAT_MANAGER,PSTR("Bed Heat Manager [0-2]"));
|
||||
#ifdef TEMP_PID
|
||||
epr_out_byte(EPR_BED_DRIVE_MAX,PSTR("Bed PID drive max"));
|
||||
epr_out_byte(EPR_BED_DRIVE_MIN,PSTR("Bed PID drive min"));
|
||||
epr_out_float(EPR_BED_PID_PGAIN,PSTR("Bed PID P-gain"));
|
||||
epr_out_float(EPR_BED_PID_IGAIN,PSTR("Bed PID I-gain"));
|
||||
epr_out_float(EPR_BED_PID_DGAIN,PSTR("Bed PID D-gain"));
|
||||
epr_out_byte(EPR_BED_PID_MAX,PSTR("Bed PID max value [0-255]"));
|
||||
#endif
|
||||
#endif
|
||||
// now the extruder
|
||||
for(byte i=0;i<NUM_EXTRUDER;i++) {
|
||||
int o=i*EEPROM_EXTRUDER_LENGTH+EEPROM_EXTRUDER_OFFSET;
|
||||
Extruder *e = &extruder[i];
|
||||
epr_out_float(o+EPR_EXTRUDER_STEPS_PER_MM,PSTR("steps per mm"));
|
||||
epr_out_float(o+EPR_EXTRUDER_MAX_FEEDRATE,PSTR("max. feedrate [mm/s]"));
|
||||
epr_out_float(o+EPR_EXTRUDER_MAX_START_FEEDRATE,PSTR("start feedrate [mm/s]"));
|
||||
epr_out_float(o+EPR_EXTRUDER_MAX_ACCELERATION,PSTR("acceleration [mm/s^2]"));
|
||||
epr_out_byte(o+EPR_EXTRUDER_HEAT_MANAGER,PSTR("heat manager [0-1]"));
|
||||
#ifdef TEMP_PID
|
||||
epr_out_byte(o+EPR_EXTRUDER_DRIVE_MAX,PSTR("PID drive max"));
|
||||
epr_out_byte(o+EPR_EXTRUDER_DRIVE_MIN,PSTR("PID drive min"));
|
||||
epr_out_float(o+EPR_EXTRUDER_PID_PGAIN,PSTR("PID P-gain"));
|
||||
epr_out_float(o+EPR_EXTRUDER_PID_IGAIN,PSTR("PID I-gain"));
|
||||
epr_out_float(o+EPR_EXTRUDER_PID_DGAIN,PSTR("PID D-gain"));
|
||||
epr_out_byte(o+EPR_EXTRUDER_PID_MAX,PSTR("PID max value [0-255]"));
|
||||
#endif
|
||||
epr_out_long(o+EPR_EXTRUDER_X_OFFSET,PSTR("X-offset [steps]"));
|
||||
epr_out_long(o+EPR_EXTRUDER_Y_OFFSET,PSTR("Y-offset [steps]"));
|
||||
epr_out_int(o+EPR_EXTRUDER_WATCH_PERIOD,PSTR("temp. stabilize time [s]"));
|
||||
#if RETRACT_DURING_HEATUP
|
||||
epr_out_int(o+EPR_EXTRUDER_WAIT_RETRACT_TEMP,PSTR("temp. for retraction when heating [C]"));
|
||||
epr_out_int(o+EPR_EXTRUDER_WAIT_RETRACT_UNITS,PSTR("distance to retract when heating [mm]"));
|
||||
#endif
|
||||
epr_out_byte(o+EPR_EXTRUDER_COOLER_SPEED,PSTR("extruder cooler speed [0-255]"));
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
epr_out_float(o+EPR_EXTRUDER_ADVANCE_K,PSTR("advance K [0=off]"));
|
||||
#endif
|
||||
epr_out_float(o+EPR_EXTRUDER_ADVANCE_L,PSTR("advance L [0=off]"));
|
||||
#endif
|
||||
}
|
||||
#else
|
||||
out.println_P(PSTR("No EEPROM support compiled."));
|
||||
#endif
|
||||
}
|
||||
|
||||
137
Repetier/Eeprom.h
Normal file
137
Repetier/Eeprom.h
Normal file
|
|
@ -0,0 +1,137 @@
|
|||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Repetier-Firmware is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef _EEPROM_H
|
||||
#define _EEPROM_H
|
||||
|
||||
#include <avr/eeprom.h>
|
||||
|
||||
// Id to distinguish version changes
|
||||
#define EEPROM_PROTOCOL_VERSION 2
|
||||
|
||||
/** Where to start with our datablock in memory. Can be moved if you
|
||||
have problems with other modules using the eeprom */
|
||||
|
||||
#define EEPROM_OFFSET 0
|
||||
#define EPR_MAGIC_BYTE 0
|
||||
#define EPR_ACCELERATION_TYPE 1
|
||||
#define EPR_XAXIS_STEPS_PER_MM 3
|
||||
#define EPR_YAXIS_STEPS_PER_MM 7
|
||||
#define EPR_ZAXIS_STEPS_PER_MM 11
|
||||
#define EPR_X_MAX_FEEDRATE 15
|
||||
#define EPR_Y_MAX_FEEDRATE 19
|
||||
#define EPR_Z_MAX_FEEDRATE 23
|
||||
#define EPR_X_HOMING_FEEDRATE 27
|
||||
#define EPR_Y_HOMING_FEEDRATE 31
|
||||
#define EPR_Z_HOMING_FEEDRATE 35
|
||||
#define EPR_MAX_JERK 39
|
||||
#define EPR_OPS_MIN_DISTANCE 43
|
||||
#define EPR_MAX_ZJERK 47
|
||||
#define EPR_X_MAX_ACCEL 51
|
||||
#define EPR_Y_MAX_ACCEL 55
|
||||
#define EPR_Z_MAX_ACCEL 59
|
||||
#define EPR_X_MAX_TRAVEL_ACCEL 63
|
||||
#define EPR_Y_MAX_TRAVEL_ACCEL 67
|
||||
#define EPR_Z_MAX_TRAVEL_ACCEL 71
|
||||
#define EPR_BAUDRATE 75
|
||||
#define EPR_MAX_INACTIVE_TIME 79
|
||||
#define EPR_STEPPER_INACTIVE_TIME 83
|
||||
#define EPR_OPS_RETRACT_DISTANCE 87
|
||||
#define EPR_OPS_RETRACT_BACKLASH 91
|
||||
#define EPR_EXTRUDER_SPEED 95
|
||||
#define EPR_OPS_MOVE_AFTER 99
|
||||
#define EPR_OPS_MODE 103
|
||||
#define EPR_INTEGRITY_BYTE 104 // Here the xored sum over eeprom is stored
|
||||
#define EPR_VERSION 105 // Version id for updates in EEPROM storage
|
||||
#define EPR_BED_HEAT_MANAGER 106
|
||||
#define EPR_BED_DRIVE_MAX 107
|
||||
#define EPR_BED_PID_PGAIN 108
|
||||
#define EPR_BED_PID_IGAIN 112
|
||||
#define EPR_BED_PID_DGAIN 116
|
||||
#define EPR_BED_PID_MAX 120
|
||||
#define EPR_BED_DRIVE_MIN 124
|
||||
#define EPR_PRINTING_TIME 125 // Time in seconds printing
|
||||
#define EPR_PRINTING_DISTANCE 129 // Filament length printed
|
||||
#define EPR_X_HOME_OFFSET 133
|
||||
#define EPR_Y_HOME_OFFSET 137
|
||||
#define EPR_Z_HOME_OFFSET 141
|
||||
#define EPR_X_LENGTH 145
|
||||
#define EPR_Y_LENGTH 149
|
||||
#define EPR_Z_LENGTH 153
|
||||
#define EPR_BACKLASH_X 157
|
||||
#define EPR_BACKLASH_Y 161
|
||||
#define EPR_BACKLASH_Z 165
|
||||
|
||||
#define EEPROM_EXTRUDER_OFFSET 200
|
||||
// bytes per extruder needed, leave some space for future development
|
||||
#define EEPROM_EXTRUDER_LENGTH 100
|
||||
// Extruder positions relative to extruder start
|
||||
#define EPR_EXTRUDER_STEPS_PER_MM 0
|
||||
#define EPR_EXTRUDER_MAX_FEEDRATE 4
|
||||
// Feedrate from halted extruder in mm/s
|
||||
#define EPR_EXTRUDER_MAX_START_FEEDRATE 8
|
||||
// Acceleration in mm/s^2
|
||||
#define EPR_EXTRUDER_MAX_ACCELERATION 12
|
||||
#define EPR_EXTRUDER_HEAT_MANAGER 16
|
||||
#define EPR_EXTRUDER_DRIVE_MAX 17
|
||||
#define EPR_EXTRUDER_PID_PGAIN 18
|
||||
#define EPR_EXTRUDER_PID_IGAIN 22
|
||||
#define EPR_EXTRUDER_PID_DGAIN 26
|
||||
#define EPR_EXTRUDER_PID_MAX 30
|
||||
#define EPR_EXTRUDER_X_OFFSET 31
|
||||
#define EPR_EXTRUDER_Y_OFFSET 35
|
||||
#define EPR_EXTRUDER_WATCH_PERIOD 39
|
||||
#define EPR_EXTRUDER_ADVANCE_K 41
|
||||
#define EPR_EXTRUDER_DRIVE_MIN 45
|
||||
#define EPR_EXTRUDER_ADVANCE_L 46
|
||||
#define EPR_EXTRUDER_WAIT_RETRACT_TEMP 50
|
||||
#define EPR_EXTRUDER_WAIT_RETRACT_UNITS 52
|
||||
#define EPR_EXTRUDER_COOLER_SPEED 54
|
||||
#if EEPROM_MODE!=0
|
||||
|
||||
extern inline void epr_set_byte(uint pos,byte value);
|
||||
extern inline void epr_set_int(uint pos,int value);
|
||||
extern inline void epr_set_long(uint pos,long value);
|
||||
extern inline void epr_set_float(uint pos,float value);
|
||||
extern void epr_data_to_eeprom(byte corrupted);
|
||||
extern void epr_eeprom_to_data();
|
||||
extern void epr_eeprom_reset();
|
||||
|
||||
inline byte epr_get_byte(uint pos) {
|
||||
return eeprom_read_byte ((unsigned char *)(EEPROM_OFFSET+pos));
|
||||
}
|
||||
inline int epr_get_int(uint pos) {
|
||||
return eeprom_read_word((unsigned int *)(EEPROM_OFFSET+pos));
|
||||
}
|
||||
inline long epr_get_long(uint pos) {
|
||||
return eeprom_read_dword((unsigned long*)(EEPROM_OFFSET+pos));
|
||||
}
|
||||
inline float epr_get_float(uint pos) {
|
||||
float v;
|
||||
eeprom_read_block(&v,(void *)(EEPROM_OFFSET+pos),4); // newer gcc have eeprom_read_block but not arduino 22
|
||||
return v;
|
||||
}
|
||||
#endif
|
||||
|
||||
extern void epr_output_settings();
|
||||
extern void epr_update(GCode *com);
|
||||
extern void epr_init();
|
||||
extern void epr_init_baudrate();
|
||||
extern void epr_update_usage();
|
||||
#endif
|
||||
|
||||
1082
Repetier/Extruder.cpp
Normal file
1082
Repetier/Extruder.cpp
Normal file
File diff suppressed because it is too large
Load diff
418
Repetier/FatStructs.h
Normal file
418
Repetier/FatStructs.h
Normal file
|
|
@ -0,0 +1,418 @@
|
|||
/* Arduino SdFat Library
|
||||
* Copyright (C) 2009 by William Greiman
|
||||
*
|
||||
* This file is part of the Arduino SdFat Library
|
||||
*
|
||||
* This Library is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This Library is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with the Arduino SdFat Library. If not, see
|
||||
* <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#ifndef FatStructs_h
|
||||
#define FatStructs_h
|
||||
/**
|
||||
* \file
|
||||
* FAT file structures
|
||||
*/
|
||||
/*
|
||||
* mostly from Microsoft document fatgen103.doc
|
||||
* http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
|
||||
*/
|
||||
//------------------------------------------------------------------------------
|
||||
/** Value for byte 510 of boot block or MBR */
|
||||
uint8_t const BOOTSIG0 = 0X55;
|
||||
/** Value for byte 511 of boot block or MBR */
|
||||
uint8_t const BOOTSIG1 = 0XAA;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct partitionTable
|
||||
* \brief MBR partition table entry
|
||||
*
|
||||
* A partition table entry for a MBR formatted storage device.
|
||||
* The MBR partition table has four entries.
|
||||
*/
|
||||
struct partitionTable {
|
||||
/**
|
||||
* Boot Indicator . Indicates whether the volume is the active
|
||||
* partition. Legal values include: 0X00. Do not use for booting.
|
||||
* 0X80 Active partition.
|
||||
*/
|
||||
uint8_t boot;
|
||||
/**
|
||||
* Head part of Cylinder-head-sector address of the first block in
|
||||
* the partition. Legal values are 0-255. Only used in old PC BIOS.
|
||||
*/
|
||||
uint8_t beginHead;
|
||||
/**
|
||||
* Sector part of Cylinder-head-sector address of the first block in
|
||||
* the partition. Legal values are 1-63. Only used in old PC BIOS.
|
||||
*/
|
||||
unsigned beginSector : 6;
|
||||
/** High bits cylinder for first block in partition. */
|
||||
unsigned beginCylinderHigh : 2;
|
||||
/**
|
||||
* Combine beginCylinderLow with beginCylinderHigh. Legal values
|
||||
* are 0-1023. Only used in old PC BIOS.
|
||||
*/
|
||||
uint8_t beginCylinderLow;
|
||||
/**
|
||||
* Partition type. See defines that begin with PART_TYPE_ for
|
||||
* some Microsoft partition types.
|
||||
*/
|
||||
uint8_t type;
|
||||
/**
|
||||
* head part of cylinder-head-sector address of the last sector in the
|
||||
* partition. Legal values are 0-255. Only used in old PC BIOS.
|
||||
*/
|
||||
uint8_t endHead;
|
||||
/**
|
||||
* Sector part of cylinder-head-sector address of the last sector in
|
||||
* the partition. Legal values are 1-63. Only used in old PC BIOS.
|
||||
*/
|
||||
unsigned endSector : 6;
|
||||
/** High bits of end cylinder */
|
||||
unsigned endCylinderHigh : 2;
|
||||
/**
|
||||
* Combine endCylinderLow with endCylinderHigh. Legal values
|
||||
* are 0-1023. Only used in old PC BIOS.
|
||||
*/
|
||||
uint8_t endCylinderLow;
|
||||
/** Logical block address of the first block in the partition. */
|
||||
uint32_t firstSector;
|
||||
/** Length of the partition, in blocks. */
|
||||
uint32_t totalSectors;
|
||||
};
|
||||
/** Type name for partitionTable */
|
||||
typedef struct partitionTable part_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct masterBootRecord
|
||||
*
|
||||
* \brief Master Boot Record
|
||||
*
|
||||
* The first block of a storage device that is formatted with a MBR.
|
||||
*/
|
||||
struct masterBootRecord {
|
||||
/** Code Area for master boot program. */
|
||||
uint8_t codeArea[440];
|
||||
/** Optional WindowsNT disk signature. May contain more boot code. */
|
||||
uint32_t diskSignature;
|
||||
/** Usually zero but may be more boot code. */
|
||||
uint16_t usuallyZero;
|
||||
/** Partition tables. */
|
||||
part_t part[4];
|
||||
/** First MBR signature byte. Must be 0X55 */
|
||||
uint8_t mbrSig0;
|
||||
/** Second MBR signature byte. Must be 0XAA */
|
||||
uint8_t mbrSig1;
|
||||
};
|
||||
/** Type name for masterBootRecord */
|
||||
typedef struct masterBootRecord mbr_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct biosParmBlock
|
||||
*
|
||||
* \brief BIOS parameter block
|
||||
*
|
||||
* The BIOS parameter block describes the physical layout of a FAT volume.
|
||||
*/
|
||||
struct biosParmBlock {
|
||||
/**
|
||||
* Count of bytes per sector. This value may take on only the
|
||||
* following values: 512, 1024, 2048 or 4096
|
||||
*/
|
||||
uint16_t bytesPerSector;
|
||||
/**
|
||||
* Number of sectors per allocation unit. This value must be a
|
||||
* power of 2 that is greater than 0. The legal values are
|
||||
* 1, 2, 4, 8, 16, 32, 64, and 128.
|
||||
*/
|
||||
uint8_t sectorsPerCluster;
|
||||
/**
|
||||
* Number of sectors before the first FAT.
|
||||
* This value must not be zero.
|
||||
*/
|
||||
uint16_t reservedSectorCount;
|
||||
/** The count of FAT data structures on the volume. This field should
|
||||
* always contain the value 2 for any FAT volume of any type.
|
||||
*/
|
||||
uint8_t fatCount;
|
||||
/**
|
||||
* For FAT12 and FAT16 volumes, this field contains the count of
|
||||
* 32-byte directory entries in the root directory. For FAT32 volumes,
|
||||
* this field must be set to 0. For FAT12 and FAT16 volumes, this
|
||||
* value should always specify a count that when multiplied by 32
|
||||
* results in a multiple of bytesPerSector. FAT16 volumes should
|
||||
* use the value 512.
|
||||
*/
|
||||
uint16_t rootDirEntryCount;
|
||||
/**
|
||||
* This field is the old 16-bit total count of sectors on the volume.
|
||||
* This count includes the count of all sectors in all four regions
|
||||
* of the volume. This field can be 0; if it is 0, then totalSectors32
|
||||
* must be non-zero. For FAT32 volumes, this field must be 0. For
|
||||
* FAT12 and FAT16 volumes, this field contains the sector count, and
|
||||
* totalSectors32 is 0 if the total sector count fits
|
||||
* (is less than 0x10000).
|
||||
*/
|
||||
uint16_t totalSectors16;
|
||||
/**
|
||||
* This dates back to the old MS-DOS 1.x media determination and is
|
||||
* no longer usually used for anything. 0xF8 is the standard value
|
||||
* for fixed (non-removable) media. For removable media, 0xF0 is
|
||||
* frequently used. Legal values are 0xF0 or 0xF8-0xFF.
|
||||
*/
|
||||
uint8_t mediaType;
|
||||
/**
|
||||
* Count of sectors occupied by one FAT on FAT12/FAT16 volumes.
|
||||
* On FAT32 volumes this field must be 0, and sectorsPerFat32
|
||||
* contains the FAT size count.
|
||||
*/
|
||||
uint16_t sectorsPerFat16;
|
||||
/** Sectors per track for interrupt 0x13. Not used otherwise. */
|
||||
uint16_t sectorsPerTrtack;
|
||||
/** Number of heads for interrupt 0x13. Not used otherwise. */
|
||||
uint16_t headCount;
|
||||
/**
|
||||
* Count of hidden sectors preceding the partition that contains this
|
||||
* FAT volume. This field is generally only relevant for media
|
||||
* visible on interrupt 0x13.
|
||||
*/
|
||||
uint32_t hidddenSectors;
|
||||
/**
|
||||
* This field is the new 32-bit total count of sectors on the volume.
|
||||
* This count includes the count of all sectors in all four regions
|
||||
* of the volume. This field can be 0; if it is 0, then
|
||||
* totalSectors16 must be non-zero.
|
||||
*/
|
||||
uint32_t totalSectors32;
|
||||
/**
|
||||
* Count of sectors occupied by one FAT on FAT32 volumes.
|
||||
*/
|
||||
uint32_t sectorsPerFat32;
|
||||
/**
|
||||
* This field is only defined for FAT32 media and does not exist on
|
||||
* FAT12 and FAT16 media.
|
||||
* Bits 0-3 -- Zero-based number of active FAT.
|
||||
* Only valid if mirroring is disabled.
|
||||
* Bits 4-6 -- Reserved.
|
||||
* Bit 7 -- 0 means the FAT is mirrored at runtime into all FATs.
|
||||
* -- 1 means only one FAT is active; it is the one referenced in bits 0-3.
|
||||
* Bits 8-15 -- Reserved.
|
||||
*/
|
||||
uint16_t fat32Flags;
|
||||
/**
|
||||
* FAT32 version. High byte is major revision number.
|
||||
* Low byte is minor revision number. Only 0.0 define.
|
||||
*/
|
||||
uint16_t fat32Version;
|
||||
/**
|
||||
* Cluster number of the first cluster of the root directory for FAT32.
|
||||
* This usually 2 but not required to be 2.
|
||||
*/
|
||||
uint32_t fat32RootCluster;
|
||||
/**
|
||||
* Sector number of FSINFO structure in the reserved area of the
|
||||
* FAT32 volume. Usually 1.
|
||||
*/
|
||||
uint16_t fat32FSInfo;
|
||||
/**
|
||||
* If non-zero, indicates the sector number in the reserved area
|
||||
* of the volume of a copy of the boot record. Usually 6.
|
||||
* No value other than 6 is recommended.
|
||||
*/
|
||||
uint16_t fat32BackBootBlock;
|
||||
/**
|
||||
* Reserved for future expansion. Code that formats FAT32 volumes
|
||||
* should always set all of the bytes of this field to 0.
|
||||
*/
|
||||
uint8_t fat32Reserved[12];
|
||||
};
|
||||
/** Type name for biosParmBlock */
|
||||
typedef struct biosParmBlock bpb_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct fat32BootSector
|
||||
*
|
||||
* \brief Boot sector for a FAT16 or FAT32 volume.
|
||||
*
|
||||
*/
|
||||
struct fat32BootSector {
|
||||
/** X86 jmp to boot program */
|
||||
uint8_t jmpToBootCode[3];
|
||||
/** informational only - don't depend on it */
|
||||
char oemName[8];
|
||||
/** BIOS Parameter Block */
|
||||
bpb_t bpb;
|
||||
/** for int0x13 use value 0X80 for hard drive */
|
||||
uint8_t driveNumber;
|
||||
/** used by Windows NT - should be zero for FAT */
|
||||
uint8_t reserved1;
|
||||
/** 0X29 if next three fields are valid */
|
||||
uint8_t bootSignature;
|
||||
/** usually generated by combining date and time */
|
||||
uint32_t volumeSerialNumber;
|
||||
/** should match volume label in root dir */
|
||||
char volumeLabel[11];
|
||||
/** informational only - don't depend on it */
|
||||
char fileSystemType[8];
|
||||
/** X86 boot code */
|
||||
uint8_t bootCode[420];
|
||||
/** must be 0X55 */
|
||||
uint8_t bootSectorSig0;
|
||||
/** must be 0XAA */
|
||||
uint8_t bootSectorSig1;
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
// End Of Chain values for FAT entries
|
||||
/** FAT16 end of chain value used by Microsoft. */
|
||||
uint16_t const FAT16EOC = 0XFFFF;
|
||||
/** Minimum value for FAT16 EOC. Use to test for EOC. */
|
||||
uint16_t const FAT16EOC_MIN = 0XFFF8;
|
||||
/** FAT32 end of chain value used by Microsoft. */
|
||||
uint32_t const FAT32EOC = 0X0FFFFFFF;
|
||||
/** Minimum value for FAT32 EOC. Use to test for EOC. */
|
||||
uint32_t const FAT32EOC_MIN = 0X0FFFFFF8;
|
||||
/** Mask a for FAT32 entry. Entries are 28 bits. */
|
||||
uint32_t const FAT32MASK = 0X0FFFFFFF;
|
||||
|
||||
/** Type name for fat32BootSector */
|
||||
typedef struct fat32BootSector fbs_t;
|
||||
//------------------------------------------------------------------------------
|
||||
/**
|
||||
* \struct directoryEntry
|
||||
* \brief FAT short directory entry
|
||||
*
|
||||
* Short means short 8.3 name, not the entry size.
|
||||
*
|
||||
* Date Format. A FAT directory entry date stamp is a 16-bit field that is
|
||||
* basically a date relative to the MS-DOS epoch of 01/01/1980. Here is the
|
||||
* format (bit 0 is the LSB of the 16-bit word, bit 15 is the MSB of the
|
||||
* 16-bit word):
|
||||
*
|
||||
* Bits 9-15: Count of years from 1980, valid value range 0-127
|
||||
* inclusive (1980-2107).
|
||||
*
|
||||
* Bits 5-8: Month of year, 1 = January, valid value range 1-12 inclusive.
|
||||
*
|
||||
* Bits 0-4: Day of month, valid value range 1-31 inclusive.
|
||||
*
|
||||
* Time Format. A FAT directory entry time stamp is a 16-bit field that has
|
||||
* a granularity of 2 seconds. Here is the format (bit 0 is the LSB of the
|
||||
* 16-bit word, bit 15 is the MSB of the 16-bit word).
|
||||
*
|
||||
* Bits 11-15: Hours, valid value range 0-23 inclusive.
|
||||
*
|
||||
* Bits 5-10: Minutes, valid value range 0-59 inclusive.
|
||||
*
|
||||
* Bits 0-4: 2-second count, valid value range 0-29 inclusive (0 - 58 seconds).
|
||||
*
|
||||
* The valid time range is from Midnight 00:00:00 to 23:59:58.
|
||||
*/
|
||||
struct directoryEntry {
|
||||
/**
|
||||
* Short 8.3 name.
|
||||
* The first eight bytes contain the file name with blank fill.
|
||||
* The last three bytes contain the file extension with blank fill.
|
||||
*/
|
||||
uint8_t name[11];
|
||||
/** Entry attributes.
|
||||
*
|
||||
* The upper two bits of the attribute byte are reserved and should
|
||||
* always be set to 0 when a file is created and never modified or
|
||||
* looked at after that. See defines that begin with DIR_ATT_.
|
||||
*/
|
||||
uint8_t attributes;
|
||||
/**
|
||||
* Reserved for use by Windows NT. Set value to 0 when a file is
|
||||
* created and never modify or look at it after that.
|
||||
*/
|
||||
uint8_t reservedNT;
|
||||
/**
|
||||
* The granularity of the seconds part of creationTime is 2 seconds
|
||||
* so this field is a count of tenths of a second and its valid
|
||||
* value range is 0-199 inclusive. (WHG note - seems to be hundredths)
|
||||
*/
|
||||
uint8_t creationTimeTenths;
|
||||
/** Time file was created. */
|
||||
uint16_t creationTime;
|
||||
/** Date file was created. */
|
||||
uint16_t creationDate;
|
||||
/**
|
||||
* Last access date. Note that there is no last access time, only
|
||||
* a date. This is the date of last read or write. In the case of
|
||||
* a write, this should be set to the same date as lastWriteDate.
|
||||
*/
|
||||
uint16_t lastAccessDate;
|
||||
/**
|
||||
* High word of this entry's first cluster number (always 0 for a
|
||||
* FAT12 or FAT16 volume).
|
||||
*/
|
||||
uint16_t firstClusterHigh;
|
||||
/** Time of last write. File creation is considered a write. */
|
||||
uint16_t lastWriteTime;
|
||||
/** Date of last write. File creation is considered a write. */
|
||||
uint16_t lastWriteDate;
|
||||
/** Low word of this entry's first cluster number. */
|
||||
uint16_t firstClusterLow;
|
||||
/** 32-bit unsigned holding this file's size in bytes. */
|
||||
uint32_t fileSize;
|
||||
};
|
||||
//------------------------------------------------------------------------------
|
||||
// Definitions for directory entries
|
||||
//
|
||||
/** Type name for directoryEntry */
|
||||
typedef struct directoryEntry dir_t;
|
||||
/** escape for name[0] = 0XE5 */
|
||||
uint8_t const DIR_NAME_0XE5 = 0X05;
|
||||
/** name[0] value for entry that is free after being "deleted" */
|
||||
uint8_t const DIR_NAME_DELETED = 0XE5;
|
||||
/** name[0] value for entry that is free and no allocated entries follow */
|
||||
uint8_t const DIR_NAME_FREE = 0X00;
|
||||
/** file is read-only */
|
||||
uint8_t const DIR_ATT_READ_ONLY = 0X01;
|
||||
/** File should hidden in directory listings */
|
||||
uint8_t const DIR_ATT_HIDDEN = 0X02;
|
||||
/** Entry is for a system file */
|
||||
uint8_t const DIR_ATT_SYSTEM = 0X04;
|
||||
/** Directory entry contains the volume label */
|
||||
uint8_t const DIR_ATT_VOLUME_ID = 0X08;
|
||||
/** Entry is for a directory */
|
||||
uint8_t const DIR_ATT_DIRECTORY = 0X10;
|
||||
/** Old DOS archive bit for backup support */
|
||||
uint8_t const DIR_ATT_ARCHIVE = 0X20;
|
||||
/** Test value for long name entry. Test is
|
||||
(d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME. */
|
||||
uint8_t const DIR_ATT_LONG_NAME = 0X0F;
|
||||
/** Test mask for long name entry */
|
||||
uint8_t const DIR_ATT_LONG_NAME_MASK = 0X3F;
|
||||
/** defined attribute bits */
|
||||
uint8_t const DIR_ATT_DEFINED_BITS = 0X3F;
|
||||
/** Directory entry is part of a long name */
|
||||
static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) {
|
||||
return (dir->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME;
|
||||
}
|
||||
/** Mask for file/subdirectory tests */
|
||||
uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
|
||||
/** Directory entry is for a file */
|
||||
static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
|
||||
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0;
|
||||
}
|
||||
/** Directory entry is for a subdirectory */
|
||||
static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
|
||||
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY;
|
||||
}
|
||||
/** Directory entry is for a file or subdirectory */
|
||||
static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) {
|
||||
return (dir->attributes & DIR_ATT_VOLUME_ID) == 0;
|
||||
}
|
||||
#endif // FatStructs_h
|
||||
2674
Repetier/Repetier.ino
Normal file
2674
Repetier/Repetier.ino
Normal file
File diff suppressed because it is too large
Load diff
983
Repetier/Reptier.h
Normal file
983
Repetier/Reptier.h
Normal file
|
|
@ -0,0 +1,983 @@
|
|||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Repetier-Firmware is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Foobar. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
*/
|
||||
|
||||
#ifndef _REPETIER_H
|
||||
#define _REPETIER_H
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
#define REPETIER_VERSION "0.80"
|
||||
|
||||
// ##########################################################################################
|
||||
// ## Debug configuration ##
|
||||
// ##########################################################################################
|
||||
|
||||
/** Uncomment, to see detailed data for every move. Only for debugging purposes! */
|
||||
//#define DEBUG_QUEUE_MOVE
|
||||
/** Allows M111 to set bit 5 (16) which disables all commands except M111. This can be used
|
||||
to test your data througput or search for communication problems. */
|
||||
#define INCLUDE_DEBUG_COMMUNICATION
|
||||
/** Allows M111 so set bit 6 (32) which disables moves, at the first tried step. In combination
|
||||
with a dry run, you can test the speed of path computations, which are still performed. */
|
||||
//#define INCLUDE_DEBUG_NO_MOVE
|
||||
/** Writes the free RAM to output, if it is less then at the last test. Should always return
|
||||
values >500 for safety, since it doesn't catch every function call. Nice to tweak cache
|
||||
usage or for seraching for memory induced errors. Switch it off for production, it costs execution time. */
|
||||
//#define DEBUG_FREE_MEMORY
|
||||
//#define DEBUG_ADVANCE
|
||||
/** \brief print ops related debug info. */
|
||||
//#define DEBUG_OPS
|
||||
/** If enabled, writes the created generic table to serial port at startup. */
|
||||
//#define DEBUG_GENERIC
|
||||
/** If enabled, steps to move and moved steps are compared. */
|
||||
//#define DEBUG_STEPCOUNT
|
||||
// Uncomment the following line to enable debugging. You can better control debugging below the following line
|
||||
//#define DEBUG
|
||||
|
||||
|
||||
// Uncomment if no analyzer is connected
|
||||
//#define ANALYZER
|
||||
// Channel->pin assignments
|
||||
#define ANALYZER_CH0 63 // New move
|
||||
#define ANALYZER_CH1 40 // Step loop
|
||||
#define ANALYZER_CH2 53 // X Step
|
||||
#define ANALYZER_CH3 65 // Y Step
|
||||
#define ANALYZER_CH4 59 // X Direction
|
||||
#define ANALYZER_CH5 64 // Y Direction
|
||||
#define ANALYZER_CH6 58 // xsig
|
||||
#define ANALYZER_CH7 57 // ysig
|
||||
|
||||
#ifdef ANALYZER
|
||||
#define ANALYZER_ON(a) {WRITE(a,HIGH);}
|
||||
#define ANALYZER_OFF(a) {WRITE(a,LOW);}
|
||||
#else
|
||||
#define ANALYZER_ON(a)
|
||||
#define ANALYZER_OFF(a)
|
||||
#endif
|
||||
|
||||
|
||||
// Bits of the ADC converter
|
||||
#define ANALOG_INPUT_BITS 10
|
||||
// Build median from 2^ANALOG_INPUT_SAMPLE samples
|
||||
#define ANALOG_INPUT_SAMPLE 5
|
||||
#define ANALOG_REF_AREF 0
|
||||
#define ANALOG_REF_AVCC _BV(REFS0)
|
||||
#define ANALOG_REF_INT_1_1 _BV(REFS1)
|
||||
#define ANALOG_REF_INT_2_56 _BV(REFS0) | _BV(REFS1)
|
||||
|
||||
// MS1 MS2 Stepper Driver Microstepping mode table
|
||||
#define MICROSTEP1 LOW,LOW
|
||||
#define MICROSTEP2 HIGH,LOW
|
||||
#define MICROSTEP4 LOW,HIGH
|
||||
#define MICROSTEP8 HIGH,HIGH
|
||||
#define MICROSTEP16 HIGH,HIGH
|
||||
|
||||
#define NEW_XY_GANTRY
|
||||
|
||||
#include "Configuration.h"
|
||||
#if DRIVE_SYSTEM==1 || DRIVE_SYSTEM==2
|
||||
#define XY_GANTRY
|
||||
#endif
|
||||
|
||||
//Step to split a cirrcle in small Lines
|
||||
#ifndef MM_PER_ARC_SEGMENT
|
||||
#define MM_PER_ARC_SEGMENT 1
|
||||
#define MM_PER_ARC_SEGMENT_BIG 3
|
||||
#else
|
||||
#define MM_PER_ARC_SEGMENT_BIG MM_PER_ARC_SEGMENT
|
||||
#endif
|
||||
//After this count of steps a new SIN / COS caluclation is startet to correct the circle interpolation
|
||||
#define N_ARC_CORRECTION 25
|
||||
#if CPU_ARCH==ARCH_AVR
|
||||
#include <avr/io.h>
|
||||
#else
|
||||
#define PROGMEM
|
||||
#define PGM_P const char *
|
||||
#define PSTR(s) s
|
||||
#define pgm_read_byte_near(x) (*(char*)x)
|
||||
#define pgm_read_byte(x) (*(char*)x)
|
||||
#endif
|
||||
|
||||
#define KOMMA
|
||||
#if NUM_EXTRUDER>0 && EXT0_TEMPSENSOR_TYPE<100
|
||||
#define EXT0_ANALOG_INPUTS 1
|
||||
#define EXT0_SENSOR_INDEX 0
|
||||
#define EXT0_ANALOG_CHANNEL EXT0_TEMPSENSOR_PIN
|
||||
#undef KOMMA
|
||||
#define KOMMA ,
|
||||
#else
|
||||
#define EXT0_ANALOG_INPUTS 0
|
||||
#define EXT0_SENSOR_INDEX EXT0_TEMPSENSOR_PIN
|
||||
#define EXT0_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#if NUM_EXTRUDER>1 && EXT1_TEMPSENSOR_TYPE<100
|
||||
#define EXT1_ANALOG_INPUTS 1
|
||||
#define EXT1_SENSOR_INDEX EXT0_ANALOG_INPUTS
|
||||
#define EXT1_ANALOG_CHANNEL KOMMA EXT1_TEMPSENSOR_PIN
|
||||
#undef KOMMA
|
||||
#define KOMMA ,
|
||||
#else
|
||||
#define EXT1_ANALOG_INPUTS 0
|
||||
#define EXT1_SENSOR_INDEX EXT1_TEMPSENSOR_PIN
|
||||
#define EXT1_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#if NUM_EXTRUDER>2 && EXT2_TEMPSENSOR_TYPE<100
|
||||
#define EXT2_ANALOG_INPUTS 1
|
||||
#define EXT2_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS
|
||||
#define EXT2_ANALOG_CHANNEL KOMMA EXT2_TEMPSENSOR_PIN
|
||||
#undef KOMMA
|
||||
#define KOMMA ,
|
||||
#else
|
||||
#define EXT2_ANALOG_INPUTS 0
|
||||
#define EXT2_SENSOR_INDEX EXT2_TEMPSENSOR_PIN
|
||||
#define EXT2_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#if NUM_EXTRUDER>3 && EXT3_TEMPSENSOR_TYPE<100
|
||||
#define EXT3_ANALOG_INPUTS 1
|
||||
#define EXT3_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS
|
||||
#define EXT3_ANALOG_CHANNEL KOMMA EXT3_TEMPSENSOR_PIN
|
||||
#undef KOMMA
|
||||
#define KOMMA ,
|
||||
#else
|
||||
#define EXT3_ANALOG_INPUTS 0
|
||||
#define EXT3_SENSOR_INDEX EXT3_TEMPSENSOR_PIN
|
||||
#define EXT3_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#if NUM_EXTRUDER>4 && EXT4_TEMPSENSOR_TYPE<100
|
||||
#define EXT4_ANALOG_INPUTS 1
|
||||
#define EXT4_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS
|
||||
#define EXT4_ANALOG_CHANNEL KOMMA EXT4_TEMPSENSOR_PIN
|
||||
#undef KOMMA
|
||||
#define KOMMA ,
|
||||
#else
|
||||
#define EXT4_ANALOG_INPUTS 0
|
||||
#define EXT4_SENSOR_INDEX EXT4_TEMPSENSOR_PIN
|
||||
#define EXT4_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#if NUM_EXTRUDER>5 && EXT5_TEMPSENSOR_TYPE<100
|
||||
#define EXT5_ANALOG_INPUTS 1
|
||||
#define EXT5_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS
|
||||
#define EXT5_ANALOG_CHANNEL KOMMA EXT5_TEMPSENSOR_PIN
|
||||
#undef KOMMA
|
||||
#define KOMMA ,
|
||||
#else
|
||||
#define EXT5_ANALOG_INPUTS 0
|
||||
#define EXT5_SENSOR_INDEX EXT5_TEMPSENSOR_PIN
|
||||
#define EXT5_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#if HAVE_HEATED_BED==true && HEATED_BED_SENSOR_TYPE<100
|
||||
#define BED_ANALOG_INPUTS 1
|
||||
#define BED_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS
|
||||
#define BED_ANALOG_CHANNEL KOMMA HEATED_BED_SENSOR_PIN
|
||||
#undef KOMMA
|
||||
#define KOMMA ,
|
||||
#else
|
||||
#define BED_ANALOG_INPUTS 0
|
||||
#define BED_SENSOR_INDEX HEATED_BED_SENSOR_PIN
|
||||
#define BED_ANALOG_CHANNEL
|
||||
#endif
|
||||
|
||||
#ifndef DEBUG_FREE_MEMORY
|
||||
#define DEBUG_MEMORY
|
||||
#else
|
||||
#define DEBUG_MEMORY check_mem();
|
||||
#endif
|
||||
|
||||
/** \brief number of analog input signals. Normally 1 for each temperature sensor */
|
||||
#define ANALOG_INPUTS (EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS+BED_ANALOG_INPUTS)
|
||||
#if ANALOG_INPUTS>0
|
||||
/** Channels are the MUX-part of ADMUX register */
|
||||
#define ANALOG_INPUT_CHANNELS {EXT0_ANALOG_CHANNEL EXT1_ANALOG_CHANNEL EXT2_ANALOG_CHANNEL EXT3_ANALOG_CHANNEL EXT4_ANALOG_CHANNEL EXT5_ANALOG_CHANNEL BED_ANALOG_CHANNEL}
|
||||
#endif
|
||||
#define ANALOG_PRESCALER _BV(ADPS0)|_BV(ADPS1)|_BV(ADPS2)
|
||||
|
||||
#if MOTHERBOARD==8 || MOTHERBOARD==9 || CPU_ARCH!=ARCH_AVR
|
||||
#define EXTERNALSERIAL
|
||||
#endif
|
||||
//#define EXTERNALSERIAL // Force using arduino serial
|
||||
#ifndef EXTERNALSERIAL
|
||||
#define HardwareSerial_h // Don't use standard serial console
|
||||
#endif
|
||||
#include <inttypes.h>
|
||||
#include "Print.h"
|
||||
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WProgram.h"
|
||||
#define COMPAT_PRE1
|
||||
#endif
|
||||
#include "gcode.h"
|
||||
#if CPU_ARCH==ARCH_AVR
|
||||
#include "fastio.h"
|
||||
#else
|
||||
#define READ(IO) digitalRead(IO)
|
||||
#define WRITE(IO, v) digitalWrite(IO, v)
|
||||
#define SET_INPUT(IO) pinMode(IO, INPUT)
|
||||
#define SET_OUTPUT(IO) pinMode(IO, OUTPUT)
|
||||
#endif
|
||||
#define SD_MAX_FOLDER_DEPTH 2
|
||||
|
||||
#include "ui.h"
|
||||
|
||||
#ifndef SDSUPPORT
|
||||
#define SDSUPPORT false
|
||||
#endif
|
||||
#if SDSUPPORT
|
||||
#include "SdFat.h"
|
||||
#endif
|
||||
#ifndef SDSUPPORT
|
||||
#define SDSUPPORT false
|
||||
#endif
|
||||
#if SDSUPPORT
|
||||
#include "SdFat.h"
|
||||
#endif
|
||||
|
||||
#if ENABLE_BACKLASH_COMPENSATION && DRIVE_SYSTEM!=0
|
||||
#undef ENABLE_BACKLASH_COMPENSATION
|
||||
#define ENABLE_BACKLASH_COMPENSATION false
|
||||
#endif
|
||||
|
||||
#define uint uint16_t
|
||||
#define uint8 uint8_t
|
||||
#define int8 int8_t
|
||||
#define uint32 uint32_t
|
||||
#define int32 int32_t
|
||||
|
||||
/*#if MOTHERBOARD==6 || MOTHERBOARD==62 || MOTHERBOARD==7
|
||||
#if MOTHERBOARD!=7
|
||||
#define SIMULATE_PWM
|
||||
#endif
|
||||
#define EXTRUDER_TIMER_VECTOR TIMER2_COMPA_vect
|
||||
#define EXTRUDER_OCR OCR2A
|
||||
#define EXTRUDER_TCCR TCCR2A
|
||||
#define EXTRUDER_TIMSK TIMSK2
|
||||
#define EXTRUDER_OCIE OCIE2A
|
||||
#define PWM_TIMER_VECTOR TIMER2_COMPB_vect
|
||||
#define PWM_OCR OCR2B
|
||||
#define PWM_TCCR TCCR2B
|
||||
#define PWM_TIMSK TIMSK2
|
||||
#define PWM_OCIE OCIE2B
|
||||
#else*/
|
||||
#define EXTRUDER_TIMER_VECTOR TIMER0_COMPA_vect
|
||||
#define EXTRUDER_OCR OCR0A
|
||||
#define EXTRUDER_TCCR TCCR0A
|
||||
#define EXTRUDER_TIMSK TIMSK0
|
||||
#define EXTRUDER_OCIE OCIE0A
|
||||
#define PWM_TIMER_VECTOR TIMER0_COMPB_vect
|
||||
#define PWM_OCR OCR0B
|
||||
#define PWM_TCCR TCCR0A
|
||||
#define PWM_TIMSK TIMSK0
|
||||
#define PWM_OCIE OCIE0B
|
||||
//#endif
|
||||
|
||||
/** TemperatureController manages one heater-temperature sensore loop. You can have up to
|
||||
4 loops allowing pid/bang bang for up to 3 extruder and the heated bed.
|
||||
|
||||
*/
|
||||
typedef struct {
|
||||
byte pwmIndex; ///< pwm index for output control. 0-2 = Extruder, 3 = Fan, 4 = Heated Bed
|
||||
byte sensorType; ///< Type of temperature sensor.
|
||||
byte sensorPin; ///< Pin to read extruder temperature.
|
||||
int currentTemperature; ///< Currenttemperature value read from sensor.
|
||||
int targetTemperature; ///< Target temperature value in units of sensor.
|
||||
float currentTemperatureC; ///< Current temperature in °C.
|
||||
float targetTemperatureC; ///< Target temperature in °C.
|
||||
unsigned long lastTemperatureUpdate; ///< Time in millis of the last temperature update.
|
||||
char heatManager; ///< How is temperature controled. 0 = on/off, 1 = PID-Control
|
||||
#ifdef TEMP_PID
|
||||
long tempIState; ///< Temp. var. for PID computation.
|
||||
byte pidDriveMax; ///< Used for windup in PID calculation.
|
||||
byte pidDriveMin; ///< Used for windup in PID calculation.
|
||||
float pidPGain; ///< Pgain (proportional gain) for PID temperature control [0,01 Units].
|
||||
float pidIGain; ///< Igain (integral) for PID temperature control [0,01 Units].
|
||||
float pidDGain; ///< Dgain (damping) for PID temperature control [0,01 Units].
|
||||
byte pidMax; ///< Maximum PWM value, the heater should be set.
|
||||
float tempIStateLimitMax;
|
||||
float tempIStateLimitMin;
|
||||
byte tempPointer;
|
||||
float tempArray[4];
|
||||
#endif
|
||||
} TemperatureController;
|
||||
/** \brief Data to drive one extruder.
|
||||
|
||||
This structure contains all definitions for an extruder and all
|
||||
current state variables, like current temperature, feeder position etc.
|
||||
*/
|
||||
typedef struct { // Size: 12*1 Byte+12*4 Byte+4*2Byte = 68 Byte
|
||||
byte id;
|
||||
long xOffset;
|
||||
long yOffset;
|
||||
float stepsPerMM; ///< Steps per mm.
|
||||
byte enablePin; ///< Pin to enable extruder stepper motor.
|
||||
// byte directionPin; ///< Pin number to assign the direction.
|
||||
// byte stepPin; ///< Pin number for a step.
|
||||
byte enableOn;
|
||||
// byte invertDir; ///< 1 if the direction of the extruder should be inverted.
|
||||
float maxFeedrate; ///< Maximum feedrate in mm/s.
|
||||
float maxAcceleration; ///< Maximum acceleration in mm/s^2.
|
||||
float maxStartFeedrate; ///< Maximum start feedrate in mm/s.
|
||||
long extrudePosition; ///< Current extruder position in steps.
|
||||
int watchPeriod; ///< Time in seconds, a M109 command will wait to stabalize temperature
|
||||
int waitRetractTemperature; ///< Temperature to retract the filament when waiting for heatup
|
||||
int waitRetractUnits; ///< Units to retract the filament when waiting for heatup
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
float advanceK; ///< Koefficient for advance algorithm. 0 = off
|
||||
#endif
|
||||
float advanceL;
|
||||
#endif
|
||||
TemperatureController tempControl;
|
||||
const char * PROGMEM selectCommands;
|
||||
const char * PROGMEM deselectCommands;
|
||||
byte coolerSpeed; ///< Speed to use when enabled
|
||||
byte coolerPWM; ///< current PWM setting
|
||||
} Extruder;
|
||||
|
||||
extern const uint8 osAnalogInputChannels[] PROGMEM;
|
||||
extern uint8 osAnalogInputCounter[ANALOG_INPUTS];
|
||||
extern uint osAnalogInputBuildup[ANALOG_INPUTS];
|
||||
extern uint8 osAnalogInputPos; // Current sampling position
|
||||
extern volatile uint osAnalogInputValues[ANALOG_INPUTS];
|
||||
extern byte pwm_pos[NUM_EXTRUDER+3]; // 0-NUM_EXTRUDER = Heater 0-NUM_EXTRUDER of extruder, NUM_EXTRUDER = Heated bed, NUM_EXTRUDER+1 Board fan, NUM_EXTRUDER+2 = Fan
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
extern int maxadv;
|
||||
#endif
|
||||
extern int maxadv2;
|
||||
extern float maxadvspeed;
|
||||
#endif
|
||||
|
||||
extern Extruder *current_extruder;
|
||||
extern Extruder extruder[];
|
||||
// Initalize extruder and heated bed related pins
|
||||
extern void initExtruder();
|
||||
extern void initHeatedBed();
|
||||
extern void updateTempControlVars(TemperatureController *tc);
|
||||
extern void extruder_select(byte ext_num);
|
||||
// Set current extruder position
|
||||
//extern void extruder_set_position(float pos,bool relative);
|
||||
// set the temperature of current extruder
|
||||
extern void extruder_set_temperature(float temp_celsius,byte extr);
|
||||
// Set temperature of heated bed
|
||||
extern void heated_bed_set_temperature(float temp_celsius);
|
||||
//extern long extruder_steps_to_position(float value,byte relative);
|
||||
extern void extruder_set_direction(byte steps);
|
||||
extern void extruder_disable();
|
||||
#ifdef TEMP_PID
|
||||
void autotunePID(float temp,int controllerId);
|
||||
#endif
|
||||
|
||||
//#ifdef TEMP_PID
|
||||
//extern byte current_extruder_out;
|
||||
//#endif
|
||||
|
||||
/** \brief Sends the high-signal to the stepper for next extruder step.
|
||||
|
||||
Call this function only, if interrupts are disabled.
|
||||
*/
|
||||
inline void extruder_step() {
|
||||
#if NUM_EXTRUDER==1
|
||||
WRITE(EXT0_STEP_PIN,HIGH);
|
||||
#else
|
||||
switch(current_extruder->id) {
|
||||
case 0:
|
||||
#if NUM_EXTRUDER>0
|
||||
WRITE(EXT0_STEP_PIN,HIGH);
|
||||
#endif
|
||||
break;
|
||||
#if defined(EXT1_STEP_PIN) && NUM_EXTRUDER>1
|
||||
case 1:
|
||||
WRITE(EXT1_STEP_PIN,HIGH);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT2_STEP_PIN) && NUM_EXTRUDER>2
|
||||
case 2:
|
||||
WRITE(EXT2_STEP_PIN,HIGH);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT3_STEP_PIN) && NUM_EXTRUDER>3
|
||||
case 3:
|
||||
WRITE(EXT3_STEP_PIN,HIGH);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT4_STEP_PIN) && NUM_EXTRUDER>4
|
||||
case 4:
|
||||
WRITE(EXT4_STEP_PIN,HIGH);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT5_STEP_PIN) && NUM_EXTRUDER>5
|
||||
case 5:
|
||||
WRITE(EXT5_STEP_PIN,HIGH);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
/** \brief Sets stepper signal to low for current extruder.
|
||||
|
||||
Call this function only, if interrupts are disabled.
|
||||
*/
|
||||
inline void extruder_unstep() {
|
||||
#if NUM_EXTRUDER==1
|
||||
WRITE(EXT0_STEP_PIN,LOW);
|
||||
#else
|
||||
switch(current_extruder->id) {
|
||||
case 0:
|
||||
#if NUM_EXTRUDER>0
|
||||
WRITE(EXT0_STEP_PIN,LOW);
|
||||
#endif
|
||||
break;
|
||||
#if defined(EXT1_STEP_PIN) && NUM_EXTRUDER>1
|
||||
case 1:
|
||||
WRITE(EXT1_STEP_PIN,LOW);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT2_STEP_PIN) && NUM_EXTRUDER>2
|
||||
case 2:
|
||||
WRITE(EXT2_STEP_PIN,LOW);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT3_STEP_PIN) && NUM_EXTRUDER>3
|
||||
case 3:
|
||||
WRITE(EXT3_STEP_PIN,LOW);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT4_STEP_PIN) && NUM_EXTRUDER>4
|
||||
case 4:
|
||||
WRITE(EXT4_STEP_PIN,LOW);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT5_STEP_PIN) && NUM_EXTRUDER>5
|
||||
case 5:
|
||||
WRITE(EXT5_STEP_PIN,LOW);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
/** \brief Activates the extruder stepper and sets the direction. */
|
||||
inline void extruder_set_direction(byte dir) {
|
||||
#if NUM_EXTRUDER==1
|
||||
if(dir)
|
||||
WRITE(EXT0_DIR_PIN,!EXT0_INVERSE);
|
||||
else
|
||||
WRITE(EXT0_DIR_PIN,EXT0_INVERSE);
|
||||
#else
|
||||
switch(current_extruder->id) {
|
||||
#if NUM_EXTRUDER>0
|
||||
case 0:
|
||||
if(dir)
|
||||
WRITE(EXT0_DIR_PIN,!EXT0_INVERSE);
|
||||
else
|
||||
WRITE(EXT0_DIR_PIN,EXT0_INVERSE);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT1_DIR_PIN) && NUM_EXTRUDER>1
|
||||
case 1:
|
||||
if(dir)
|
||||
WRITE(EXT1_DIR_PIN,!EXT1_INVERSE);
|
||||
else
|
||||
WRITE(EXT1_DIR_PIN,EXT1_INVERSE);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT2_DIR_PIN) && NUM_EXTRUDER>2
|
||||
case 2:
|
||||
if(dir)
|
||||
WRITE(EXT2_DIR_PIN,!EXT2_INVERSE);
|
||||
else
|
||||
WRITE(EXT2_DIR_PIN,EXT2_INVERSE);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT3_DIR_PIN) && NUM_EXTRUDER>3
|
||||
case 3:
|
||||
if(dir)
|
||||
WRITE(EXT3_DIR_PIN,!EXT3_INVERSE);
|
||||
else
|
||||
WRITE(EXT3_DIR_PIN,EXT3_INVERSE);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT4_DIR_PIN) && NUM_EXTRUDER>4
|
||||
case 4:
|
||||
if(dir)
|
||||
WRITE(EXT4_DIR_PIN,!EXT4_INVERSE);
|
||||
else
|
||||
WRITE(EXT4_DIR_PIN,EXT4_INVERSE);
|
||||
break;
|
||||
#endif
|
||||
#if defined(EXT5_DIR_PIN) && NUM_EXTRUDER>5
|
||||
case 5:
|
||||
if(dir)
|
||||
WRITE(EXT5_DIR_PIN,!EXT5_INVERSE);
|
||||
else
|
||||
WRITE(EXT5_DIR_PIN,EXT5_INVERSE);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
inline void extruder_enable() {
|
||||
#if NUM_EXTRUDER==1
|
||||
#if EXT0_ENABLE_PIN>-1
|
||||
WRITE(EXT0_ENABLE_PIN,EXT0_ENABLE_ON );
|
||||
#endif
|
||||
#else
|
||||
if(current_extruder->enablePin > -1)
|
||||
digitalWrite(current_extruder->enablePin,current_extruder->enableOn);
|
||||
#endif
|
||||
}
|
||||
extern void(* resetFunc) (void);
|
||||
// Read a temperature and return its value in °C
|
||||
// this high level method supports all known methods
|
||||
extern int read_raw_temperature(byte type,byte pin);
|
||||
extern float heated_bed_get_temperature();
|
||||
// Convert a raw temperature value into °C
|
||||
extern float conv_raw_temp(byte type,int raw_temp);
|
||||
// Converts a temperture temp in °C into a raw value
|
||||
// which can be compared with results of read_raw_temperature
|
||||
extern int conv_temp_raw(byte type,float temp);
|
||||
// Updates the temperature of all extruders and heated bed if it's time.
|
||||
// Toggels the heater power if necessary.
|
||||
extern void manage_temperatures();
|
||||
extern bool reportTempsensorError(); ///< Report defect sensors
|
||||
extern byte manage_monitor;
|
||||
|
||||
void process_command(GCode *code,byte bufferedCommand);
|
||||
|
||||
void manage_inactivity(byte debug);
|
||||
|
||||
extern void wait_until_end_of_move();
|
||||
extern void update_ramps_parameter();
|
||||
extern void update_extruder_flags();
|
||||
extern void finishNextSegment();
|
||||
extern void printPosition();
|
||||
extern void defaultLoopActions();
|
||||
extern void change_feedrate_multiply(int factor); ///< Set feedrate multiplier
|
||||
extern void set_fan_speed(int speed,bool wait); /// Set fan speed 0..255
|
||||
extern void home_axis(bool xaxis,bool yaxis,bool zaxis); /// Home axis
|
||||
extern byte get_coordinates(GCode *com);
|
||||
extern void move_steps(long x,long y,long z,long e,float feedrate,bool waitEnd,bool check_endstop);
|
||||
extern void queue_move(byte check_endstops,byte pathOptimize);
|
||||
#if DRIVE_SYSTEM==3
|
||||
extern byte calculate_delta(long cartesianPosSteps[], long deltaPosSteps[]);
|
||||
extern void set_delta_position(long xaxis, long yaxis, long zaxis);
|
||||
extern float rodMaxLength;
|
||||
extern void split_delta_move(byte check_endstops,byte pathOptimize, byte softEndstop);
|
||||
#ifdef SOFTWARE_LEVELING
|
||||
extern void calculate_plane(long factors[], long p1[], long p2[], long p3[]);
|
||||
extern float calc_zoffset(long factors[], long pointX, long pointY);
|
||||
#endif
|
||||
#endif
|
||||
extern void linear_move(long steps_remaining[]);
|
||||
extern inline void disable_x();
|
||||
extern inline void disable_y();
|
||||
extern inline void disable_z();
|
||||
extern inline void enable_x();
|
||||
extern inline void enable_y();
|
||||
extern inline void enable_z();
|
||||
|
||||
#define PREVIOUS_PLANNER_INDEX(p) {p--;if(p==255) p = MOVE_CACHE_SIZE-1;}
|
||||
#define NEXT_PLANNER_INDEX(idx) {++idx;if(idx==MOVE_CACHE_SIZE) idx=0;}
|
||||
|
||||
extern void kill(byte only_steppers);
|
||||
|
||||
extern float axis_steps_per_unit[];
|
||||
extern float inv_axis_steps_per_unit[];
|
||||
extern float max_feedrate[];
|
||||
extern float homing_feedrate[];
|
||||
extern float max_start_speed_units_per_second[];
|
||||
extern long max_acceleration_units_per_sq_second[];
|
||||
extern long max_travel_acceleration_units_per_sq_second[];
|
||||
extern unsigned long axis_steps_per_sqr_second[];
|
||||
extern unsigned long axis_travel_steps_per_sqr_second[];
|
||||
extern byte relative_mode; ///< Determines absolute (false) or relative Coordinates (true).
|
||||
extern byte relative_mode_e; ///< Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode.
|
||||
|
||||
extern byte unit_inches;
|
||||
extern unsigned long previous_millis_cmd;
|
||||
extern unsigned long max_inactive_time;
|
||||
extern unsigned long stepper_inactive_time;
|
||||
|
||||
extern void setupTimerInterrupt();
|
||||
extern void current_control_init();
|
||||
extern void microstep_init();
|
||||
extern void print_temperatures();
|
||||
extern void check_mem();
|
||||
#if ARC_SUPPORT
|
||||
extern void mc_arc(float *position, float *target, float *offset, float radius, uint8_t isclockwise);
|
||||
#endif
|
||||
|
||||
#define PRINTER_FLAG0_STEPPER_DISABLED 1
|
||||
#define PRINTER_FLAG0_SEPERATE_EXTRUDER_INT 2
|
||||
#define PRINTER_FLAG0_TEMPSENSOR_DEFECT 4
|
||||
typedef struct {
|
||||
byte flag0; // 1 = stepper disabled, 2 = use external extruder interrupt, 4 = temp Sensor defect
|
||||
#if USE_OPS==1 || defined(USE_ADVANCE)
|
||||
volatile int extruderStepsNeeded; ///< This many extruder steps are still needed, <0 = reverse steps needed.
|
||||
// float extruderSpeed; ///< Extruder speed in mm/s.
|
||||
byte minExtruderSpeed; ///< Timer delay for start extruder speed
|
||||
byte maxExtruderSpeed; ///< Timer delay for end extruder speed
|
||||
byte extruderAccelerateDelay; ///< delay between 2 speec increases
|
||||
#endif
|
||||
long interval; ///< Last step duration in ticks.
|
||||
#if USE_OPS==1
|
||||
bool filamentRetracted; ///< Is the extruder filament retracted
|
||||
#endif
|
||||
unsigned long timer; ///< used for acceleration/deceleration timing
|
||||
unsigned long stepNumber; ///< Step number in current move.
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
long advance_executed; ///< Executed advance steps
|
||||
#endif
|
||||
int advance_steps_set;
|
||||
unsigned int advance_lin_set;
|
||||
#endif
|
||||
long currentPositionSteps[4]; ///< Position in steps from origin.
|
||||
long destinationSteps[4]; ///< Target position in steps.
|
||||
#if DRIVE_SYSTEM==3
|
||||
#ifdef STEP_COUNTER
|
||||
long countZSteps; ///< Count of steps from last position reset
|
||||
#endif
|
||||
long currentDeltaPositionSteps[4];
|
||||
long maxDeltaPositionSteps;
|
||||
#endif
|
||||
#ifdef SOFTWARE_LEVELING
|
||||
long levelingP1[3];
|
||||
long levelingP2[3];
|
||||
long levelingP3[3];
|
||||
#endif
|
||||
#if USE_OPS==1
|
||||
int opsRetractSteps; ///< Retract filament this much steps
|
||||
int opsPushbackSteps; ///< Retract+extra distance for backsash
|
||||
float opsMinDistance;
|
||||
float opsRetractDistance;
|
||||
float opsRetractBacklash;
|
||||
byte opsMode; ///< OPS operation mode. 0 = Off, 1 = Classic, 2 = Fast
|
||||
float opsMoveAfter; ///< Start move after opsModeAfter percent off full retract.
|
||||
int opsMoveAfterSteps; ///< opsMoveAfter converted in steps (negative value!).
|
||||
#endif
|
||||
long xMaxSteps; ///< For software endstops, limit of move in positive direction.
|
||||
long yMaxSteps; ///< For software endstops, limit of move in positive direction.
|
||||
long zMaxSteps; ///< For software endstops, limit of move in positive direction.
|
||||
long xMinSteps; ///< For software endstops, limit of move in negative direction.
|
||||
long yMinSteps; ///< For software endstops, limit of move in negative direction.
|
||||
long zMinSteps; ///< For software endstops, limit of move in negative direction.
|
||||
float xLength;
|
||||
float xMin;
|
||||
float yLength;
|
||||
float yMin;
|
||||
float zLength;
|
||||
float zMin;
|
||||
float feedrate; ///< Last requested feedrate.
|
||||
int feedrateMultiply; ///< Multiplier for feedrate in percent (factor 1 = 100)
|
||||
unsigned int extrudeMultiply; ///< Flow multiplier in percdent (factor 1 = 100)
|
||||
float maxJerk; ///< Maximum allowed jerk in mm/s
|
||||
float maxZJerk; ///< Maximum allowed jerk in z direction in mm/s
|
||||
long offsetX; ///< X-offset for different extruder positions.
|
||||
long offsetY; ///< Y-offset for different extruder positions.
|
||||
unsigned int vMaxReached; ///< MAximumu reached speed
|
||||
byte stepper_loops;
|
||||
unsigned long msecondsPrinting; ///< Milliseconds of printing time (means time with heated extruder)
|
||||
float filamentPrinted; ///< mm of filament printed since counting started
|
||||
byte waslasthalfstepping; ///< Indicates if last move had halfstepping enabled
|
||||
#if ENABLE_BACKLASH_COMPENSATION
|
||||
float backlashX;
|
||||
float backlashY;
|
||||
float backlashZ;
|
||||
byte backlashDir;
|
||||
#endif
|
||||
#ifdef DEBUG_STEPCOUNT
|
||||
long totalStepsRemaining;
|
||||
#endif
|
||||
#if FEATURE_MEMORY_POSITION
|
||||
long memoryX;
|
||||
long memoryY;
|
||||
long memoryZ;
|
||||
#endif
|
||||
#ifdef XY_GANTRY
|
||||
char motorX;
|
||||
char motorY;
|
||||
#endif
|
||||
} PrinterState;
|
||||
extern PrinterState printer_state;
|
||||
|
||||
/** Marks the first step of a new move */
|
||||
#define FLAG_WARMUP 1
|
||||
#define FLAG_NOMINAL 2
|
||||
#define FLAG_DECELERATING 4
|
||||
#define FLAG_ACCELERATION_ENABLED 8
|
||||
#define FLAG_CHECK_ENDSTOPS 16
|
||||
#define FLAG_SKIP_ACCELERATING 32
|
||||
#define FLAG_SKIP_DEACCELERATING 64
|
||||
#define FLAG_BLOCKED 128
|
||||
|
||||
/** Are the step parameter computed */
|
||||
#define FLAG_JOIN_STEPPARAMS_COMPUTED 1
|
||||
/** The right speed is fixed. Don't check this block or any block to the left. */
|
||||
#define FLAG_JOIN_END_FIXED 2
|
||||
/** The left speed is fixed. Don't check left block. */
|
||||
#define FLAG_JOIN_START_FIXED 4
|
||||
/** Start filament retraction at move start */
|
||||
#define FLAG_JOIN_START_RETRACT 8
|
||||
/** Wait for filament pushback, before ending move */
|
||||
#define FLAG_JOIN_END_RETRACT 16
|
||||
/** Disable retract for this line */
|
||||
#define FLAG_JOIN_NO_RETRACT 32
|
||||
/** Wait for the extruder to finish it's up movement */
|
||||
#define FLAG_JOIN_WAIT_EXTRUDER_UP 64
|
||||
/** Wait for the extruder to finish it's down movement */
|
||||
#define FLAG_JOIN_WAIT_EXTRUDER_DOWN 128
|
||||
// Printing related data
|
||||
#if DRIVE_SYSTEM==3
|
||||
// Allow the delta cache to store segments for every line in line cache. Beware this gets big ... fast.
|
||||
// MAX_DELTA_SEGMENTS_PER_LINE *
|
||||
#define DELTA_CACHE_SIZE (MAX_DELTA_SEGMENTS_PER_LINE * MOVE_CACHE_SIZE)
|
||||
typedef struct {
|
||||
byte dir; ///< Direction of delta movement.
|
||||
unsigned int deltaSteps[3]; ///< Number of steps in move.
|
||||
} DeltaSegment;
|
||||
extern DeltaSegment segments[]; // Delta segment cache
|
||||
extern unsigned int delta_segment_write_pos; // Position where we write the next cached delta move
|
||||
extern volatile unsigned int delta_segment_count; // Number of delta moves cached 0 = nothing in cache
|
||||
extern byte lastMoveID;
|
||||
#endif
|
||||
typedef struct { // RAM usage: 24*4+15 = 113 Byte
|
||||
byte primaryAxis;
|
||||
volatile byte flags;
|
||||
long timeInTicks;
|
||||
byte joinFlags;
|
||||
byte halfstep; ///< 0 = disabled, 1 = halfstep, 2 = fulstep
|
||||
byte dir; ///< Direction of movement. 1 = X+, 2 = Y+, 4= Z+, values can be combined.
|
||||
long delta[4]; ///< Steps we want to move.
|
||||
long error[4]; ///< Error calculation for Bresenham algorithm
|
||||
float speedX; ///< Speed in x direction at fullInterval in mm/s
|
||||
float speedY; ///< Speed in y direction at fullInterval in mm/s
|
||||
float speedZ; ///< Speed in z direction at fullInterval in mm/s
|
||||
float speedE; ///< Speed in E direction at fullInterval in mm/s
|
||||
float fullSpeed; ///< Desired speed mm/s
|
||||
float invFullSpeed; ///< 1.0/fullSpeed for fatser computation
|
||||
float acceleration; ///< Real 2.0*distanceÜacceleration mm²/s²
|
||||
float maxJunctionSpeed; ///< Max. junction speed between this and next segment
|
||||
float startSpeed; ///< Staring speed in mm/s
|
||||
float endSpeed; ///< Exit speed in mm/s
|
||||
float distance;
|
||||
#if DRIVE_SYSTEM==3
|
||||
byte numDeltaSegments; ///< Number of delta segments left in line. Decremented by stepper timer.
|
||||
byte moveID; ///< ID used to identify moves which are all part of the same line
|
||||
int deltaSegmentReadPos; ///< Pointer to next DeltaSegment
|
||||
long numPrimaryStepPerSegment; ///< Number of primary bresenham axis steps in each delta segment
|
||||
#endif
|
||||
unsigned long fullInterval; ///< interval at full speed in ticks/step.
|
||||
unsigned long stepsRemaining; ///< Remaining steps, until move is finished
|
||||
unsigned int accelSteps; ///< How much steps does it take, to reach the plateau.
|
||||
unsigned int decelSteps; ///< How much steps does it take, to reach the end speed.
|
||||
unsigned long accelerationPrim; ///< Acceleration along primary axis
|
||||
unsigned long facceleration; ///< accelerationPrim*262144/F_CPU
|
||||
unsigned int vMax; ///< Maximum reached speed in steps/s.
|
||||
unsigned int vStart; ///< Starting speed in steps/s.
|
||||
unsigned int vEnd; ///< End speed in steps/s
|
||||
#ifdef USE_ADVANCE
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
long advanceRate; ///< Advance steps at full speed
|
||||
long advanceFull; ///< Maximum advance at fullInterval [steps*65536]
|
||||
long advanceStart;
|
||||
long advanceEnd;
|
||||
#endif
|
||||
unsigned int advanceL; ///< Recomputated L value
|
||||
#endif
|
||||
#if USE_OPS==1
|
||||
long opsReverseSteps; ///< How many steps are needed to reverse retracted filament at full speed
|
||||
#endif
|
||||
#ifdef DEBUG_STEPCOUNT
|
||||
long totalStepsRemaining;
|
||||
#endif
|
||||
} PrintLine;
|
||||
|
||||
extern PrintLine lines[];
|
||||
extern byte lines_write_pos; // Position where we write the next cached line move
|
||||
extern byte lines_pos; // Position for executing line movement
|
||||
extern volatile byte lines_count; // Number of lines cached 0 = nothing to do
|
||||
extern byte printmoveSeen;
|
||||
extern long baudrate;
|
||||
#if OS_ANALOG_INPUTS>0
|
||||
// Get last result for pin x
|
||||
extern volatile uint osAnalogInputValues[OS_ANALOG_INPUTS];
|
||||
#endif
|
||||
#define BEGIN_INTERRUPT_PROTECTED {byte sreg=SREG;__asm volatile( "cli" ::: "memory" );
|
||||
#define END_INTERRUPT_PROTECTED SREG=sreg;}
|
||||
#define ESCAPE_INTERRUPT_PROTECTED SREG=sreg;
|
||||
|
||||
#define SECONDS_TO_TICKS(s) (unsigned long)(s*(float)F_CPU)
|
||||
extern long CPUDivU2(unsigned int divisor);
|
||||
|
||||
extern unsigned int counter_periodical;
|
||||
extern volatile byte execute_periodical;
|
||||
extern byte counter_250ms;
|
||||
extern void write_monitor();
|
||||
extern void check_periodical();
|
||||
#define CELSIUS_EXTRA_BITS 3
|
||||
#define ANALOG_REDUCE_BITS 0
|
||||
#define ANALOG_REDUCE_FACTOR 1
|
||||
|
||||
#if HAVE_HEATED_BED
|
||||
#define NUM_TEMPERATURE_LOOPS NUM_EXTRUDER+1
|
||||
extern TemperatureController heatedBedController;
|
||||
#else
|
||||
#define NUM_TEMPERATURE_LOOPS NUM_EXTRUDER
|
||||
#endif
|
||||
#define TEMP_INT_TO_FLOAT(temp) ((float)(temp)/(float)(1<<CELSIUS_EXTRA_BITS))
|
||||
#define TEMP_FLOAT_TO_INT(temp) ((int)((temp)*(1<<CELSIUS_EXTRA_BITS)))
|
||||
|
||||
extern TemperatureController *tempController[NUM_TEMPERATURE_LOOPS];
|
||||
extern byte autotuneIndex;
|
||||
|
||||
#if SDSUPPORT
|
||||
|
||||
|
||||
#include "SdFat.h"
|
||||
|
||||
enum LsAction {LS_SerialPrint,LS_Count,LS_GetFilename};
|
||||
class SDCard {
|
||||
public:
|
||||
SdFat fat;
|
||||
//Sd2Card card; // ~14 Byte
|
||||
//SdVolume volume;
|
||||
//SdFile root;
|
||||
//SdFile dir[SD_MAX_FOLDER_DEPTH+1];
|
||||
SdFile file;
|
||||
uint32_t filesize;
|
||||
uint32_t sdpos;
|
||||
char fullName[13*SD_MAX_FOLDER_DEPTH+13]; // Fill name
|
||||
char *shortname; // Pointer to start of filename itself
|
||||
char *pathend; // File to char where pathname in fullname ends
|
||||
bool sdmode; // true if we are printing from sd card
|
||||
bool sdactive;
|
||||
//int16_t n;
|
||||
bool savetosd;
|
||||
SDCard();
|
||||
void initsd();
|
||||
void write_command(GCode *code);
|
||||
void selectFile(char *filename);
|
||||
inline void mount() {
|
||||
sdmode = false;
|
||||
initsd();
|
||||
}
|
||||
inline void unmount() {
|
||||
sdmode = false;
|
||||
sdactive = false;
|
||||
}
|
||||
inline void startPrint() {if(sdactive) sdmode = true; }
|
||||
inline void pausePrint() {sdmode = false;}
|
||||
inline void setIndex(uint32_t newpos) { if(!sdactive) return; sdpos = newpos;file.seekSet(sdpos);}
|
||||
void printStatus();
|
||||
void ls();
|
||||
void startWrite(char *filename);
|
||||
void deleteFile(char *filename);
|
||||
void finishWrite();
|
||||
char *createFilename(char *buffer,const dir_t &p);
|
||||
void makeDirectory(char *filename);
|
||||
bool showFilename(const uint8_t *name);
|
||||
void automount();
|
||||
private:
|
||||
void lsRecursive(SdBaseFile *parent,byte level);
|
||||
// SdFile *getDirectory(char* name);
|
||||
};
|
||||
|
||||
extern SDCard sd;
|
||||
#endif
|
||||
|
||||
extern int waitRelax; // Delay filament relax at the end of print, could be a simple timeout
|
||||
#ifdef USE_OPS
|
||||
extern byte printmoveSeen;
|
||||
#endif
|
||||
extern void updateStepsParameter(PrintLine *p/*,byte caller*/);
|
||||
|
||||
/** \brief Disable stepper motor for x direction. */
|
||||
inline void disable_x() {
|
||||
#if (X_ENABLE_PIN > -1)
|
||||
WRITE(X_ENABLE_PIN,!X_ENABLE_ON);
|
||||
#endif
|
||||
}
|
||||
/** \brief Disable stepper motor for y direction. */
|
||||
inline void disable_y() {
|
||||
#if (Y_ENABLE_PIN > -1)
|
||||
WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON);
|
||||
#endif
|
||||
}
|
||||
/** \brief Disable stepper motor for z direction. */
|
||||
inline void disable_z() {
|
||||
#if (Z_ENABLE_PIN > -1)
|
||||
WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON);
|
||||
#endif
|
||||
}
|
||||
/** \brief Enable stepper motor for x direction. */
|
||||
inline void enable_x() {
|
||||
#if (X_ENABLE_PIN > -1)
|
||||
WRITE(X_ENABLE_PIN, X_ENABLE_ON);
|
||||
#endif
|
||||
}
|
||||
/** \brief Enable stepper motor for y direction. */
|
||||
inline void enable_y() {
|
||||
#if (Y_ENABLE_PIN > -1)
|
||||
WRITE(Y_ENABLE_PIN, Y_ENABLE_ON);
|
||||
#endif
|
||||
}
|
||||
/** \brief Enable stepper motor for z direction. */
|
||||
inline void enable_z() {
|
||||
#if (Z_ENABLE_PIN > -1)
|
||||
WRITE(Z_ENABLE_PIN, Z_ENABLE_ON);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#if DRIVE_SYSTEM==3
|
||||
#define SIN_60 0.8660254037844386
|
||||
#define COS_60 0.5
|
||||
#define DELTA_DIAGONAL_ROD_STEPS (AXIS_STEPS_PER_MM * DELTA_DIAGONAL_ROD)
|
||||
#define DELTA_DIAGONAL_ROD_STEPS_SQUARED (DELTA_DIAGONAL_ROD_STEPS * DELTA_DIAGONAL_ROD_STEPS)
|
||||
#define DELTA_ZERO_OFFSET_STEPS (AXIS_STEPS_PER_MM * DELTA_ZERO_OFFSET)
|
||||
#define DELTA_RADIUS_STEPS (AXIS_STEPS_PER_MM * DELTA_RADIUS)
|
||||
|
||||
#define DELTA_TOWER1_X_STEPS -SIN_60*DELTA_RADIUS_STEPS
|
||||
#define DELTA_TOWER1_Y_STEPS -COS_60*DELTA_RADIUS_STEPS
|
||||
#define DELTA_TOWER2_X_STEPS SIN_60*DELTA_RADIUS_STEPS
|
||||
#define DELTA_TOWER2_Y_STEPS -COS_60*DELTA_RADIUS_STEPS
|
||||
#define DELTA_TOWER3_X_STEPS 0.0
|
||||
#define DELTA_TOWER3_Y_STEPS DELTA_RADIUS_STEPS
|
||||
|
||||
#define NUM_AXIS 4
|
||||
#define X_AXIS 0
|
||||
#define Y_AXIS 1
|
||||
#define Z_AXIS 2
|
||||
#define E_AXIS 3
|
||||
|
||||
#endif
|
||||
|
||||
#define STR(s) #s
|
||||
#define XSTR(s) STR(s)
|
||||
|
||||
#endif
|
||||
289
Repetier/SDCard.cpp
Normal file
289
Repetier/SDCard.cpp
Normal file
|
|
@ -0,0 +1,289 @@
|
|||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Repetier-Firmware is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Foobar. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
This firmware is a nearly complete rewrite of the sprinter firmware
|
||||
by kliment (https://github.com/kliment/Sprinter)
|
||||
which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
||||
*/
|
||||
|
||||
#include "Reptier.h"
|
||||
#include "ui.h"
|
||||
|
||||
#if SDSUPPORT
|
||||
|
||||
#ifndef SD_ALLOW_LONG_NAMES
|
||||
#define SD_ALLOW_LONG_NAMES false
|
||||
#endif
|
||||
|
||||
SDCard sd;
|
||||
|
||||
SDCard::SDCard() {
|
||||
sdmode = false;
|
||||
sdactive = false;
|
||||
savetosd = false;
|
||||
//power to SD reader
|
||||
#if SDPOWER > -1
|
||||
SET_OUTPUT(SDPOWER);
|
||||
WRITE(SDPOWER,HIGH);
|
||||
#endif
|
||||
#if defined(SDCARDDETECT) && SDCARDDETECT>-1
|
||||
SET_INPUT(SDCARDDETECT);
|
||||
WRITE(SDCARDDETECT,HIGH);
|
||||
#endif
|
||||
}
|
||||
void SDCard::automount() {
|
||||
#if defined(SDCARDDETECT) && SDCARDDETECT>-1
|
||||
if(READ(SDCARDDETECT) != SDCARDDETECTINVERTED) {
|
||||
if(sdactive) { // Card removed
|
||||
sdactive = false;
|
||||
savetosd = false;
|
||||
sdmode = false;
|
||||
UI_STATUS(UI_TEXT_SD_REMOVED);
|
||||
OUT_P_LN(UI_TEXT_SD_REMOVED);
|
||||
}
|
||||
} else {
|
||||
if(!sdactive) {
|
||||
UI_STATUS(UI_TEXT_SD_INSERTED);
|
||||
OUT_P_LN(UI_TEXT_SD_INSERTED);
|
||||
initsd();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
void SDCard::initsd() {
|
||||
sdactive = false;
|
||||
#if SDSS >- 1
|
||||
/*if(dir[0].isOpen())
|
||||
dir[0].close();*/
|
||||
if(!fat.begin(SDSS,SPI_FULL_SPEED)) {
|
||||
OUT_P_LN("SD init fail");
|
||||
return;
|
||||
}
|
||||
fat.setStdOut(&out);
|
||||
sdactive = true;
|
||||
#endif
|
||||
}
|
||||
|
||||
void SDCard::write_command(GCode *code) {
|
||||
unsigned int sum1=0,sum2=0; // for fletcher-16 checksum
|
||||
byte buf[100];
|
||||
byte p=2;
|
||||
file.writeError = false;
|
||||
int params = 128 | (code->params & ~1);
|
||||
*(int*)buf = params;
|
||||
if(GCODE_IS_V2(code)) { // Read G,M as 16 bit value
|
||||
*(int*)&buf[p] = code->params2;p+=2;
|
||||
if(GCODE_HAS_STRING(code))
|
||||
buf[p++] = strlen(code->text);
|
||||
if(code->params & 2) {*(int*)&buf[p] = code->M;p+=2;}
|
||||
if(code->params & 4) {*(int*)&buf[p]= code->G;p+=2;}
|
||||
} else {
|
||||
if(code->params & 2) {buf[p++] = (byte)code->M;}
|
||||
if(code->params & 4) {buf[p++] = (byte)code->G;}
|
||||
}
|
||||
if(code->params & 8) {*(float*)&buf[p] = code->X;p+=4;}
|
||||
if(code->params & 16) {*(float*)&buf[p] = code->Y;p+=4;}
|
||||
if(code->params & 32) {*(float*)&buf[p] = code->Z;p+=4;}
|
||||
if(code->params & 64) {*(float*)&buf[p] = code->E;p+=4;}
|
||||
if(code->params & 256) {*(float*)&buf[p] = code->F;p+=4;}
|
||||
if(code->params & 512) {buf[p++] = code->T;}
|
||||
if(code->params & 1024) {*(long int*)&buf[p] = code->S;p+=4;}
|
||||
if(code->params & 2048) {*(long int*)&buf[p] = code->P;p+=4;}
|
||||
if(code->params2 & 1) {*(float*)&buf[p] = code->I;p+=4;}
|
||||
if(code->params2 & 2) {*(float*)&buf[p] = code->J;p+=4;}
|
||||
if(GCODE_HAS_STRING(code)) { // read 16 byte into string
|
||||
char *sp = code->text;
|
||||
if(GCODE_IS_V2(code)) {
|
||||
byte i = strlen(code->text);
|
||||
for(;i;i--) buf[p++] = *sp++;
|
||||
} else {
|
||||
for(byte i=0;i<16;++i) buf[p++] = *sp++;
|
||||
}
|
||||
}
|
||||
byte *ptr = buf;
|
||||
byte len = p;
|
||||
while (len) {
|
||||
byte tlen = len > 21 ? 21 : len;
|
||||
len -= tlen;
|
||||
do {
|
||||
sum1 += *ptr++;
|
||||
if(sum1>=255) sum1-=255;
|
||||
sum2 += sum1;
|
||||
if(sum2>=255) sum2-=255;
|
||||
} while (--tlen);
|
||||
}
|
||||
buf[p++] = sum1;
|
||||
buf[p++] = sum2;
|
||||
file.write(buf,p);
|
||||
if (file.writeError){
|
||||
OUT_P_LN("error writing to file");
|
||||
}
|
||||
}
|
||||
char *SDCard::createFilename(char *buffer,const dir_t &p)
|
||||
{
|
||||
char *pos = buffer,*src = (char*)p.name;
|
||||
for (byte i = 0; i < 11; i++,src++)
|
||||
{
|
||||
if (*src == ' ') continue;
|
||||
if (i == 8)
|
||||
*pos++ = '.';
|
||||
*pos++ = *src;
|
||||
}
|
||||
*pos = 0;
|
||||
return pos;
|
||||
}
|
||||
bool SDCard::showFilename(const uint8_t *name) {
|
||||
if (*name == DIR_NAME_DELETED || *name == '.') return false;
|
||||
#if !SD_ALLOW_LONG_NAMES
|
||||
byte i=11;
|
||||
while(i--) {
|
||||
if(*name=='~') return false;
|
||||
name++;
|
||||
}
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
void SDCard::lsRecursive(SdBaseFile *parent,byte level)
|
||||
{
|
||||
dir_t *p;
|
||||
uint8_t cnt=0;
|
||||
char *oldpathend = pathend;
|
||||
char filename[13];
|
||||
parent->rewind();
|
||||
while ((p= parent->readDirCache()))
|
||||
{
|
||||
if (p->name[0] == DIR_NAME_FREE) break;
|
||||
if (!showFilename(p->name)) continue;
|
||||
if (!DIR_IS_FILE_OR_SUBDIR(p)) continue;
|
||||
if( DIR_IS_SUBDIR(p))
|
||||
{
|
||||
if(level>=SD_MAX_FOLDER_DEPTH) continue; // can't go deeper
|
||||
if(level<SD_MAX_FOLDER_DEPTH) {
|
||||
createFilename(filename,*p);
|
||||
if(level) {
|
||||
out.print(fullName);
|
||||
out.print('/');
|
||||
}
|
||||
out.print(filename);
|
||||
out.println('/'); //End with / to mark it as directory entry, so we can see empty directories.
|
||||
}
|
||||
char *tmp = oldpathend;
|
||||
if(level) *tmp++ = '/';
|
||||
char *dirname = tmp;
|
||||
pathend = createFilename(tmp,*p);
|
||||
SdBaseFile next;
|
||||
uint16_t index = parent->curPosition()/32 - 1;
|
||||
if(next.open(parent,dirname, O_READ))
|
||||
lsRecursive(&next,level+1);
|
||||
parent->seekSet(32 * (index + 1));
|
||||
*oldpathend = 0;
|
||||
} else {
|
||||
createFilename(filename,*p);
|
||||
if(level) {
|
||||
out.print(fullName);
|
||||
out.print('/');
|
||||
}
|
||||
out.print(filename);
|
||||
#ifdef SD_EXTENDED_DIR
|
||||
out.write(' ');
|
||||
out.print(p->fileSize);
|
||||
#endif
|
||||
out.println();
|
||||
}
|
||||
}
|
||||
}
|
||||
void SDCard::ls() {
|
||||
OUT_P_LN("Begin file list");
|
||||
*fullName = 0;
|
||||
pathend = fullName;
|
||||
fat.chdir();
|
||||
lsRecursive(fat.vwd(),0);
|
||||
OUT_P_LN("End file list");
|
||||
}
|
||||
|
||||
void SDCard::selectFile(char *filename) {
|
||||
if(!sdactive) return;
|
||||
sdmode = false;
|
||||
file.close();
|
||||
fat.chdir();
|
||||
if (file.open(fat.vwd(),filename, O_READ)) {
|
||||
OUT_P("File opened:");
|
||||
out.print(filename);
|
||||
OUT_P_L_LN(" Size:",file.fileSize());
|
||||
sdpos = 0;
|
||||
filesize = file.fileSize();
|
||||
OUT_P_LN("File selected");
|
||||
} else {
|
||||
OUT_P_LN("file.open failed");
|
||||
}
|
||||
}
|
||||
void SDCard::printStatus() {
|
||||
if(sdactive){
|
||||
OUT_P_L("SD printing byte ",sdpos);
|
||||
OUT_P_L_LN("/",filesize);
|
||||
} else {
|
||||
OUT_P_LN("Not SD printing");
|
||||
}
|
||||
}
|
||||
void SDCard::startWrite(char *filename) {
|
||||
if(!sdactive) return;
|
||||
file.close();
|
||||
sdmode = false;
|
||||
fat.chdir();
|
||||
if(!file.open(filename, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) {
|
||||
OUT_P("open failed, File: ");
|
||||
out.print(filename);
|
||||
out.print('.');
|
||||
} else {
|
||||
UI_STATUS(UI_TEXT_UPLOADING);
|
||||
savetosd = true;
|
||||
OUT_P("Writing to file: ");
|
||||
out.println(filename);
|
||||
}
|
||||
}
|
||||
void SDCard::finishWrite() {
|
||||
if(!savetosd) return; // already closed or never opened
|
||||
file.sync();
|
||||
file.close();
|
||||
savetosd = false;
|
||||
OUT_P_LN("Done saving file.");
|
||||
UI_CLEAR_STATUS;
|
||||
}
|
||||
void SDCard::deleteFile(char *filename) {
|
||||
if(!sdactive) return;
|
||||
sdmode = false;
|
||||
file.close();
|
||||
if(fat.remove(filename)) {
|
||||
OUT_P_LN("File deleted");
|
||||
} else {
|
||||
if(fat.rmdir(filename))
|
||||
OUT_P_LN("File deleted");
|
||||
else
|
||||
OUT_P_LN("Deletion failed");
|
||||
}
|
||||
}
|
||||
void SDCard::makeDirectory(char *filename) {
|
||||
if(!sdactive) return;
|
||||
sdmode = false;
|
||||
file.close();
|
||||
if(fat.mkdir(filename)) {
|
||||
OUT_P_LN("Directory created");
|
||||
} else {
|
||||
OUT_P_LN("Creation failed");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
3761
Repetier/SdFat.cpp
Normal file
3761
Repetier/SdFat.cpp
Normal file
File diff suppressed because it is too large
Load diff
2160
Repetier/SdFat.h
Normal file
2160
Repetier/SdFat.h
Normal file
File diff suppressed because it is too large
Load diff
3048
Repetier/fastio.h
Normal file
3048
Repetier/fastio.h
Normal file
File diff suppressed because it is too large
Load diff
1012
Repetier/gcode.cpp
Normal file
1012
Repetier/gcode.cpp
Normal file
File diff suppressed because it is too large
Load diff
201
Repetier/gcode.h
Normal file
201
Repetier/gcode.h
Normal file
|
|
@ -0,0 +1,201 @@
|
|||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Repetier-Firmware is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#ifndef _GCODE_H
|
||||
#define _GCODE_H
|
||||
|
||||
#include <avr/pgmspace.h>
|
||||
// Workaround for http://gcc.gnu.org/bugzilla/show_bug.cgi?id=34734
|
||||
//#ifdef PROGMEM
|
||||
//#undef PROGMEM
|
||||
//#define PROGMEM __attribute__((section(".progmem.data")))
|
||||
//#endif
|
||||
|
||||
typedef struct { // 52 bytes per command needed
|
||||
unsigned int params;
|
||||
unsigned int params2;
|
||||
unsigned int N; // Line number
|
||||
unsigned int M;
|
||||
unsigned int G;
|
||||
float X;
|
||||
float Y;
|
||||
float Z;
|
||||
float E;
|
||||
float F;
|
||||
byte T;
|
||||
long S;
|
||||
long P;
|
||||
float I;
|
||||
float J;
|
||||
float R;
|
||||
char *text; //text[17];
|
||||
} GCode;
|
||||
|
||||
#ifndef EXTERNALSERIAL
|
||||
// Implement serial communication for one stream only!
|
||||
/*
|
||||
HardwareSerial.h - Hardware serial library for Wiring
|
||||
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
|
||||
Modified 28 September 2010 by Mark Sproul
|
||||
|
||||
Modified to use only 1 queue with fixed length by Repetier
|
||||
*/
|
||||
|
||||
#define SERIAL_BUFFER_SIZE 128
|
||||
#define SERIAL_BUFFER_MASK 127
|
||||
|
||||
struct ring_buffer
|
||||
{
|
||||
unsigned char buffer[SERIAL_BUFFER_SIZE];
|
||||
volatile int head;
|
||||
volatile int tail;
|
||||
};
|
||||
class RFHardwareSerial : public Print
|
||||
{
|
||||
public:
|
||||
ring_buffer *_rx_buffer;
|
||||
ring_buffer *_tx_buffer;
|
||||
volatile uint8_t *_ubrrh;
|
||||
volatile uint8_t *_ubrrl;
|
||||
volatile uint8_t *_ucsra;
|
||||
volatile uint8_t *_ucsrb;
|
||||
volatile uint8_t *_udr;
|
||||
uint8_t _rxen;
|
||||
uint8_t _txen;
|
||||
uint8_t _rxcie;
|
||||
uint8_t _udrie;
|
||||
uint8_t _u2x;
|
||||
public:
|
||||
RFHardwareSerial(ring_buffer *rx_buffer, ring_buffer *tx_buffer,
|
||||
volatile uint8_t *ubrrh, volatile uint8_t *ubrrl,
|
||||
volatile uint8_t *ucsra, volatile uint8_t *ucsrb,
|
||||
volatile uint8_t *udr,
|
||||
uint8_t rxen, uint8_t txen, uint8_t rxcie, uint8_t udrie, uint8_t u2x);
|
||||
void begin(unsigned long);
|
||||
void end();
|
||||
virtual int available(void);
|
||||
virtual int peek(void);
|
||||
virtual int read(void);
|
||||
virtual void flush(void);
|
||||
#ifdef COMPAT_PRE1
|
||||
virtual void write(uint8_t);
|
||||
#else
|
||||
virtual size_t write(uint8_t);
|
||||
#endif
|
||||
using Print::write; // pull in write(str) and write(buf, size) from Print
|
||||
operator bool();
|
||||
};
|
||||
extern RFHardwareSerial RFSerial;
|
||||
#define RFSERIAL RFSerial
|
||||
extern ring_buffer tx_buffer;
|
||||
#define WAIT_OUT_EMPTY while(tx_buffer.head != tx_buffer.tail) {}
|
||||
#else
|
||||
#define RFSERIAL Serial
|
||||
#endif
|
||||
|
||||
class SerialOutput : public Print {
|
||||
public:
|
||||
SerialOutput();
|
||||
#ifdef COMPAT_PRE1
|
||||
void write(uint8_t);
|
||||
#else
|
||||
size_t write(uint8_t);
|
||||
#endif
|
||||
void print_P(PGM_P ptr);
|
||||
void println_P(PGM_P ptr);
|
||||
void print_long_P(PGM_P ptr,long value);
|
||||
void print_int_P(PGM_P ptr,int value);
|
||||
void print_float_P(PGM_P ptr,float value,uint8_t digits = 2);
|
||||
void println_long_P(PGM_P ptr,long value);
|
||||
void println_int_P(PGM_P ptr,int value);
|
||||
void println_float_P(PGM_P ptr,float value,uint8_t digits = 2);
|
||||
void print_error_P(PGM_P ptr,bool newline);
|
||||
void printFloat(double number, uint8_t digits=2);
|
||||
|
||||
};
|
||||
#define OUT_P_I(p,i) out.print_int_P(PSTR(p),(int)(i))
|
||||
#define OUT_P_I_LN(p,i) out.println_int_P(PSTR(p),(int)(i))
|
||||
#define OUT_P_L(p,i) out.print_long_P(PSTR(p),(long)(i))
|
||||
#define OUT_P_L_LN(p,i) out.println_long_P(PSTR(p),(long)(i))
|
||||
#define OUT_P_F(p,i) out.print_float_P(PSTR(p),(float)(i))
|
||||
#define OUT_P_F_LN(p,i) out.println_float_P(PSTR(p),(float)(i))
|
||||
#define OUT_P_FX(p,i,x) out.print_float_P(PSTR(p),(float)(i),x)
|
||||
#define OUT_P_FX_LN(p,i,x) out.println_float_P(PSTR(p),(float)(i),x)
|
||||
#define OUT_P(p) out.print_P(PSTR(p))
|
||||
#define OUT_P_LN(p) out.println_P(PSTR(p))
|
||||
#define OUT_ERROR_P(p) out.print_error_P(PSTR(p),false)
|
||||
#define OUT_ERROR_P_LN(p) out.print_error_P(PSTR(p),true)
|
||||
#define OUT(v) out.print(v)
|
||||
#define OUT_LN out.println()
|
||||
extern SerialOutput out;
|
||||
/** Get next command in command buffer. After the command is processed, call gcode_command_finished() */
|
||||
extern GCode *gcode_next_command();
|
||||
/** Frees the cache used by the last command fetched. */
|
||||
extern void gcode_command_finished(GCode *code);
|
||||
// check for new commands
|
||||
extern void gcode_read_serial();
|
||||
extern void gcode_execute_PString(PGM_P cmd);
|
||||
extern void gcode_print_command(GCode *code);
|
||||
extern byte gcode_comp_binary_size(char *ptr);
|
||||
extern bool gcode_parse_binary(GCode *code,byte *buffer);
|
||||
extern bool gcode_parse_ascii(GCode *code,char *line);
|
||||
extern void emergencyStop();
|
||||
|
||||
// Helper macros to detect, if parameter is stored in GCode struct
|
||||
#define GCODE_HAS_N(a) ((a->params & 1)!=0)
|
||||
#define GCODE_HAS_M(a) ((a->params & 2)!=0)
|
||||
#define GCODE_HAS_G(a) ((a->params & 4)!=0)
|
||||
#define GCODE_HAS_X(a) ((a->params & 8)!=0)
|
||||
#define GCODE_HAS_Y(a) ((a->params & 16)!=0)
|
||||
#define GCODE_HAS_Z(a) ((a->params & 32)!=0)
|
||||
#define GCODE_HAS_NO_XYZ(a) ((a->params & 56)==0)
|
||||
#define GCODE_HAS_E(a) ((a->params & 64)!=0)
|
||||
#define GCODE_HAS_F(a) ((a->params & 256)!=0)
|
||||
#define GCODE_HAS_T(a) ((a->params & 512)!=0)
|
||||
#define GCODE_HAS_S(a) ((a->params & 1024)!=0)
|
||||
#define GCODE_HAS_P(a) ((a->params & 2048)!=0)
|
||||
#define GCODE_IS_V2(a) ((a->params & 4096)!=0)
|
||||
#define GCODE_HAS_STRING(a) ((a->params & 32768)!=0)
|
||||
#define GCODE_HAS_I(a) ((a->params2 & 1)!=0)
|
||||
#define GCODE_HAS_J(a) ((a->params2 & 2)!=0)
|
||||
#define GCODE_HAS_R(a) ((a->params2 & 4)!=0)
|
||||
|
||||
extern byte debug_level;
|
||||
#define DEBUG_ECHO ((debug_level & 1)!=0)
|
||||
#define DEBUG_INFO ((debug_level & 2)!=0)
|
||||
#define DEBUG_ERRORS ((debug_level & 4)!=0)
|
||||
#define DEBUG_DRYRUN ((debug_level & 8)!=0)
|
||||
#define DEBUG_COMMUNICATION ((debug_level & 16)!=0)
|
||||
#define DEBUG_NO_MOVES ((debug_level & 32)!=0)
|
||||
|
||||
#endif
|
||||
|
||||
1371
Repetier/motion.cpp
Normal file
1371
Repetier/motion.cpp
Normal file
File diff suppressed because it is too large
Load diff
1229
Repetier/pins.h
Normal file
1229
Repetier/pins.h
Normal file
File diff suppressed because it is too large
Load diff
2291
Repetier/ui.cpp
Normal file
2291
Repetier/ui.cpp
Normal file
File diff suppressed because it is too large
Load diff
695
Repetier/ui.h
Normal file
695
Repetier/ui.h
Normal file
|
|
@ -0,0 +1,695 @@
|
|||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Repetier-Firmware is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef _ui_h
|
||||
#define _ui_h
|
||||
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WProgram.h"
|
||||
#define COMPAT_PRE1
|
||||
#endif
|
||||
#include <avr/pgmspace.h>
|
||||
#include "gcode.h"
|
||||
|
||||
// ----------------------------------------------------------------------------
|
||||
// Action codes
|
||||
// 1-999 : Autorepeat
|
||||
// 1000-1999 : Execute
|
||||
// 2000-2999 : Write code
|
||||
// 4000-4999 : Show menu
|
||||
// Add UI_ACTION_TOPMENU to show a menu as top menu
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
#define UI_ACTION_TOPMENU 8192
|
||||
|
||||
#define UI_ACTION_NEXT 1
|
||||
#define UI_ACTION_PREVIOUS 2
|
||||
|
||||
#define UI_ACTION_X_UP 100
|
||||
#define UI_ACTION_X_DOWN 101
|
||||
#define UI_ACTION_Y_UP 102
|
||||
#define UI_ACTION_Y_DOWN 103
|
||||
#define UI_ACTION_Z_UP 104
|
||||
#define UI_ACTION_Z_DOWN 105
|
||||
#define UI_ACTION_EXTRUDER_UP 106
|
||||
#define UI_ACTION_EXTRUDER_DOWN 107
|
||||
#define UI_ACTION_EXTRUDER_TEMP_UP 108
|
||||
#define UI_ACTION_EXTRUDER_TEMP_DOWN 109
|
||||
#define UI_ACTION_HEATED_BED_UP 110
|
||||
#define UI_ACTION_HEATED_BED_DOWN 111
|
||||
#define UI_ACTION_FAN_UP 112
|
||||
#define UI_ACTION_FAN_DOWN 113
|
||||
|
||||
#define UI_ACTION_DUMMY 10000
|
||||
#define UI_ACTION_BACK 1000
|
||||
#define UI_ACTION_OK 1001
|
||||
#define UI_ACTION_MENU_UP 1002
|
||||
#define UI_ACTION_TOP_MENU 1003
|
||||
#define UI_ACTION_EMERGENCY_STOP 1004
|
||||
#define UI_ACTION_XPOSITION 1005
|
||||
#define UI_ACTION_YPOSITION 1006
|
||||
#define UI_ACTION_ZPOSITION 1007
|
||||
#define UI_ACTION_EPOSITION 1008
|
||||
#define UI_ACTION_BED_TEMP 1009
|
||||
#define UI_ACTION_EXTRUDER_TEMP 1010
|
||||
#define UI_ACTION_SD_DELETE 1012
|
||||
#define UI_ACTION_SD_PRINT 1013
|
||||
#define UI_ACTION_SD_PAUSE 1014
|
||||
#define UI_ACTION_SD_CONTINUE 1015
|
||||
#define UI_ACTION_SD_UNMOUNT 1016
|
||||
#define UI_ACTION_SD_MOUNT 1017
|
||||
#define UI_ACTION_XPOSITION_FAST 1018
|
||||
#define UI_ACTION_YPOSITION_FAST 1019
|
||||
#define UI_ACTION_ZPOSITION_FAST 1020
|
||||
#define UI_ACTION_HOME_ALL 1021
|
||||
#define UI_ACTION_HOME_X 1022
|
||||
#define UI_ACTION_HOME_Y 1023
|
||||
#define UI_ACTION_HOME_Z 1024
|
||||
#define UI_ACTION_SELECT_EXTRUDER1 1025
|
||||
#define UI_ACTION_OPS_RETRACTDISTANCE 1026
|
||||
#define UI_ACTION_OPS_BACKLASH 1027
|
||||
#define UI_ACTION_OPS_MOVE_AFTER 1028
|
||||
#define UI_ACTION_OPS_MINDISTANCE 1029
|
||||
#define UI_ACTION_STORE_EEPROM 1030
|
||||
#define UI_ACTION_LOAD_EEPROM 1031
|
||||
#define UI_ACTION_PRINT_ACCEL_X 1032
|
||||
#define UI_ACTION_PRINT_ACCEL_Y 1033
|
||||
#define UI_ACTION_PRINT_ACCEL_Z 1034
|
||||
#define UI_ACTION_MOVE_ACCEL_X 1035
|
||||
#define UI_ACTION_MOVE_ACCEL_Y 1036
|
||||
#define UI_ACTION_MOVE_ACCEL_Z 1037
|
||||
#define UI_ACTION_MAX_JERK 1038
|
||||
#define UI_ACTION_MAX_ZJERK 1039
|
||||
#define UI_ACTION_BAUDRATE 1040
|
||||
#define UI_ACTION_HOMING_FEEDRATE_X 1041
|
||||
#define UI_ACTION_HOMING_FEEDRATE_Y 1042
|
||||
#define UI_ACTION_HOMING_FEEDRATE_Z 1043
|
||||
#define UI_ACTION_MAX_FEEDRATE_X 1044
|
||||
#define UI_ACTION_MAX_FEEDRATE_Y 1045
|
||||
#define UI_ACTION_MAX_FEEDRATE_Z 1046
|
||||
#define UI_ACTION_STEPS_X 1047
|
||||
#define UI_ACTION_STEPS_Y 1048
|
||||
#define UI_ACTION_STEPS_Z 1049
|
||||
#define UI_ACTION_FAN_OFF 1050
|
||||
#define UI_ACTION_FAN_25 1051
|
||||
#define UI_ACTION_FAN_50 1052
|
||||
#define UI_ACTION_FAN_75 1053
|
||||
#define UI_ACTION_FAN_FULL 1054
|
||||
#define UI_ACTION_FEEDRATE_MULTIPLY 1055
|
||||
#define UI_ACTION_STEPPER_INACTIVE 1056
|
||||
#define UI_ACTION_MAX_INACTIVE 1057
|
||||
#define UI_ACTION_PID_PGAIN 1058
|
||||
#define UI_ACTION_PID_IGAIN 1059
|
||||
#define UI_ACTION_PID_DGAIN 1060
|
||||
#define UI_ACTION_DRIVE_MIN 1061
|
||||
#define UI_ACTION_DRIVE_MAX 1062
|
||||
#define UI_ACTION_X_OFFSET 1063
|
||||
#define UI_ACTION_Y_OFFSET 1064
|
||||
#define UI_ACTION_EXTR_STEPS 1065
|
||||
#define UI_ACTION_EXTR_ACCELERATION 1066
|
||||
#define UI_ACTION_EXTR_MAX_FEEDRATE 1067
|
||||
#define UI_ACTION_EXTR_START_FEEDRATE 1068
|
||||
#define UI_ACTION_EXTR_HEATMANAGER 1069
|
||||
#define UI_ACTION_EXTR_WATCH_PERIOD 1070
|
||||
#define UI_ACTION_PID_MAX 1071
|
||||
#define UI_ACTION_ADVANCE_K 1072
|
||||
#define UI_ACTION_SET_ORIGIN 1073
|
||||
#define UI_ACTION_DEBUG_ECHO 1074
|
||||
#define UI_ACTION_DEBUG_INFO 1075
|
||||
#define UI_ACTION_DEBUG_ERROR 1076
|
||||
#define UI_ACTION_DEBUG_DRYRUN 1077
|
||||
#define UI_ACTION_POWER 1078
|
||||
#define UI_ACTION_PREHEAT_PLA 1079
|
||||
#define UI_ACTION_COOLDOWN 1080
|
||||
#define UI_ACTION_HEATED_BED_OFF 1081
|
||||
#define UI_ACTION_EXTRUDER0_OFF 1082
|
||||
#define UI_ACTION_EXTRUDER1_OFF 1083
|
||||
#define UI_ACTION_HEATED_BED_TEMP 1084
|
||||
#define UI_ACTION_EXTRUDER0_TEMP 1085
|
||||
#define UI_ACTION_EXTRUDER1_TEMP 1086
|
||||
#define UI_ACTION_OPS_OFF 1087
|
||||
#define UI_ACTION_OPS_CLASSIC 1088
|
||||
#define UI_ACTION_OPS_FAST 1089
|
||||
#define UI_ACTION_DISABLE_STEPPER 1090
|
||||
#define UI_ACTION_RESET_EXTRUDER 1091
|
||||
#define UI_ACTION_EXTRUDER_RELATIVE 1092
|
||||
#define UI_ACTION_SELECT_EXTRUDER0 1093
|
||||
#define UI_ACTION_ADVANCE_L 1094
|
||||
#define UI_ACTION_PREHEAT_ABS 1095
|
||||
#define UI_ACTION_FLOWRATE_MULTIPLY 1096
|
||||
#define UI_ACTION_KILL 1097
|
||||
#define UI_ACTION_RESET 1098
|
||||
#define UI_ACTION_PAUSE 1099
|
||||
#define UI_ACTION_EXTR_WAIT_RETRACT_TEMP 1100
|
||||
#define UI_ACTION_EXTR_WAIT_RETRACT_UNITS 1101
|
||||
|
||||
#define UI_ACTION_MENU_XPOS 4000
|
||||
#define UI_ACTION_MENU_YPOS 4001
|
||||
#define UI_ACTION_MENU_ZPOS 4002
|
||||
#define UI_ACTION_MENU_XPOSFAST 4003
|
||||
#define UI_ACTION_MENU_YPOSFAST 4004
|
||||
#define UI_ACTION_MENU_ZPOSFAST 4005
|
||||
#define UI_ACTION_MENU_SDCARD 4006
|
||||
#define UI_ACTION_MENU_QUICKSETTINGS 4007
|
||||
#define UI_ACTION_MENU_EXTRUDER 4008
|
||||
#define UI_ACTION_MENU_POSITIONS 4009
|
||||
#define UI_ACTION_SHOW_MEASUREMENT 4010
|
||||
#define UI_ACTION_RESET_MEASUREMENT 4011
|
||||
#define UI_ACTION_SET_MEASURED_ORIGIN 4012
|
||||
#define UI_ACTION_SET_P1 4013
|
||||
#define UI_ACTION_SET_P2 4014
|
||||
#define UI_ACTION_SET_P3 4015
|
||||
#define UI_ACTION_CALC_LEVEL 4016
|
||||
|
||||
#define UI_ACTION_SHOW_USERMENU1 4101
|
||||
#define UI_ACTION_SHOW_USERMENU2 4102
|
||||
#define UI_ACTION_SHOW_USERMENU3 4103
|
||||
#define UI_ACTION_SHOW_USERMENU4 4104
|
||||
#define UI_ACTION_SHOW_USERMENU5 4105
|
||||
#define UI_ACTION_SHOW_USERMENU6 4106
|
||||
#define UI_ACTION_SHOW_USERMENU7 4107
|
||||
#define UI_ACTION_SHOW_USERMENU8 4108
|
||||
#define UI_ACTION_SHOW_USERMENU9 4109
|
||||
#define UI_ACTION_SHOW_USERMENU10 4110
|
||||
|
||||
// Load basic language definition to make sure all values are defined
|
||||
#include "uilang.h"
|
||||
|
||||
#include "Configuration.h"
|
||||
#include <avr/pgmspace.h>
|
||||
#include "fastio.h"
|
||||
|
||||
typedef struct {
|
||||
const char *text; // Menu text
|
||||
unsigned char menuType; // 0 = Info, 1 = Headline, 2 = submenu ref, 3 = direct action command, 4 = modify action command
|
||||
unsigned int action;
|
||||
} const UIMenuEntry;
|
||||
|
||||
typedef struct {
|
||||
// 0 = info page
|
||||
// 1 = file selector
|
||||
// 2 = submenu
|
||||
// 3 = modififaction menu
|
||||
unsigned char menuType;
|
||||
int id; // Type of modification
|
||||
int numEntries;
|
||||
const UIMenuEntry * const * entries;
|
||||
} const UIMenu;
|
||||
extern const int8_t encoder_table[16] PROGMEM ;
|
||||
|
||||
//#ifdef COMPILE_I2C_DRIVER
|
||||
|
||||
/*************************************************************************
|
||||
* Title: C include file for the I2C master interface
|
||||
* (i2cmaster.S or twimaster.c)
|
||||
* Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
|
||||
* File: $Id: i2cmaster.h,v 1.10 2005/03/06 22:39:57 Peter Exp $
|
||||
* Software: AVR-GCC 3.4.3 / avr-libc 1.2.3
|
||||
* Target: any AVR device
|
||||
* Usage: see Doxygen manual
|
||||
**************************************************************************/
|
||||
|
||||
#if (__GNUC__ * 100 + __GNUC_MINOR__) < 304
|
||||
#error "This library requires AVR-GCC 3.4 or later, update to newer AVR-GCC compiler !"
|
||||
#endif
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
/** defines the data direction (reading from I2C device) in i2c_start(),i2c_rep_start() */
|
||||
#define I2C_READ 1
|
||||
/** defines the data direction (writing to I2C device) in i2c_start(),i2c_rep_start() */
|
||||
#define I2C_WRITE 0
|
||||
|
||||
/**
|
||||
@brief Terminates the data transfer and releases the I2C bus
|
||||
@param void
|
||||
@return none
|
||||
*/
|
||||
extern void i2c_stop(void);
|
||||
/**
|
||||
@brief Issues a start condition and sends address and transfer direction
|
||||
|
||||
@param addr address and transfer direction of I2C device
|
||||
@retval 0 device accessible
|
||||
@retval 1 failed to access device
|
||||
*/
|
||||
extern unsigned char i2c_start(unsigned char addr);
|
||||
/**
|
||||
@brief Issues a start condition and sends address and transfer direction
|
||||
|
||||
If device is busy, use ack polling to wait until device ready
|
||||
@param addr address and transfer direction of I2C device
|
||||
@return none
|
||||
*/
|
||||
extern void i2c_start_wait(unsigned char addr);
|
||||
/**
|
||||
@brief Send one byte to I2C device
|
||||
@param data byte to be transfered
|
||||
@retval 0 write successful
|
||||
@retval 1 write failed
|
||||
*/
|
||||
extern unsigned char i2c_write(unsigned char data);
|
||||
/**
|
||||
@brief read one byte from the I2C device, request more data from device
|
||||
@return byte read from I2C device
|
||||
*/
|
||||
extern unsigned char i2c_readAck(void);
|
||||
/**
|
||||
@brief read one byte from the I2C device, read is followed by a stop condition
|
||||
@return byte read from I2C device
|
||||
*/
|
||||
extern unsigned char i2c_readNak(void);
|
||||
/**
|
||||
@brief read one byte from the I2C device
|
||||
|
||||
Implemented as a macro, which calls either i2c_readAck or i2c_readNak
|
||||
|
||||
@param ack 1 send ack, request more data from device<br>
|
||||
0 send nak, read is followed by a stop condition
|
||||
@return byte read from I2C device
|
||||
*/
|
||||
extern unsigned char i2c_read(unsigned char ack);
|
||||
#define i2c_read(ack) (ack) ? i2c_readAck() : i2c_readNak();
|
||||
/**@}*/
|
||||
|
||||
|
||||
|
||||
//extern const int matrixActions[] PROGMEM;
|
||||
// Key codes
|
||||
#define UI_KEYS_INIT_CLICKENCODER_LOW(pinA,pinB) SET_INPUT(pinA);SET_INPUT(pinB); WRITE(pinA,HIGH);WRITE(pinB,HIGH);
|
||||
#define UI_KEYS_INIT_BUTTON_LOW(pin) SET_INPUT(pin);WRITE(pin,HIGH);
|
||||
#define UI_KEYS_INIT_CLICKENCODER_HIGH(pinA,pinB) SET_INPUT(pinA);SET_INPUT(pinB); WRITE(pinA,LOW);WRITE(pinB,LOW);
|
||||
#define UI_KEYS_INIT_BUTTON_HIGH(pin) SET_INPUT(pin);WRITE(pin,LOW);
|
||||
|
||||
#define UI_KEYS_CLICKENCODER_LOW(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (!READ(pinA)) uid.encoderLast |=2;if (!READ(pinB)) uid.encoderLast |=1; uid.encoderPos += pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_CLICKENCODER_LOW_REV(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (!READ(pinA)) uid.encoderLast |=2;if (!READ(pinB)) uid.encoderLast |=1; uid.encoderPos -= pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_BUTTON_LOW(pin,action_) if(READ(pin)==0) action=action_;
|
||||
#define UI_KEYS_CLICKENCODER_HIGH(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (READ(pinA)) uid.encoderLast |=2;if (READ(pinB)) uid.encoderLast |=1; uid.encoderPos += pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_CLICKENCODER_HIGH_REV(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (READ(pinA)) uid.encoderLast |=2;if (READ(pinB)) uid.encoderLast |=1; uid.encoderPos -= pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_BUTTON_HIGH(pin,action_) if(READ(pin)!=0) action=action_;
|
||||
#define UI_KEYS_INIT_MATRIX(r1,r2,r3,r4,c1,c2,c3,c4) if(c1>=0){SET_INPUT(c1);WRITE(c1,HIGH);}if(c2>=0){SET_INPUT(c2);WRITE(c2,HIGH);}if(c3>=0){SET_INPUT(c3);WRITE(c3,HIGH);}\
|
||||
if(c4>=0) {SET_INPUT(c4);WRITE(c4,HIGH);}if(r1>=0)SET_OUTPUT(r1);if(r2>=0)SET_OUTPUT(r2);if(r3>=0)SET_OUTPUT(r3);if(r4>=0)SET_OUTPUT(r4);\
|
||||
if(r1>=0)WRITE(r1,LOW);if(r2>=0)WRITE(r2,LOW);if(r3>=0)WRITE(r3,LOW);if(r4>=0)WRITE(r4,LOW);
|
||||
// out.print_int_P(PSTR("r4=>c1:"),READ(c1));out.print_int_P(PSTR(" c2:"),READ(c2));out.print_int_P(PSTR(" c3:"),READ(c3));out.println_int_P(PSTR(" c4:"),READ(c4));
|
||||
#define UI_KEYS_MATRIX(r1,r2,r3,r4,c1,c2,c3,c4) {byte r = (c1>=0?READ(c1):0) && (c2>=0?READ(c2):0) && (c3>=0?READ(c3):0) && (c4>=0?READ(c4):0);\
|
||||
if(!r) {\
|
||||
r = 255;\
|
||||
if(r2>=0)WRITE(r2,HIGH);if(r3>=0)WRITE(r3,HIGH);if(r4>=0)WRITE(r4,HIGH);\
|
||||
if(r1>=0) {\
|
||||
asm volatile ("nop\nnop\nnop\nnop\nnop");\
|
||||
if(!((c1>=0?READ(c1):1) && (c2>=0?READ(c2):1) && (c3>=0?READ(c3):1) && (c4>=0?READ(c4):1))) r = 0;\
|
||||
else WRITE(r1,HIGH);\
|
||||
}\
|
||||
if(r==255 && r2>=0) {\
|
||||
WRITE(r2,LOW);asm volatile ("nop\nnop\nnop\nnop\nnop");\
|
||||
if(!((c1>=0?READ(c1):1) && (c2>=0?READ(c2):1) && (c3>=0?READ(c3):1) && (c4>=0?READ(c4):1))) r = 4;\
|
||||
else WRITE(r2,HIGH);\
|
||||
}\
|
||||
if(r==255 && r3>=0) {\
|
||||
WRITE(r3,LOW);asm volatile ("nop\nnop\nnop\nnop\nnop");\
|
||||
if(!((c1>=0?READ(c1):0) && (c2>=0?READ(c2):1) && (c3>=0?READ(c3):1) && (c4>=0?READ(c4):1))) r = 8;\
|
||||
else WRITE(r3,HIGH);\
|
||||
}\
|
||||
if(r==255 && r4>=0) {\
|
||||
WRITE(r4,LOW);asm volatile ("nop\nnop\nnop\nnop\nnop");\
|
||||
if(!((c1>=0?READ(c1):1) && (c2>=0?READ(c2):1) && (c3>=0?READ(c3):1) && (c4>=0?READ(c4):1))) r = 12;\
|
||||
else WRITE(r4,HIGH);\
|
||||
}\
|
||||
if(c2>=0 && !READ(c2)) r+=1;\
|
||||
else if(c3>=0 && !READ(c3)) r+=2;\
|
||||
else if(c4>=0 && !READ(c4)) r+=3;\
|
||||
if(r<16) {action = pgm_read_word(&(matrixActions[r]));}\
|
||||
}if(r1>=0)WRITE(r1,LOW);if(r2>=0)WRITE(r2,LOW);if(r3>=0)WRITE(r3,LOW);if(r4>=0)WRITE(r4,LOW);}
|
||||
// I2C keymask tests
|
||||
#define UI_KEYS_I2C_CLICKENCODER_LOW(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (!(keymask & pinA)) uid.encoderLast |=2;if (!(keymask & pinB)) uid.encoderLast |=1; uid.encoderPos += pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_I2C_CLICKENCODER_LOW_REV(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (!(keymask & pinA)) uid.encoderLast |=2;if (!(keymask & pinB)) uid.encoderLast |=1; uid.encoderPos -= pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_I2C_BUTTON_LOW(pin,action_) if((keymask & pin)==0) action=action_;
|
||||
#define UI_KEYS_I2C_CLICKENCODER_HIGH(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (keymask & pinA) uid.encoderLast |=2;if (keymask & pinB) uid.encoderLast |=1; uid.encoderPos += pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_I2C_CLICKENCODER_HIGH_REV(pinA,pinB) uid.encoderLast = (uid.encoderLast << 2) & 0x0F;if (keymask & pinA) uid.encoderLast |=2;if (keymask & pinB) uid.encoderLast |=1; uid.encoderPos -= pgm_read_byte(&encoder_table[uid.encoderLast]);
|
||||
#define UI_KEYS_I2C_BUTTON_HIGH(pin,action_) if((pin & keymask)!=0) action=action_;
|
||||
|
||||
#define UI_STRING(name,text) const char PROGMEM name[] = text;
|
||||
|
||||
#define UI_PAGE4(name,row1,row2,row3,row4) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);UI_STRING(name ## _3txt,row3);UI_STRING(name ## _4txt,row4);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0};\
|
||||
const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\
|
||||
const UIMenu name PROGMEM = {0,0,4,name ## _entries};
|
||||
#define UI_PAGE2(name,row1,row2) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\
|
||||
const UIMenu name PROGMEM = {0,0,2,name ## _entries};
|
||||
#define UI_MENU_ACTION4C(name,action,rows) UI_MENU_ACTION4(name,action,rows)
|
||||
#define UI_MENU_ACTION2C(name,action,rows) UI_MENU_ACTION2(name,action,rows)
|
||||
#define UI_MENU_ACTION4(name,action,row1,row2,row3,row4) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);UI_STRING(name ## _3txt,row3);UI_STRING(name ## _4txt,row4);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0};\
|
||||
UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0};\
|
||||
UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\
|
||||
const UIMenu name PROGMEM = {3,action,4,name ## _entries};
|
||||
#define UI_MENU_ACTION2(name,action,row1,row2) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);\
|
||||
UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0};\
|
||||
UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0};\
|
||||
const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\
|
||||
const UIMenu name PROGMEM = {3,action,2,name ## _entries};
|
||||
#define UI_MENU_HEADLINE(name,text) UI_STRING(name ## _txt,text);UIMenuEntry name PROGMEM = {name ## _txt,1,0};
|
||||
#define UI_MENU_CHANGEACTION(name,row,action) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,4,action};
|
||||
#define UI_MENU_ACTIONCOMMAND(name,row,action) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,3,action};
|
||||
#define UI_MENU_ACTIONSELECTOR(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries};
|
||||
#define UI_MENU_SUBMENU(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries};
|
||||
#define UI_MENU(name,items,itemsCnt) const UIMenuEntry * const name ## _entries[] PROGMEM = items;const UIMenu name PROGMEM = {2,0,itemsCnt,name ## _entries}
|
||||
#define UI_MENU_FILESELECT(name,items,itemsCnt) const UIMenuEntry *name ## _entries[] PROGMEM = items;const UIMenu name PROGMEM = {1,0,itemsCnt,name ## _entries}
|
||||
|
||||
#if FEATURE_CONTROLLER==2 // reprapdiscount smartcontroller has a sd card buildin
|
||||
#undef SDCARDDETECT
|
||||
#define SDCARDDETECT 49
|
||||
#undef SDCARDDETECTINVERTED
|
||||
#define SDCARDDETECTINVERTED false
|
||||
#undef SDSUPPORT
|
||||
#define SDSUPPORT true
|
||||
#endif
|
||||
|
||||
class UIDisplay {
|
||||
public:
|
||||
volatile byte flags; // 1 = fast key action, 2 = slow key action, 4 = slow action running, 8 = key test running
|
||||
byte col; // current col for buffer prefill
|
||||
byte menuLevel; // current menu level, 0 = info, 1 = group, 2 = groupdata select, 3 = value change
|
||||
byte menuPos[5]; // Positions in menu
|
||||
void *menu[5]; // Menus active
|
||||
byte menuTop[5]; // Top row in menu
|
||||
int pageDelay; // Counter. If 0 page is refreshed if menuLevel is 0.
|
||||
void *errorMsg;
|
||||
unsigned int activeAction; // action for ok/next/previous
|
||||
unsigned int lastAction;
|
||||
unsigned long lastSwitch; // Last time display switched pages
|
||||
unsigned long lastRefresh;
|
||||
unsigned int lastButtonAction;
|
||||
unsigned long lastButtonStart;
|
||||
unsigned long nextRepeat; // Time of next autorepeat
|
||||
unsigned int outputMask; // Output mask for backlight, leds etc.
|
||||
int repeatDuration; // Time beween to actions if autorepeat is enabled
|
||||
void addInt(int value,byte digits); // Print int into printCols
|
||||
void addLong(long value,char digits);
|
||||
void addFloat(float number, char fixdigits,byte digits);
|
||||
void addStringP(PGM_P text);
|
||||
void okAction();
|
||||
void nextPreviousAction(char next);
|
||||
char statusMsg[17];
|
||||
char encoderPos;
|
||||
int8_t encoderLast;
|
||||
PGM_P statusText;
|
||||
UIDisplay();
|
||||
void createChar(byte location,const byte charmap[]);
|
||||
void initialize(); // Initialize display and keys
|
||||
void printRow(byte r,char *txt); // Print row on display
|
||||
void printRowP(byte r,PGM_P txt);
|
||||
void parse(char *txt,bool ram); /// Parse output and write to printCols;
|
||||
void refreshPage();
|
||||
void executeAction(int action);
|
||||
void finishAction(int action);
|
||||
void slowAction();
|
||||
void fastAction();
|
||||
void mediumAction();
|
||||
void pushMenu(void *men,bool refresh);
|
||||
void setStatusP(PGM_P txt);
|
||||
void setStatus(char *txt);
|
||||
inline void setOutputMaskBits(unsigned int bits) {outputMask|=bits;}
|
||||
inline void unsetOutputMaskBits(unsigned int bits) {outputMask&=~bits;}
|
||||
#if SDSUPPORT
|
||||
void updateSDFileCount();
|
||||
void sdrefresh(byte &r);
|
||||
void goDir(char *name);
|
||||
bool isDirname(char *name);
|
||||
char cwd[SD_MAX_FOLDER_DEPTH*13+2];
|
||||
byte folderLevel;
|
||||
#endif
|
||||
};
|
||||
extern UIDisplay uid;
|
||||
|
||||
|
||||
#if FEATURE_CONTROLLER==1
|
||||
#include "uiconfig.h"
|
||||
#endif
|
||||
#if FEATURE_CONTROLLER==0 // No controller at all
|
||||
#define UI_HAS_KEYS 0
|
||||
#define UI_DISPLAY_TYPE 0
|
||||
#ifdef UI_MAIN
|
||||
void ui_init_keys() {}
|
||||
void ui_check_keys(int &action) {}
|
||||
inline void ui_check_slow_encoder() {}
|
||||
void ui_check_slow_keys(int &action) {}
|
||||
#endif
|
||||
#endif
|
||||
#if FEATURE_CONTROLLER==2 // reprapdiscount smartcontroller
|
||||
#define UI_HAS_KEYS 1
|
||||
#define UI_HAS_BACK_KEY 0
|
||||
#define UI_DISPLAY_TYPE 1
|
||||
#define UI_DISPLAY_CHARSET 1
|
||||
#define BEEPER_TYPE 1
|
||||
#define UI_COLS 20
|
||||
#define UI_ROWS 4
|
||||
#if MOTHERBOARD==80 // Rumba has different pins as RAMPS!
|
||||
#define BEEPER_PIN 44
|
||||
#define UI_DISPLAY_RS_PIN 19
|
||||
#define UI_DISPLAY_RW_PIN -1
|
||||
#define UI_DISPLAY_ENABLE_PIN 42
|
||||
#define UI_DISPLAY_D0_PIN 18
|
||||
#define UI_DISPLAY_D1_PIN 38
|
||||
#define UI_DISPLAY_D2_PIN 41
|
||||
#define UI_DISPLAY_D3_PIN 40
|
||||
#define UI_DISPLAY_D4_PIN 18
|
||||
#define UI_DISPLAY_D5_PIN 38
|
||||
#define UI_DISPLAY_D6_PIN 41
|
||||
#define UI_DISPLAY_D7_PIN 40
|
||||
#define UI_ENCODER_A 12
|
||||
#define UI_ENCODER_B 11
|
||||
#define UI_ENCODER_CLICK 43
|
||||
#define UI_RESET_PIN 46
|
||||
#else
|
||||
#define BEEPER_PIN 37
|
||||
#define UI_DISPLAY_RS_PIN 16
|
||||
#define UI_DISPLAY_RW_PIN -1
|
||||
#define UI_DISPLAY_ENABLE_PIN 17
|
||||
#define UI_DISPLAY_D0_PIN 23
|
||||
#define UI_DISPLAY_D1_PIN 25
|
||||
#define UI_DISPLAY_D2_PIN 27
|
||||
#define UI_DISPLAY_D3_PIN 29
|
||||
#define UI_DISPLAY_D4_PIN 23
|
||||
#define UI_DISPLAY_D5_PIN 25
|
||||
#define UI_DISPLAY_D6_PIN 27
|
||||
#define UI_DISPLAY_D7_PIN 29
|
||||
#define UI_ENCODER_A 33
|
||||
#define UI_ENCODER_B 31
|
||||
#define UI_ENCODER_CLICK 35
|
||||
#define UI_RESET_PIN 41
|
||||
#endif
|
||||
#define UI_DELAYPERCHAR 320
|
||||
#define UI_INVERT_MENU_DIRECTION false
|
||||
#ifdef UI_MAIN
|
||||
void ui_init_keys() {
|
||||
UI_KEYS_INIT_CLICKENCODER_LOW(UI_ENCODER_A,UI_ENCODER_B); // click encoder on pins 47 and 45. Phase is connected with gnd for signals.
|
||||
UI_KEYS_INIT_BUTTON_LOW(UI_ENCODER_CLICK); // push button, connects gnd to pin
|
||||
UI_KEYS_INIT_BUTTON_LOW(UI_RESET_PIN); // Kill pin
|
||||
}
|
||||
void ui_check_keys(int &action) {
|
||||
UI_KEYS_CLICKENCODER_LOW_REV(UI_ENCODER_A,UI_ENCODER_B); // click encoder on pins 47 and 45. Phase is connected with gnd for signals.
|
||||
UI_KEYS_BUTTON_LOW(UI_ENCODER_CLICK,UI_ACTION_OK); // push button, connects gnd to pin
|
||||
UI_KEYS_BUTTON_LOW(UI_RESET_PIN,UI_ACTION_RESET);
|
||||
}
|
||||
inline void ui_check_slow_encoder() {}
|
||||
void ui_check_slow_keys(int &action) {}
|
||||
#endif
|
||||
#endif // Controller 2
|
||||
|
||||
#if FEATURE_CONTROLLER==3 // Adafruit RGB controller
|
||||
#define UI_HAS_KEYS 1
|
||||
#define UI_HAS_BACK_KEY 1
|
||||
#define UI_DISPLAY_TYPE 3
|
||||
#define UI_DISPLAY_CHARSET 1
|
||||
#define UI_COLS 16
|
||||
#define UI_ROWS 2
|
||||
#define UI_DISPLAY_I2C_CHIPTYPE 1
|
||||
#define UI_DISPLAY_I2C_ADDRESS 0x40
|
||||
#define UI_DISPLAY_I2C_OUTPUT_PINS 65504
|
||||
#define UI_DISPLAY_I2C_OUTPUT_START_MASK 0
|
||||
#define UI_DISPLAY_I2C_PULLUP 31
|
||||
#define UI_I2C_CLOCKSPEED 400000L
|
||||
#define UI_DISPLAY_RS_PIN _BV(15)
|
||||
#define UI_DISPLAY_RW_PIN _BV(14)
|
||||
#define UI_DISPLAY_ENABLE_PIN _BV(13)
|
||||
#define UI_DISPLAY_D0_PIN _BV(12)
|
||||
#define UI_DISPLAY_D1_PIN _BV(11)
|
||||
#define UI_DISPLAY_D2_PIN _BV(10)
|
||||
#define UI_DISPLAY_D3_PIN _BV(9)
|
||||
#define UI_DISPLAY_D4_PIN _BV(12)
|
||||
#define UI_DISPLAY_D5_PIN _BV(11)
|
||||
#define UI_DISPLAY_D6_PIN _BV(10)
|
||||
#define UI_DISPLAY_D7_PIN _BV(9)
|
||||
#define UI_INVERT_MENU_DIRECTION true
|
||||
#define UI_HAS_I2C_KEYS
|
||||
#define UI_HAS_I2C_ENCODER 0
|
||||
#define UI_I2C_KEY_ADDRESS 0x40
|
||||
#ifdef UI_MAIN
|
||||
void ui_init_keys() {}
|
||||
void ui_check_keys(int &action) {}
|
||||
inline void ui_check_slow_encoder() {
|
||||
i2c_start_wait(UI_DISPLAY_I2C_ADDRESS+I2C_WRITE);
|
||||
i2c_write(0x12); // GIOA
|
||||
i2c_stop();
|
||||
i2c_start_wait(UI_DISPLAY_I2C_ADDRESS+I2C_READ);
|
||||
unsigned int keymask = i2c_readAck();
|
||||
keymask = keymask + (i2c_readNak()<<8);
|
||||
i2c_stop();
|
||||
}
|
||||
void ui_check_slow_keys(int &action) {
|
||||
i2c_start_wait(UI_DISPLAY_I2C_ADDRESS+I2C_WRITE);
|
||||
i2c_write(0x12); // GPIOA
|
||||
i2c_stop();
|
||||
i2c_start_wait(UI_DISPLAY_I2C_ADDRESS+I2C_READ);
|
||||
unsigned int keymask = i2c_readAck();
|
||||
keymask = keymask + (i2c_readNak()<<8);
|
||||
i2c_stop();
|
||||
UI_KEYS_I2C_BUTTON_LOW(4,UI_ACTION_PREVIOUS); // Up button
|
||||
UI_KEYS_I2C_BUTTON_LOW(8,UI_ACTION_NEXT); // down button
|
||||
UI_KEYS_I2C_BUTTON_LOW(16,UI_ACTION_BACK); // left button
|
||||
UI_KEYS_I2C_BUTTON_LOW(2,UI_ACTION_OK); // right button
|
||||
UI_KEYS_I2C_BUTTON_LOW(1,UI_ACTION_MENU_QUICKSETTINGS); //Select button
|
||||
}
|
||||
#endif
|
||||
#endif // Controller 3
|
||||
|
||||
#if FEATURE_CONTROLLER==4 // Foltyn 3D Master
|
||||
#define UI_HAS_KEYS 1
|
||||
#define UI_HAS_BACK_KEY 1
|
||||
#define UI_DISPLAY_TYPE 1
|
||||
#define UI_DISPLAY_CHARSET 2
|
||||
#define UI_COLS 20
|
||||
#define UI_ROWS 4
|
||||
#define UI_DISPLAY_RS_PIN 63 // PINK.1, 88, D_RS
|
||||
#define UI_DISPLAY_RW_PIN -1
|
||||
#define UI_DISPLAY_ENABLE_PIN 65 // PINK.3, 86, D_E
|
||||
#define UI_DISPLAY_D0_PIN 59 // PINF.5, 92, D_D4
|
||||
#define UI_DISPLAY_D1_PIN 64 // PINK.2, 87, D_D5
|
||||
#define UI_DISPLAY_D2_PIN 44 // PINL.5, 40, D_D6
|
||||
#define UI_DISPLAY_D3_PIN 66 // PINK.4, 85, D_D7
|
||||
#define UI_DISPLAY_D4_PIN 59 // PINF.5, 92, D_D4
|
||||
#define UI_DISPLAY_D5_PIN 64 // PINK.2, 87, D_D5
|
||||
#define UI_DISPLAY_D6_PIN 44 // PINL.5, 40, D_D6
|
||||
#define UI_DISPLAY_D7_PIN 66 // PINK.4, 85, D_D7
|
||||
#define UI_DELAYPERCHAR 320
|
||||
#define UI_INVERT_MENU_DIRECTION false
|
||||
#ifdef UI_MAIN
|
||||
void ui_init_keys() {
|
||||
UI_KEYS_INIT_BUTTON_LOW(4); // push button, connects gnd to pin
|
||||
UI_KEYS_INIT_BUTTON_LOW(5);
|
||||
UI_KEYS_INIT_BUTTON_LOW(6);
|
||||
UI_KEYS_INIT_BUTTON_LOW(11);
|
||||
UI_KEYS_INIT_BUTTON_LOW(42);
|
||||
}
|
||||
void ui_check_keys(int &action) {
|
||||
UI_KEYS_BUTTON_LOW(4,UI_ACTION_OK); // push button, connects gnd to pin
|
||||
UI_KEYS_BUTTON_LOW(5,UI_ACTION_NEXT); // push button, connects gnd to pin
|
||||
UI_KEYS_BUTTON_LOW(6,UI_ACTION_PREVIOUS); // push button, connects gnd to pin
|
||||
UI_KEYS_BUTTON_LOW(11,UI_ACTION_BACK); // push button, connects gnd to pin
|
||||
UI_KEYS_BUTTON_LOW(42,UI_ACTION_SD_PRINT ); // push button, connects gnd to pin
|
||||
}
|
||||
inline void ui_check_slow_encoder() {}
|
||||
void ui_check_slow_keys(int &action) {}
|
||||
#endif
|
||||
#endif // Controller 4
|
||||
|
||||
|
||||
#if FEATURE_CONTROLLER>0
|
||||
|
||||
#if UI_ROWS==4
|
||||
#if UI_COLS==16
|
||||
#define UI_LINE_OFFSETS {0,0x40,0x10,0x50} // 4x16
|
||||
#elif UI_COLS==20
|
||||
//#define UI_LINE_OFFSETS {0,0x20,0x40,0x60} // 4x20 with KS0073
|
||||
#define UI_LINE_OFFSETS {0,0x40,0x14,0x54} // 4x20 with HD44780
|
||||
#else
|
||||
#error Unknown combination off rows/columns - define UI_LINE_OFFSETS manually.
|
||||
#endif
|
||||
#else
|
||||
#define UI_LINE_OFFSETS {0,0x40,0x10,0x50} // 2x16, 2x20, 2x24
|
||||
#endif
|
||||
#include "uilang.h"
|
||||
#include "uimenu.h"
|
||||
#endif
|
||||
|
||||
#define UI_VERSION_STRING "Repetier " REPETIER_VERSION
|
||||
|
||||
#ifdef UI_HAS_I2C_KEYS
|
||||
#define COMPILE_I2C_DRIVER
|
||||
#endif
|
||||
|
||||
#if UI_DISPLAY_TYPE!=0
|
||||
|
||||
|
||||
#if UI_DISPLAY_TYPE==3
|
||||
#define COMPILE_I2C_DRIVER
|
||||
#endif
|
||||
|
||||
#ifndef UI_TEMP_PRECISION
|
||||
#if UI_COLS>16
|
||||
#define UI_TEMP_PRECISION 1
|
||||
#else
|
||||
#define UI_TEMP_PRECISION 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define UI_INITIALIZE uid.initialize();
|
||||
#define UI_FAST if(pwm_count & 4) {uid.fastAction();}
|
||||
#define UI_MEDIUM uid.mediumAction();
|
||||
#define UI_SLOW uid.slowAction();
|
||||
#define UI_STATUS(status) uid.setStatusP(PSTR(status));
|
||||
#define UI_STATUS_UPD(status) {uid.setStatusP(PSTR(status));uid.refreshPage();}
|
||||
#define UI_STATUS_RAM(status) uid.setStatus(status);
|
||||
#define UI_STATUS_UPD_RAM(status) {uid.setStatus(status);uid.refreshPage();}
|
||||
#define UI_ERROR(msg) {uid.errorMsg=PSTR(msg);pushMenu((void*)&ui_menu_error,true);}
|
||||
#define UI_CLEAR_STATUS {uid.statusMsg[0]=0;}
|
||||
#else
|
||||
#define UI_INITIALIZE {}
|
||||
#define UI_FAST {}
|
||||
#define UI_MEDIUM {}
|
||||
#define UI_SLOW {}
|
||||
#define UI_STATUS(status) {}
|
||||
#define UI_STATUS_UPD(status) {}
|
||||
#define UI_CLEAR_STATUS {}
|
||||
#define UI_ERROR(msg) {}
|
||||
#define UI_STATUS_UPD_RAM(status) {}
|
||||
#endif // Display
|
||||
|
||||
// Beeper methods
|
||||
#if BEEPER_TYPE==0
|
||||
#define BEEP_SHORT {}
|
||||
#define BEEP_LONG {}
|
||||
#else
|
||||
#define BEEP_SHORT beep(BEEPER_SHORT_SEQUENCE);
|
||||
#define BEEP_LONG beep(BEEPER_LONG_SEQUENCE);
|
||||
#endif
|
||||
extern void beep(byte duration,byte count);
|
||||
|
||||
#endif
|
||||
|
||||
388
Repetier/uiconfig.h
Normal file
388
Repetier/uiconfig.h
Normal file
|
|
@ -0,0 +1,388 @@
|
|||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Repetier-Firmware is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
|
||||
/* ===================== IMPORTANT ========================
|
||||
|
||||
The LCD and Key support is new. I tested everything as good as possible,
|
||||
but some combinations may not work as supposed.
|
||||
The I2C methods rely on a stable I2C connection. Noise may cause wrong signals
|
||||
which can cause the firmware to freeze.
|
||||
|
||||
The ui adds quite some code, so AVRs with 64kB ram (Sanguino, Gen6) can not handle all features
|
||||
of the firmware at the same time. You have to disable some features to gain the
|
||||
ram needed. What should work:
|
||||
- No sd card - the sd card code is quite large.
|
||||
- No keys attached - The longest part is the menu handling.
|
||||
- EEPROM_MODE 0 and USE_OPS 0.
|
||||
|
||||
Currently supported hardware:
|
||||
|
||||
*** Displays ***
|
||||
|
||||
- direct connected lcd with 4 data lines
|
||||
- connected via i2c
|
||||
|
||||
*** Keys ***
|
||||
|
||||
- rotary encoder
|
||||
- push button
|
||||
- key matrix up to 4x4
|
||||
- rotary encoder via i2c (only slow turns are captured correct)
|
||||
- push button via i2c
|
||||
|
||||
*** Buzzer ***
|
||||
|
||||
- directly connected, high = on
|
||||
- connected via i2c, low = on
|
||||
|
||||
==============================================================*/
|
||||
|
||||
|
||||
/** While the ascii chars are all the same, the driver have different charsets
|
||||
for special chars used in different countries. The charset allows to fix for
|
||||
this problem. If characters look wrong, try a different charset. If nothing
|
||||
works, use the ascii charset 0 as fallback. Not the nicest for everything but working!
|
||||
|
||||
0 = ASCII fallback
|
||||
1 = Default works on most displays. This has some japanese chars in charset
|
||||
2 = Alternative charset with more european chars
|
||||
|
||||
*/
|
||||
#define UI_DISPLAY_CHARSET 1
|
||||
|
||||
/** Select type of beeper
|
||||
0 = none
|
||||
1 = Piezo connected to pin
|
||||
2 = Piezo connected to a pin over I2C
|
||||
*/
|
||||
#ifndef BEEPER_TYPE
|
||||
#define BEEPER_TYPE 1
|
||||
#endif
|
||||
|
||||
#if BEEPER_TYPE==1 && !defined(BEEPER_PIN)
|
||||
#define BEEPER_PIN 79
|
||||
#endif
|
||||
#if BEEPER_TYPE==2
|
||||
#define BEEPER_ADDRESS 0x40 // I2C address of the chip with the beeper pin
|
||||
#define BEEPER_PIN _BV(7) // Bit value for pin 8
|
||||
#define COMPILE_I2C_DRIVER // We need the I2C driver as we are using i2c
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
What display type do you use?
|
||||
0 = No display
|
||||
1 = LCD Display with 4 bit data bus
|
||||
2 = LCD Display with 8 bit data bus (currently not implemented, fallback to 1)
|
||||
3 = LCD Display with I2C connection, 4 bit mode
|
||||
4 = Use the slower LiquiedCrystal library bundled with arduino.
|
||||
IMPORTANT: You need to uncomment the LiquidCrystal include in Repetier.pde for it to work.
|
||||
If you have Sanguino and want to use the library, you need to have Arduino 023 or older. (13.04.2012)
|
||||
*/
|
||||
#define UI_DISPLAY_TYPE 1
|
||||
|
||||
/** Number of columns per row
|
||||
|
||||
Typical values are 16 and 20
|
||||
*/
|
||||
#define UI_COLS 20
|
||||
/**
|
||||
Rows of your display. 2 or 4
|
||||
*/
|
||||
#define UI_ROWS 4
|
||||
|
||||
/* What type of chip is used for I2C communication
|
||||
0 : PCF8574 or PCF8574A or compatible chips.
|
||||
1 : MCP23017
|
||||
*/
|
||||
#define UI_DISPLAY_I2C_CHIPTYPE 0
|
||||
// 0x40 till 0x4e for PCF8574, 0x40 for the adafruid RGB shield, 0x40 - 0x4e for MCP23017
|
||||
// Official addresses have a value twice as high!
|
||||
#define UI_DISPLAY_I2C_ADDRESS 0x4e
|
||||
// For MCP 23017 define which pins should be output
|
||||
#define UI_DISPLAY_I2C_OUTPUT_PINS 65504
|
||||
// Set the output mask that is or'd over the output data. This is needed to activate
|
||||
// a backlight switched over the I2C.
|
||||
// The adafruit RGB shields enables a light if the bit is not set. Bits 6-8 are used for backlight.
|
||||
#define UI_DISPLAY_I2C_OUTPUT_START_MASK 0
|
||||
// For MCP which inputs are with pullup. 31 = pins 0-4 for adafruid rgb shield buttons
|
||||
#define UI_DISPLAY_I2C_PULLUP 31
|
||||
/* How fast should the I2C clock go. The PCF8574 work only with the lowest setting 100000.
|
||||
A MCP23017 can run also with 400000 Hz */
|
||||
#define UI_I2C_CLOCKSPEED 100000L
|
||||
/**
|
||||
Define the pin
|
||||
*/
|
||||
#if UI_DISPLAY_TYPE==3 // I2C Pin configuration
|
||||
#define UI_DISPLAY_RS_PIN _BV(4)
|
||||
#define UI_DISPLAY_RW_PIN _BV(5)
|
||||
#define UI_DISPLAY_ENABLE_PIN _BV(6)
|
||||
#define UI_DISPLAY_D0_PIN _BV(0)
|
||||
#define UI_DISPLAY_D1_PIN _BV(1)
|
||||
#define UI_DISPLAY_D2_PIN _BV(2)
|
||||
#define UI_DISPLAY_D3_PIN _BV(3)
|
||||
#define UI_DISPLAY_D4_PIN _BV(0)
|
||||
#define UI_DISPLAY_D5_PIN _BV(1)
|
||||
#define UI_DISPLAY_D6_PIN _BV(2)
|
||||
#define UI_DISPLAY_D7_PIN _BV(3)
|
||||
|
||||
// Pins for adafruid RGB shield
|
||||
/*#define UI_DISPLAY_RS_PIN _BV(15)
|
||||
#define UI_DISPLAY_RW_PIN _BV(14)
|
||||
#define UI_DISPLAY_ENABLE_PIN _BV(13)
|
||||
#define UI_DISPLAY_D0_PIN _BV(12)
|
||||
#define UI_DISPLAY_D1_PIN _BV(11)
|
||||
#define UI_DISPLAY_D2_PIN _BV(10)
|
||||
#define UI_DISPLAY_D3_PIN _BV(9)
|
||||
#define UI_DISPLAY_D4_PIN _BV(12)
|
||||
#define UI_DISPLAY_D5_PIN _BV(11)
|
||||
#define UI_DISPLAY_D6_PIN _BV(10)
|
||||
#define UI_DISPLAY_D7_PIN _BV(9)*/
|
||||
|
||||
#else // Direct display connections
|
||||
#define UI_DISPLAY_RS_PIN 70//63 // PINK.1, 88, D_RS
|
||||
#define UI_DISPLAY_RW_PIN -1
|
||||
#define UI_DISPLAY_ENABLE_PIN 71// // PINK.3, 86, D_E
|
||||
#define UI_DISPLAY_D0_PIN 72 // PINF.5, 92, D_D4
|
||||
#define UI_DISPLAY_D1_PIN 73 // PINK.2, 87, D_D5
|
||||
#define UI_DISPLAY_D2_PIN 74 // PINL.5, 40, D_D6
|
||||
#define UI_DISPLAY_D3_PIN 75 // PINK.4, 85, D_D7
|
||||
#define UI_DISPLAY_D4_PIN 72 // PINF.5, 92, D_D4
|
||||
#define UI_DISPLAY_D5_PIN 73 // PINK.2, 87, D_D5
|
||||
#define UI_DISPLAY_D6_PIN 74 // PINL.5, 40, D_D6
|
||||
#define UI_DISPLAY_D7_PIN 75 // PINK.4, 85, D_D7
|
||||
#define UI_DELAYPERCHAR 320
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
/** \brief Are some keys connected?
|
||||
|
||||
0 = No keys attached - disables also menu
|
||||
1 = Some keys attached
|
||||
*/
|
||||
#define UI_HAS_KEYS 1
|
||||
|
||||
|
||||
/** \brief Is a back key present.
|
||||
|
||||
If you have menus enabled, you need a method to leave it. If you have a back key, you can always go one level higher.
|
||||
Without a back key, you need to navigate to the back entry in the menu. Setting this value to 1 removes the back entry.
|
||||
*/
|
||||
#define UI_HAS_BACK_KEY 0
|
||||
|
||||
/* Then you have the next/previous keys more like up/down keys, it may be more intuitive to change the direction you skip through the menus.
|
||||
If you set it to true, next will go to previous menu instead of the next menu.
|
||||
|
||||
*/
|
||||
#define UI_INVERT_MENU_DIRECTION false
|
||||
|
||||
/** Uncomment this, if you have keys connected via i2c to a PCF8574 chip. */
|
||||
//#define UI_HAS_I2C_KEYS
|
||||
|
||||
// Do you have a I2C connected encoder?
|
||||
#define UI_HAS_I2C_ENCODER 0
|
||||
|
||||
// Under which address can the key status requested. This is the address of your PCF8574 where the keys are connected.
|
||||
// If you use a MCP23017 the address from display is used also for keys.
|
||||
#define UI_I2C_KEY_ADDRESS 0x40
|
||||
|
||||
|
||||
#ifdef UI_MAIN
|
||||
/* #######################################################################
|
||||
Key definitions
|
||||
|
||||
The firmware is very flexible regarding your input methods. You can use one
|
||||
or more of the predefined key macros, to define a mapper. If no matching mapper
|
||||
is available, you can add you c-code for mapping directly into the keyboard
|
||||
routines. The predefined macros do the same, just hiding the code behind it.
|
||||
|
||||
For each key, two seperate parts must be defined. The first is the initialization
|
||||
which must be added inside ui_init_keys() and the second ist a testing routine.
|
||||
These come into ui_check_keys() or ui_check_slow_keys() depending on the time needed
|
||||
for testing. If you are in doubt, put it in ui_check_slow_keys().
|
||||
ui_init_keys() is called from an interrupt controlling the extruder, so only
|
||||
fast tests should be put there.
|
||||
The detect methods need an action identifier. A list of supported ids is found
|
||||
at the beginning of ui.h It's best to use the symbol name, in case the value changes.
|
||||
|
||||
1. Simple push button connected to gnd if closed on a free arduino pin
|
||||
init -> UI_KEYS_INIT_BUTTON_LOW(pinNumber);
|
||||
detect -> UI_KEYS_BUTTON_LOW(pinNumber,action);
|
||||
|
||||
2. Simple push button connected to 5v if closed on a free arduino pin
|
||||
init -> UI_KEYS_INIT_BUTTON_HIGH(pinNumber);
|
||||
detect -> UI_KEYS_BUTTON_HIGH(pinNumber,action);
|
||||
|
||||
3. Click encoder, A/B connected to gnd if closed.
|
||||
init -> UI_KEYS_INIT_CLICKENCODER_LOW(pinA,pinB);
|
||||
detect -> UI_KEYS_CLICKENCODER_LOW(pinA,pinB);
|
||||
or UI_KEYS_CLICKENCODER_LOW_REV(pinA,pinB); // reverse direction
|
||||
If you can move the menu cursor without a click, just be adding some force in one direction,
|
||||
toggle the _REV with non _REV and toggle pins.
|
||||
If the direction is wrong, toggle _REV with non _REV version.
|
||||
For the push button of the encoder use 1.
|
||||
|
||||
4. Click encoder, A/B connected to 5V if closed.
|
||||
init -> UI_KEYS_INIT_CLICKENCODER_HIGH(pinA,pinB);
|
||||
detect -> UI_KEYS_CLICKENCODER_HIGH(pinA,pinB);
|
||||
or UI_KEYS_CLICKENCODER_HIGH_REV(pinA,pinB); // reverse direction
|
||||
If you can move the menu cursor without a click, just be adding some force in one direction,
|
||||
toggle the _REV with non _REV and toggle pins.
|
||||
If the direction is wrong, toggle _REV with non _REV version.
|
||||
For the push button of the encoder use 2.
|
||||
|
||||
5. Maxtrix keyboard with 1-4 rows and 1-4 columns.
|
||||
init -> UI_KEYS_INIT_MATRIX(r1,r2,r3,r4,c1,c2,c3,c4);
|
||||
detect -> UI_KEYS_MATRIX(r1,r2,r3,r4,c1,c2,c3,c4);
|
||||
In addition you have to set UI_MATRIX_ACTIONS to match your desired actions.
|
||||
|
||||
------- Keys connected via I2C -------------
|
||||
|
||||
All keys and the buzzer if present must be on a connected to a single PCF8574 chip!
|
||||
As all I2C request take time, they belong all in ui_check_slow_keys.
|
||||
Dont use the pin ids but instead _BV(pinNumber0_7) as pin id. 0 = First pin
|
||||
|
||||
6. Click encoder, A/B connected to gnd if closed.
|
||||
init -> not needed, but make sure UI_HAS_I2C_KEY is not commented out.
|
||||
detect -> UI_KEYS_I2C_CLICKENCODER_LOW(pinA,pinB);
|
||||
or UI_KEYS_I2C_CLICKENCODER_LOW_REV(pinA,pinB); // reverse direction
|
||||
If you can move the menu cursor without a click, just be adding some force in one direction,
|
||||
toggle the _REV with non _REV and toggle pins.
|
||||
If the direction is wrong, toggle _REV with non _REV version.
|
||||
For the push button of the encoder use 7.
|
||||
NOTICE: The polling frequency is limited, so only slow turns are captured correct!
|
||||
|
||||
7. Simple push button connected to gnd if closed via I2C on a PCF8574
|
||||
init -> not needed, but make sure UI_HAS_I2C_KEY is not commented out.
|
||||
detect -> UI_KEYS_I2C_BUTTON_LOW(pinNumber,action);
|
||||
|
||||
-------- Some notes on actions -------------
|
||||
|
||||
There are three kinds of actions.
|
||||
|
||||
Type 1: Immediate actions - these are execute and forget actions like home/pre-heat
|
||||
Type 2: Parameter change action - these change the mode for next/previous keys. They are valid
|
||||
until a new change action is initiated or the action is finished with ok button.
|
||||
Type 3: Show menu action. These actions have a _MENU_ in their name. If they are executed, a new
|
||||
menu is pushed on the menu stack and you see the menu. If you assign these actions directly
|
||||
to a key, you might not want this pushing behaviour. In this case add UI_ACTION_TOPMENU to the
|
||||
action, like UI_ACTION_TOPMENU+UI_ACTION_MENU_XPOSFAST. That will show the menu as top-menu
|
||||
closing all othe submenus that were open.
|
||||
|
||||
####################################################################### */
|
||||
|
||||
// Use these codes for key detect. The main menu will show the pressed action in the lcd display.
|
||||
// after that assign the desired codes.
|
||||
//#define UI_MATRIX_ACTIONS {2000,2001,2002,2003,2004,2005,2006,2007,2008,2009,2010,2011,2012,2013,2014,2015}
|
||||
// Define your matrix actions
|
||||
#define UI_MATRIX_ACTIONS {UI_ACTION_HOME_ALL, UI_ACTION_TOP_MENU, UI_ACTION_SET_ORIGIN, UI_ACTION_NEXT,\
|
||||
UI_ACTION_HOME_Z, UI_ACTION_MENU_ZPOS, UI_ACTION_COOLDOWN, UI_ACTION_OK,\
|
||||
UI_ACTION_HOME_Y, UI_ACTION_MENU_YPOSFAST, UI_ACTION_PREHEAT_ABS, UI_ACTION_PREVIOUS,\
|
||||
UI_ACTION_HOME_X, UI_ACTION_MENU_XPOSFAST, UI_ACTION_DISABLE_STEPPER, UI_ACTION_BACK}
|
||||
#ifdef UI_MATRIX_ACTIONS
|
||||
const int matrixActions[] PROGMEM = UI_MATRIX_ACTIONS;
|
||||
#endif
|
||||
|
||||
void ui_init_keys() {
|
||||
#if UI_HAS_KEYS!=0
|
||||
UI_KEYS_INIT_CLICKENCODER_LOW(76,77); // click encoder on pins 47 and 45. Phase is connected with gnd for signals.
|
||||
UI_KEYS_INIT_BUTTON_LOW(78);
|
||||
UI_KEYS_INIT_BUTTON_LOW(KILL_PIN);
|
||||
|
||||
// UI_KEYS_INIT_BUTTON_LOW(4); // push button, connects gnd to pin
|
||||
// UI_KEYS_INIT_BUTTON_LOW(5);
|
||||
// UI_KEYS_INIT_BUTTON_LOW(6);
|
||||
// UI_KEYS_INIT_BUTTON_LOW(11);
|
||||
// UI_KEYS_INIT_BUTTON_LOW(42);
|
||||
// UI_KEYS_INIT_CLICKENCODER_LOW(47,45); // click encoder on pins 47 and 45. Phase is connected with gnd for signals.
|
||||
// UI_KEYS_INIT_BUTTON_LOW(43); // push button, connects gnd to pin
|
||||
// UI_KEYS_INIT_MATRIX(32,47,45,43,41,39,37,35);
|
||||
#endif
|
||||
}
|
||||
void ui_check_keys(int &action) {
|
||||
#if UI_HAS_KEYS!=0
|
||||
|
||||
UI_KEYS_CLICKENCODER_LOW_REV(76,77); // click encoder on pins 47 and 45. Phase is connected with gnd for signals.
|
||||
UI_KEYS_BUTTON_LOW(78,UI_ACTION_OK); // push button, connects gnd to pin
|
||||
UI_KEYS_BUTTON_LOW(KILL_PIN,UI_ACTION_KILL); // push button, connects gnd to pin
|
||||
|
||||
// UI_KEYS_BUTTON_LOW(5,UI_ACTION_NEXT); // push button, connects gnd to pin
|
||||
// UI_KEYS_BUTTON_LOW(6,UI_ACTION_PREVIOUS); // push button, connects gnd to pin
|
||||
// UI_KEYS_BUTTON_LOW(11,UI_ACTION_BACK); // push button, connects gnd to pin
|
||||
// UI_KEYS_BUTTON_LOW(42,UI_ACTION_SD_PRINT ); // push button, connects gnd to pin
|
||||
// UI_KEYS_CLICKENCODER_LOW_REV(47,45); // click encoder on pins 47 and 45. Phase is connected with gnd for signals.
|
||||
// UI_KEYS_BUTTON_LOW(43,UI_ACTION_OK); // push button, connects gnd to pin
|
||||
#endif
|
||||
}
|
||||
inline void ui_check_slow_encoder() {
|
||||
#if defined(UI_HAS_I2C_KEYS) && UI_HAS_KEYS!=0
|
||||
#if UI_DISPLAY_I2C_CHIPTYPE==0
|
||||
i2c_start_wait(UI_I2C_KEY_ADDRESS+I2C_READ);
|
||||
byte keymask = i2c_readNak(); // Read current key mask
|
||||
#endif
|
||||
#if UI_DISPLAY_I2C_CHIPTYPE==1
|
||||
i2c_start_wait(UI_DISPLAY_I2C_ADDRESS+I2C_WRITE);
|
||||
i2c_write(0x12); // GIOA
|
||||
i2c_stop();
|
||||
i2c_start_wait(UI_DISPLAY_I2C_ADDRESS+I2C_READ);
|
||||
unsigned int keymask = i2c_readAck();
|
||||
keymask = keymask + (i2c_readNak()<<8);
|
||||
#endif
|
||||
i2c_stop();
|
||||
// Add I2C click encoder tests here, all other i2c tests and a copy of the encoder test belog in ui_check_slow_keys
|
||||
UI_KEYS_I2C_CLICKENCODER_LOW_REV(_BV(2),_BV(0)); // click encoder on pins 0 and 2. Phase is connected with gnd for signals.
|
||||
#endif
|
||||
}
|
||||
void ui_check_slow_keys(int &action) {
|
||||
#if defined(UI_HAS_I2C_KEYS) && UI_HAS_KEYS!=0
|
||||
#if UI_DISPLAY_I2C_CHIPTYPE==0
|
||||
i2c_start_wait(UI_I2C_KEY_ADDRESS+I2C_READ);
|
||||
byte keymask = i2c_readNak(); // Read current key mask
|
||||
#endif
|
||||
#if UI_DISPLAY_I2C_CHIPTYPE==1
|
||||
i2c_start_wait(UI_DISPLAY_I2C_ADDRESS+I2C_WRITE);
|
||||
i2c_write(0x12); // GPIOA
|
||||
i2c_stop();
|
||||
i2c_start_wait(UI_DISPLAY_I2C_ADDRESS+I2C_READ);
|
||||
unsigned int keymask = i2c_readAck();
|
||||
keymask = keymask + (i2c_readNak()<<8);
|
||||
#endif
|
||||
i2c_stop();
|
||||
// Add I2C key tests here
|
||||
UI_KEYS_I2C_CLICKENCODER_LOW_REV(_BV(2),_BV(0)); // click encoder on pins 0 and 2. Phase is connected with gnd for signals.
|
||||
UI_KEYS_I2C_BUTTON_LOW(_BV(1),UI_ACTION_OK); // push button, connects gnd to pin
|
||||
UI_KEYS_I2C_BUTTON_LOW(_BV(3),UI_ACTION_BACK); // push button, connects gnd to pin
|
||||
UI_KEYS_I2C_BUTTON_LOW(_BV(4),UI_ACTION_MENU_QUICKSETTINGS+UI_ACTION_TOPMENU); // push button, connects gnd to pin
|
||||
UI_KEYS_I2C_BUTTON_LOW(_BV(5),UI_ACTION_MENU_EXTRUDER+UI_ACTION_TOPMENU); // push button, connects gnd to pin
|
||||
UI_KEYS_I2C_BUTTON_LOW(_BV(6),UI_ACTION_MENU_POSITIONS+UI_ACTION_TOPMENU); // push button, connects gnd to pin
|
||||
/*
|
||||
// Button handling for the Adafruit RGB shild
|
||||
UI_KEYS_I2C_BUTTON_LOW(4,UI_ACTION_PREVIOUS); // Up button
|
||||
UI_KEYS_I2C_BUTTON_LOW(8,UI_ACTION_NEXT); // down button
|
||||
UI_KEYS_I2C_BUTTON_LOW(16,UI_ACTION_BACK); // left button
|
||||
UI_KEYS_I2C_BUTTON_LOW(2,UI_ACTION_OK); // right button
|
||||
UI_KEYS_I2C_BUTTON_LOW(1,UI_ACTION_MENU_QUICKSETTINGS); //Select button
|
||||
// ----- End RGB shield ----------
|
||||
*/
|
||||
#endif
|
||||
|
||||
//UI_KEYS_MATRIX(32,47,45,43,41,39,37,35);
|
||||
}
|
||||
|
||||
#endif
|
||||
671
Repetier/uilang.h
Normal file
671
Repetier/uilang.h
Normal file
|
|
@ -0,0 +1,671 @@
|
|||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Repetier-Firmware is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
|
||||
#if !defined(UI_DISPLAY_CHARSET) || UI_DISPLAY_CHARSET>2
|
||||
#define UI_DISPLAY_CHARSET 1
|
||||
#endif
|
||||
|
||||
#if UI_DISPLAY_CHARSET==0 // ASCII fallback
|
||||
#define CHAR_RIGHT '-'
|
||||
#define CHAR_SELECTOR '>'
|
||||
#define CHAR_SELECTED '*'
|
||||
#define STR_auml "ae"
|
||||
#define STR_Auml "Ae"
|
||||
#define STR_uuml "ue"
|
||||
#define STR_Uuml "Ue"
|
||||
#define STR_ouml "oe"
|
||||
#define STR_Ouml "Oe"
|
||||
#define STR_szlig "ss"
|
||||
#endif
|
||||
|
||||
#if UI_DISPLAY_CHARSET==1 // HD44870 charset with knji chars
|
||||
#define CHAR_RIGHT 0x7e
|
||||
#define CHAR_SELECTOR '>'
|
||||
#define CHAR_SELECTED '*'
|
||||
#define STR_auml "\xe1"
|
||||
#define STR_Auml "Ae"
|
||||
#define STR_uuml "\365"
|
||||
#define STR_Uuml "Ue"
|
||||
#define STR_ouml "\357"
|
||||
#define STR_Ouml "Oe"
|
||||
#define STR_szlig "\342"
|
||||
#endif
|
||||
|
||||
#if UI_DISPLAY_CHARSET==2 // Western charset
|
||||
#define CHAR_RIGHT 0xbc
|
||||
#define CHAR_SELECTOR 0xf6
|
||||
#define CHAR_SELECTED '*'
|
||||
#define STR_auml "\204"
|
||||
#define STR_Auml "\216"
|
||||
#define STR_uuml "\201"
|
||||
#define STR_Uuml "\212"
|
||||
#define STR_ouml "\204"
|
||||
#define STR_Ouml "\211"
|
||||
#define STR_szlig "160"
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
// At first all terms in english are defined. After that the selected language
|
||||
// can overwrite the definition. That way new strings are at least in english
|
||||
// available.
|
||||
|
||||
#define UI_TEXT_ON "On"
|
||||
#define UI_TEXT_OFF "Off"
|
||||
#define UI_TEXT_NA "N/A" // Output for not available
|
||||
#define UI_TEXT_YES "Yes"
|
||||
#define UI_TEXT_NO "No"
|
||||
#define UI_TEXT_SEL "\003"
|
||||
#define UI_TEXT_NOSEL "\004"
|
||||
#define UI_TEXT_PRINT_POS "Printing..."
|
||||
#define UI_TEXT_PRINTING "Printing"
|
||||
#define UI_TEXT_IDLE "Idle"
|
||||
#define UI_TEXT_NOSDCARD "No SD Card"
|
||||
#define UI_TEXT_ERROR "**** ERROR ****"
|
||||
#define UI_TEXT_BACK "Back \001"
|
||||
#define UI_TEXT_QUICK_SETTINGS "Quick Settings"
|
||||
#define UI_TEXT_CONFIGURATION "Configuration"
|
||||
#define UI_TEXT_POSITION "Position"
|
||||
#define UI_TEXT_EXTRUDER "Extruder"
|
||||
#define UI_TEXT_SD_CARD "SD Card"
|
||||
#define UI_TEXT_DEBUGGING "Debugging"
|
||||
#define UI_TEXT_HOME_DELTA "Home Delta"
|
||||
#define UI_TEXT_HOME_ALL "Home All"
|
||||
#define UI_TEXT_HOME_X "Home X"
|
||||
#define UI_TEXT_HOME_Y "Home Y"
|
||||
#define UI_TEXT_HOME_Z "Home Z"
|
||||
#define UI_TEXT_PREHEAT_PLA "Preheat PLA"
|
||||
#define UI_TEXT_PREHEAT_ABS "Preheat ABS"
|
||||
#define UI_TEXT_COOLDOWN "Cooldown"
|
||||
#define UI_TEXT_SET_TO_ORIGIN "Set to Origin"
|
||||
#define UI_TEXT_DISABLE_STEPPER "Disable stepper"
|
||||
#define UI_TEXT_X_POSITION "X Position"
|
||||
#define UI_TEXT_X_POS_FAST "X Pos. Fast"
|
||||
#define UI_TEXT_Y_POSITION "Y Position"
|
||||
#define UI_TEXT_Y_POS_FAST "Y Pos. Fast"
|
||||
#define UI_TEXT_Z_POSITION "Z Position"
|
||||
#define UI_TEXT_Z_POS_FAST "Z Pos. Fast"
|
||||
#define UI_TEXT_E_POSITION "Extr. position"
|
||||
#define UI_TEXT_BED_TEMP "Bed Temp.:%Eb\002C"
|
||||
#define UI_TEXT_EXTR0_TEMP "Temp. 0 :%E0\002C"
|
||||
#define UI_TEXT_EXTR1_TEMP "Temp. 1 :%E0\002C"
|
||||
#define UI_TEXT_EXTR0_OFF "Extruder 0 Off"
|
||||
#define UI_TEXT_EXTR1_OFF "Extruder 1 Off"
|
||||
#define UI_TEXT_EXTR0_SELECT "%X0 Select Extr.0"
|
||||
#define UI_TEXT_EXTR1_SELECT "%X1 Select Extr.1"
|
||||
#define UI_TEXT_EXTR_ORIGIN "Set Origin"
|
||||
#define UI_TEXT_PRINT_X "Print X:%ax"
|
||||
#define UI_TEXT_PRINT_Y "Print Y:%ay"
|
||||
#define UI_TEXT_PRINT_Z "Print Z:%az"
|
||||
#define UI_TEXT_MOVE_X "Move X :%aX"
|
||||
#define UI_TEXT_MOVE_Y "Move Y :%aY"
|
||||
#define UI_TEXT_MOVE_Z "Move Z :%aZ"
|
||||
#define UI_TEXT_JERK "Jerk :%aj"
|
||||
#define UI_TEXT_ZJERK "Z-Jerk :%aJ"
|
||||
#define UI_TEXT_ACCELERATION "Acceleration"
|
||||
#define UI_TEXT_STORE_TO_EEPROM "Store to EEPROM"
|
||||
#define UI_TEXT_LOAD_EEPROM "Load f. EEPROM"
|
||||
#define UI_TEXT_DBG_ECHO "Echo :%do"
|
||||
#define UI_TEXT_DBG_INFO "Info :%di"
|
||||
#define UI_TEXT_DBG_ERROR "Errors :%de"
|
||||
#define UI_TEXT_DBG_DRYRUN "Dry run:%dd"
|
||||
#define UI_TEXT_OPS_OFF "%O0 OPS Off"
|
||||
#define UI_TEXT_OPS_CLASSIC "%O1 OPS Classic"
|
||||
#define UI_TEXT_OPS_FAST "%O2 OPS Fast"
|
||||
#define UI_TEXT_OPS_RETRACT "Retract :%Or"
|
||||
#define UI_TEXT_OPS_BACKSLASH "Backsl. :%Ob"
|
||||
#define UI_TEXT_OPS_MINDIST "Min.dist :%Od"
|
||||
#define UI_TEXT_OPS_MOVE_AFTER "Move after:%Oa"
|
||||
#define UI_TEXT_ANTI_OOZE "Anti Ooze"
|
||||
#define UI_TEXT_PRINT_FILE "Print file"
|
||||
#define UI_TEXT_PAUSE_PRINT "Pause Print"
|
||||
#define UI_TEXT_CONTINUE_PRINT "Continue Print"
|
||||
#define UI_TEXT_UNMOUNT_CARD "Unmount Card"
|
||||
#define UI_TEXT_MOUNT_CARD "Mount Card"
|
||||
#define UI_TEXT_DELETE_FILE "Delete file"
|
||||
#define UI_TEXT_FEEDRATE "Feedrate"
|
||||
#define UI_TEXT_FEED_MAX_X "Max X:%fx"
|
||||
#define UI_TEXT_FEED_MAX_Y "Max Y:%fy"
|
||||
#define UI_TEXT_FEED_MAX_Z "Max Z:%fz"
|
||||
#define UI_TEXT_FEED_HOME_X "Home X:%fX"
|
||||
#define UI_TEXT_FEED_HOME_Y "Home Y:%fY"
|
||||
#define UI_TEXT_FEED_HOME_Z "Home Z:%fZ"
|
||||
#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Min endstop:%sx","Max endstop:%sX",""
|
||||
#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Min endstop:%sy","Max endstop:%sY",""
|
||||
#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Min endstop:%sz","Max endstop:%sZ",""
|
||||
#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Min endstop:%sx","Max endstop:%sX",""
|
||||
#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Min endstop:%sy","Max endstop:%sY",""
|
||||
#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Min endstop:%sz","Max endstop:%sZ",""
|
||||
#define UI_TEXT_ACTION_EPOSITION_FAST2 "E:%x3 mm","1 click = 1 mm"
|
||||
#define UI_TEXT_ACTION_XPOSITION2 "X:%x0 mm","Min:%sx Max:%sX"
|
||||
#define UI_TEXT_ACTION_YPOSITION2 "Y:%x1 mm","Min:%sy Max:%sY"
|
||||
#define UI_TEXT_ACTION_ZPOSITION2 "Z:%x2 mm","Min:%sz Max:%sZ"
|
||||
#define UI_TEXT_ACTION_XPOSITION_FAST2 "X:%x0 mm","Min:%sx Max:%sX"
|
||||
#define UI_TEXT_ACTION_YPOSITION_FAST2 "Y:%x1 mm","Min:%sy Max:%sY"
|
||||
#define UI_TEXT_ACTION_ZPOSITION_FAST2 "Z:%x2 mm","Min:%sz Max:%sZ"
|
||||
#define UI_TEXT_FANSPEED "Fan speed"
|
||||
#define UI_TEXT_FAN_OFF "Turn Fan Off"
|
||||
#define UI_TEXT_FAN_25 "Set Fan 25%%%"
|
||||
#define UI_TEXT_FAN_50 "Set Fan 50%%%"
|
||||
#define UI_TEXT_FAN_75 "Set Fan 75%%%"
|
||||
#define UI_TEXT_FAN_FULL "Set Fan Full"
|
||||
#define UI_TEXT_STEPPER_INACTIVE "Stepper Inactive"
|
||||
#define UI_TEXT_STEPPER_INACTIVE2 "Dis. After:%is","[s] 0=Off"
|
||||
#define UI_TEXT_POWER_INACTIVE "Max. Inactive"
|
||||
#define UI_TEXT_POWER_INACTIVE2 "Dis. After:%ip","[s] 0=Off"
|
||||
#define UI_TEXT_GENERAL "General"
|
||||
#define UI_TEXT_BAUDRATE "Baudrate:%oc"
|
||||
#define UI_TEXT_EXTR_STEPS "Steps/MM:%Se"
|
||||
#define UI_TEXT_EXTR_START_FEED "Start FR:%Xf"
|
||||
#define UI_TEXT_EXTR_MAX_FEED "Max FR:%XF"
|
||||
#define UI_TEXT_EXTR_ACCEL "Accel:%XA"
|
||||
#define UI_TEXT_EXTR_WATCH "Stab.Time:%Xw"
|
||||
#define UI_TEXT_EXTR_ADVANCE_L "Advance lin:%Xl"
|
||||
#define UI_TEXT_EXTR_ADVANCE_K "Advance quad:%Xa"
|
||||
#define UI_TEXT_EXTR_MANAGER "Control:%Xh"
|
||||
#define UI_TEXT_EXTR_PGAIN "PID P:%Xp"
|
||||
#define UI_TEXT_EXTR_IGAIN "PID I:%Xi"
|
||||
#define UI_TEXT_EXTR_DGAIN "PID D:%Xd"
|
||||
#define UI_TEXT_EXTR_DMIN "Drive Min:%Xm"
|
||||
#define UI_TEXT_EXTR_DMAX "Drive Max:%XM"
|
||||
#define UI_TEXT_EXTR_PMAX "PID Max:%XD"
|
||||
#define UI_TEXT_EXTR_XOFF "X-Offset:%Xx"
|
||||
#define UI_TEXT_EXTR_YOFF "Y-Offset:%Xy"
|
||||
#define UI_TEXT_STRING_HM_BANGBANG "BangBang"
|
||||
#define UI_TEXT_STRING_HM_PID "PID"
|
||||
#define UI_TEXT_STRING_ACTION "Action:%la"
|
||||
#define UI_TEXT_HEATING_EXTRUDER "Heating Extruder"
|
||||
#define UI_TEXT_HEATING_BED "Heating Bed"
|
||||
#define UI_TEXT_KILLED "Killed"
|
||||
#define UI_TEXT_STEPPER_DISABLED "Stepper Disabled"
|
||||
#define UI_TEXT_EEPROM_STORED "Configuration","stored in EEPROM"
|
||||
#define UI_TEXT_EEPROM_LOADED "Configuration","loaded f. EEPROM"
|
||||
#define UI_TEXT_UPLOADING "Uploading..."
|
||||
#define UI_TEXT_PAGE_BUFFER "Buffer:%oB"
|
||||
#define UI_TEXT_PAGE_EXTRUDER "E:%ec/%Ec\002C\176%oC"
|
||||
#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0\002C\176%o0"
|
||||
#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1\002C\176%o1"
|
||||
#define UI_TEXT_PAGE_BED "B:%eb/%Eb\002C\176%ob"
|
||||
#define UI_TEXT_SPEED_MULTIPLY "Speed Mul.:%om%%%"
|
||||
#define UI_TEXT_FLOW_MULTIPLY "Flow Mul. :%of%%%"
|
||||
#define UI_TEXT_SHOW_MEASUREMENT "Show meas."
|
||||
#define UI_TEXT_RESET_MEASUREMENT "Reset meas."
|
||||
#define UI_TEXT_SET_MEASURED_ORIGIN "Set meas. origin"
|
||||
#define UI_TEXT_DELTA "Delta Calib."
|
||||
#define UI_TEXT_SET_P1 "Set P1"
|
||||
#define UI_TEXT_SET_P2 "Set P2"
|
||||
#define UI_TEXT_SET_P3 "Set P3"
|
||||
#define UI_TEXT_CALCULATE_LEVELING "Calculate Leveling"
|
||||
#define UI_TEXT_LEVEL "Level delta"
|
||||
#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "Wait Temp. %XT\002C"
|
||||
#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Wait Units: %XU mm"
|
||||
#define UI_TEXT_SD_REMOVED "SD Card removed"
|
||||
#define UI_TEXT_SD_INSERTED "SD Card inserted"
|
||||
#define UI_TEXT_PRINTER_READY "Printer ready."
|
||||
|
||||
// *************** german translation ****************
|
||||
|
||||
#if UI_LANGUAGE==1
|
||||
|
||||
#define UI_TEXT_ON "An"
|
||||
#define UI_TEXT_OFF "Aus"
|
||||
#define UI_TEXT_NA "nv"
|
||||
#define UI_TEXT_YES "Ja"
|
||||
#define UI_TEXT_NO "Nein"
|
||||
#define UI_TEXT_PRINT_POS "Drucke..."
|
||||
#define UI_TEXT_PRINTING "Drucken"
|
||||
#define UI_TEXT_IDLE "Leerlauf"
|
||||
#define UI_TEXT_NOSDCARD "Keine SD Karte"
|
||||
#define UI_TEXT_ERROR "**** FEHLER ****"
|
||||
#define UI_TEXT_BACK "Zur" STR_uuml "ck \001"
|
||||
#define UI_TEXT_QUICK_SETTINGS "Schnelleinst."
|
||||
#define UI_TEXT_CONFIGURATION "Konfiguration"
|
||||
#define UI_TEXT_POSITION "Position"
|
||||
#define UI_TEXT_EXTRUDER "Extruder"
|
||||
#define UI_TEXT_SD_CARD "SD Karte"
|
||||
#define UI_TEXT_DEBUGGING "Debugging"
|
||||
#define UI_TEXT_HOME_ALL "Home Alle"
|
||||
#define UI_TEXT_HOME_X "Home X"
|
||||
#define UI_TEXT_HOME_Y "Home Y"
|
||||
#define UI_TEXT_HOME_Z "Home Z"
|
||||
#define UI_TEXT_PREHEAT_PLA "Vorheizen PLA"
|
||||
#define UI_TEXT_PREHEAT_ABS "Vorheizen ABS"
|
||||
#define UI_TEXT_COOLDOWN "Abk" STR_uuml "hlen"
|
||||
#define UI_TEXT_SET_TO_ORIGIN "Setze Nullpunkt"
|
||||
#define UI_TEXT_DISABLE_STEPPER "Motoren Aussch."
|
||||
#define UI_TEXT_X_POSITION "X Position"
|
||||
#define UI_TEXT_X_POS_FAST "X Pos. Schnell"
|
||||
#define UI_TEXT_Y_POSITION "Y Position"
|
||||
#define UI_TEXT_Y_POS_FAST "Y Pos. Schnell"
|
||||
#define UI_TEXT_Z_POSITION "Z Position"
|
||||
#define UI_TEXT_Z_POS_FAST "Z Pos. Schnell"
|
||||
#define UI_TEXT_E_POSITION "Extr. Position"
|
||||
#define UI_TEXT_BED_TEMP "Bed Temp.:%Eb\002C"
|
||||
#define UI_TEXT_EXTR0_TEMP "Temp. 0 :%E0\002C"
|
||||
#define UI_TEXT_EXTR1_TEMP "Temp. 1 :%E0\002C"
|
||||
#define UI_TEXT_EXTR0_OFF "Extruder 0 Aus"
|
||||
#define UI_TEXT_EXTR1_OFF "Extruder 1 Aus"
|
||||
#define UI_TEXT_EXTR0_SELECT "W" STR_auml "hle Extr. 0"
|
||||
#define UI_TEXT_EXTR1_SELECT "W" STR_auml "hle Extr. 1"
|
||||
#define UI_TEXT_EXTR_ORIGIN "Setze Nullpunkt"
|
||||
#define UI_TEXT_PRINT_X "Drucken X:%ax"
|
||||
#define UI_TEXT_PRINT_Y "Drucken Y:%ay"
|
||||
#define UI_TEXT_PRINT_Z "Drucken Z:%az"
|
||||
#define UI_TEXT_MOVE_X "Bewegen X:%aX"
|
||||
#define UI_TEXT_MOVE_Y "Bewegen Y:%aY"
|
||||
#define UI_TEXT_MOVE_Z "Bewegen Z:%aZ"
|
||||
#define UI_TEXT_JERK "Ruck :%aj"
|
||||
#define UI_TEXT_ZJERK "Z-Ruck :%aJ"
|
||||
#define UI_TEXT_ACCELERATION "Beschleunigung"
|
||||
#define UI_TEXT_STORE_TO_EEPROM "Sichere EEPROM"
|
||||
#define UI_TEXT_LOAD_EEPROM "Lade vom EEPROM"
|
||||
#define UI_TEXT_DBG_ECHO "Echo :%do"
|
||||
#define UI_TEXT_DBG_INFO "Info :%di"
|
||||
#define UI_TEXT_DBG_ERROR "Fehler :%de"
|
||||
#define UI_TEXT_DBG_DRYRUN "Trockenlauf:%dd"
|
||||
#define UI_TEXT_OPS_OFF "%O0 OPS Aus"
|
||||
#define UI_TEXT_OPS_CLASSIC "%O1 OPS Klassisch"
|
||||
#define UI_TEXT_OPS_FAST "%O2 OPS Schnell"
|
||||
#define UI_TEXT_OPS_RETRACT "Einfahren :%Or"
|
||||
#define UI_TEXT_OPS_BACKSLASH "Backsl. :%Ob"
|
||||
#define UI_TEXT_OPS_MINDIST "Min.Abst. :%Od"
|
||||
#define UI_TEXT_OPS_MOVE_AFTER "Start nach:%Oa"
|
||||
#define UI_TEXT_ANTI_OOZE "Anti Ooze"
|
||||
#define UI_TEXT_PRINT_FILE "Drucke Datei"
|
||||
#define UI_TEXT_PAUSE_PRINT "Druck Pausieren"
|
||||
#define UI_TEXT_CONTINUE_PRINT "Druck Forts."
|
||||
#define UI_TEXT_UNMOUNT_CARD "Unmount Karte"
|
||||
#define UI_TEXT_MOUNT_CARD "Mount Karte"
|
||||
#define UI_TEXT_DELETE_FILE "Datei l" STR_ouml "schen"
|
||||
#define UI_TEXT_FEED_MAX_X "Max X:%fx"
|
||||
#define UI_TEXT_FEED_MAX_Y "Max Y:%fy"
|
||||
#define UI_TEXT_FEED_MAX_Z "Max Z:%fz"
|
||||
#define UI_TEXT_FEED_HOME_X "Home X:%fX"
|
||||
#define UI_TEXT_FEED_HOME_Y "Home Y:%fY"
|
||||
#define UI_TEXT_FEED_HOME_Z "Home Z:%fZ"
|
||||
#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Min Endstopp:%sx","Max Endstopp:%sX",""
|
||||
#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Min Endstopp:%sy","Max Endstopp:%sY",""
|
||||
#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Min Endstopp:%sz","Max Endstopp:%sZ",""
|
||||
#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Min Endstopp:%sx","Max Endstopp:%sX",""
|
||||
#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Min Endstopp:%sy","Max Endstopp:%sY",""
|
||||
#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Min Endstopp:%sz","Max Endstopp:%sZ",""
|
||||
#define UI_TEXT_ACTION_EPOSITION_FAST2 "E:%x3 mm","1 klick = 1 mm"
|
||||
#define UI_TEXT_ACTION_XPOSITION2 "X:%x0 mm","Min:%sx Max:%sX"
|
||||
#define UI_TEXT_ACTION_YPOSITION2 "Y:%x1 mm","Min:%sy Max:%sY"
|
||||
#define UI_TEXT_ACTION_ZPOSITION2 "Z:%x2 mm","Min:%sz Max:%sZ"
|
||||
#define UI_TEXT_ACTION_XPOSITION_FAST2 "X:%x0 mm","Min:%sx Max:%sX"
|
||||
#define UI_TEXT_ACTION_YPOSITION_FAST2 "Y:%x1 mm","Min:%sy Max:%sY"
|
||||
#define UI_TEXT_ACTION_ZPOSITION_FAST2 "Z:%x2 mm","Min:%sz Max:%sZ"
|
||||
#define UI_TEXT_FANSPEED "L" STR_uuml "fter"
|
||||
#define UI_TEXT_FAN_OFF "L" STR_uuml "fter Aus"
|
||||
#define UI_TEXT_FAN_25 "L" STR_uuml "fter auf 25%%%"
|
||||
#define UI_TEXT_FAN_50 "L" STR_uuml "fter auf 50%%%"
|
||||
#define UI_TEXT_FAN_75 "L" STR_uuml "fter auf 75%%%"
|
||||
#define UI_TEXT_FAN_FULL "L" STR_uuml "fter Voll"
|
||||
#define UI_TEXT_STEPPER_INACTIVE "Motor Inaktiv"
|
||||
#define UI_TEXT_STEPPER_INACTIVE2 "Aus nach:%is","[s] 0=Aus"
|
||||
#define UI_TEXT_POWER_INACTIVE "Max. Inaktiv"
|
||||
#define UI_TEXT_POWER_INACTIVE2 "Aus nach:%ip","[s] 0=Aus"
|
||||
#define UI_TEXT_GENERAL "Allgemein"
|
||||
#define UI_TEXT_BAUDRATE "Baudrate:%oc"
|
||||
#define UI_TEXT_EXTR_STEPS "Schr/MM:%Se"
|
||||
#define UI_TEXT_EXTR_START_FEED "Start FR:%Xf"
|
||||
#define UI_TEXT_EXTR_MAX_FEED "Max FR:%XF"
|
||||
#define UI_TEXT_EXTR_ACCEL "Beschl.:%XA"
|
||||
#define UI_TEXT_EXTR_WATCH "Stab.Zeit:%Xw"
|
||||
#define UI_TEXT_EXTR_ADVANCE_L "Advance lin:Xl%"
|
||||
#define UI_TEXT_EXTR_ADVANCE_K "Advance quad:Xa%"
|
||||
#define UI_TEXT_EXTR_MANAGER "Regler:%Xh"
|
||||
#define UI_TEXT_EXTR_PGAIN "PID P:%Xp"
|
||||
#define UI_TEXT_EXTR_IGAIN "PID I:%Xi"
|
||||
#define UI_TEXT_EXTR_DGAIN "PID D:%Xd"
|
||||
#define UI_TEXT_EXTR_DMIN "Drive Min:%Xm"
|
||||
#define UI_TEXT_EXTR_DMAX "Drive Max:%XM"
|
||||
#define UI_TEXT_EXTR_PMAX "PID Max:%XD"
|
||||
#define UI_TEXT_EXTR_XOFF "X-Offset:%Xx"
|
||||
#define UI_TEXT_EXTR_YOFF "Y-Offset:%Xy"
|
||||
#define UI_TEXT_STRING_HM_BANGBANG "BangBang"
|
||||
#define UI_TEXT_STRING_HM_PID "PID"
|
||||
#define UI_TEXT_STRING_ACTION "Aktion:%la"
|
||||
#define UI_TEXT_HEATING_EXTRUDER "Heize Extruder"
|
||||
#define UI_TEXT_HEATING_BED "Heize Druckbett"
|
||||
#define UI_TEXT_KILLED "Angehalten"
|
||||
#define UI_TEXT_STEPPER_DISABLED "Motoren Aus"
|
||||
#define UI_TEXT_EEPROM_STORED "Konfiguration","gespeichert."
|
||||
#define UI_TEXT_EEPROM_LOADED "Konfiguration","geladen."
|
||||
#define UI_TEXT_UPLOADING "Hochladen..."
|
||||
#define UI_TEXT_PAGE_BUFFER "Puffer:%oB"
|
||||
#define UI_TEXT_PAGE_EXTRUDER "E:%ec/%Ec\002C\176%oC"
|
||||
#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0\002C\176%o0"
|
||||
#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1\002C\176%o1"
|
||||
#define UI_TEXT_PAGE_BED "B:%eb/%Eb\002C\176%ob"
|
||||
#define UI_TEXT_SPEED_MULTIPLY "Geschw.Mul:%om%%%"
|
||||
#define UI_TEXT_FLOW_MULTIPLY "Flow Mul.:%of%%%"
|
||||
#define UI_TEXT_ADVANCE_L "Advance lin:Xl%"
|
||||
#define UI_TEXT_ADVANCE_K "Advance quad:Xa%"
|
||||
#define UI_TEXT_SHOW_MEASUREMENT "Zeige Messung"
|
||||
#define UI_TEXT_RESET_MEASUREMENT "Reset Messung"
|
||||
#define UI_TEXT_SET_MEASURED_ORIGIN "Setze Ursprung Mess."
|
||||
#define UI_TEXT_DELTA "Delta Calib."
|
||||
#define UI_TEXT_SET_P1 "Setze P1"
|
||||
#define UI_TEXT_SET_P2 "Setze P2"
|
||||
#define UI_TEXT_SET_P3 "Setze P3"
|
||||
#define UI_TEXT_CALCULATE_LEVELING "Berechne Leveling"
|
||||
#define UI_TEXT_LEVEL "Level delta"
|
||||
#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "Wait Temp.%XT\002C"
|
||||
#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Wait Units:%XUmm"
|
||||
#define UI_TEXT_SD_REMOVED "Karte entfernt"
|
||||
#define UI_TEXT_SD_INSERTED "Karte eingelegt"
|
||||
#define UI_TEXT_PRINTER_READY "Drucker bereit."
|
||||
|
||||
#endif
|
||||
|
||||
// Dutch translation
|
||||
#if UI_LANGUAGE==2
|
||||
|
||||
#define UI_TEXT_ON "Aan"
|
||||
#define UI_TEXT_OFF "Uit"
|
||||
#define UI_TEXT_NA "N/A" // Output for not available
|
||||
#define UI_TEXT_YES "Ja"
|
||||
#define UI_TEXT_NO "Nee"
|
||||
#define UI_TEXT_SEL "\003"
|
||||
#define UI_TEXT_NOSEL "\004"
|
||||
#define UI_TEXT_PRINT_POS "Printen..."
|
||||
#define UI_TEXT_PRINTING "Printen"
|
||||
#define UI_TEXT_IDLE "Rust"
|
||||
#define UI_TEXT_NOSDCARD "Geen SD Kaart"
|
||||
#define UI_TEXT_ERROR "**** FOUT ****"
|
||||
#define UI_TEXT_BACK "Terug \001"
|
||||
#define UI_TEXT_QUICK_SETTINGS "Snel Instelling"
|
||||
#define UI_TEXT_CONFIGURATION "Configuratie"
|
||||
#define UI_TEXT_POSITION "Positie"
|
||||
#define UI_TEXT_EXTRUDER "Extruder"
|
||||
#define UI_TEXT_SD_CARD "SD Kaart"
|
||||
#define UI_TEXT_DEBUGGING "Debugging"
|
||||
#define UI_TEXT_HOME_ALL "Home Alles"
|
||||
#define UI_TEXT_HOME_X "Home X"
|
||||
#define UI_TEXT_HOME_Y "Home Y"
|
||||
#define UI_TEXT_HOME_Z "Home Z"
|
||||
#define UI_TEXT_PREHEAT "Voorverwarmen"
|
||||
#define UI_TEXT_COOLDOWN "Koelen"
|
||||
#define UI_TEXT_SET_TO_ORIGIN "Zet oorsprong"
|
||||
#define UI_TEXT_DISABLE_STEPPER "Zet motor uit"
|
||||
#define UI_TEXT_X_POSITION "X Positie"
|
||||
#define UI_TEXT_X_POS_FAST "X Pos. Snel"
|
||||
#define UI_TEXT_Y_POSITION "Y Positie"
|
||||
#define UI_TEXT_Y_POS_FAST "Y Pos. Snel"
|
||||
#define UI_TEXT_Z_POSITION "Z Positie"
|
||||
#define UI_TEXT_Z_POS_FAST "Z Pos. Snel"
|
||||
#define UI_TEXT_E_POSITION "Extr. positie"
|
||||
#define UI_TEXT_BED_TEMP "Bed Temp.:%Eb\002C"
|
||||
#define UI_TEXT_EXTR0_TEMP "Temp. 0 :%E0\002C"
|
||||
#define UI_TEXT_EXTR1_TEMP "Temp. 1 :%E0\002C"
|
||||
#define UI_TEXT_EXTR0_OFF "Extruder 0 Uit"
|
||||
#define UI_TEXT_EXTR1_OFF "Extruder 1 Uit"
|
||||
#define UI_TEXT_EXTR0_SELECT "%X0 Select Extr.0"
|
||||
#define UI_TEXT_EXTR1_SELECT "%X1 Select Extr.1"
|
||||
#define UI_TEXT_EXTR_ORIGIN "Zet oorsprong"
|
||||
#define UI_TEXT_PRINT_X "Print X:%ax"
|
||||
#define UI_TEXT_PRINT_Y "Print Y:%ay"
|
||||
#define UI_TEXT_PRINT_Z "Print Z:%az"
|
||||
#define UI_TEXT_MOVE_X "Beweeg X:%aX"
|
||||
#define UI_TEXT_MOVE_Y "Beweeg Y:%aY"
|
||||
#define UI_TEXT_MOVE_Z "Beweeg Z:%aZ"
|
||||
#define UI_TEXT_JERK "Ruk:%aj"
|
||||
#define UI_TEXT_ZJERK "Z-Ruk:%aJ"
|
||||
#define UI_TEXT_ACCELERATION "Acceleratie"
|
||||
#define UI_TEXT_STORE_TO_EEPROM "Opslaan n. EEPROM"
|
||||
#define UI_TEXT_LOAD_EEPROM "Ladd f. EEPROM"
|
||||
#define UI_TEXT_DBG_ECHO "Echo :%do"
|
||||
#define UI_TEXT_DBG_INFO "Info :%di"
|
||||
#define UI_TEXT_DBG_ERROR "Fouten :%de"
|
||||
#define UI_TEXT_DBG_DRYRUN "Droogloop:%dd"
|
||||
#define UI_TEXT_OPS_OFF "%O0 OPS Uit"
|
||||
#define UI_TEXT_OPS_CLASSIC "%O1 OPS Klassiek"
|
||||
#define UI_TEXT_OPS_FAST "%O2 OPS Snel"
|
||||
#define UI_TEXT_OPS_RETRACT "Terugtrekken:%Or"
|
||||
#define UI_TEXT_OPS_BACKSLASH "Backsl. :%Ob"
|
||||
#define UI_TEXT_OPS_MINDIST "Min. afstand:%Od"
|
||||
#define UI_TEXT_OPS_MOVE_AFTER "Beweeg na:%Oa"
|
||||
#define UI_TEXT_ANTI_OOZE "Anti lekken"
|
||||
#define UI_TEXT_PRINT_FILE "Print bestand"
|
||||
#define UI_TEXT_PAUSE_PRINT "Pauzeer Print"
|
||||
#define UI_TEXT_CONTINUE_PRINT "Zet print voort"
|
||||
#define UI_TEXT_UNMOUNT_CARD "Ontkoppel Kaart"
|
||||
#define UI_TEXT_MOUNT_CARD "Koppel Kaart"
|
||||
#define UI_TEXT_DELETE_FILE "Verw. bestand"
|
||||
#define UI_TEXT_FEEDRATE "Beweeg snelheid"
|
||||
#define UI_TEXT_FEED_MAX_X "Max X:%fx"
|
||||
#define UI_TEXT_FEED_MAX_Y "Max Y:%fy"
|
||||
#define UI_TEXT_FEED_MAX_Z "Max Z:%fz"
|
||||
#define UI_TEXT_FEED_HOME_X "Home X:%fX"
|
||||
#define UI_TEXT_FEED_HOME_Y "Home Y:%fY"
|
||||
#define UI_TEXT_FEED_HOME_Z "Home Z:%fZ"
|
||||
#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Min eindst.:%sx","Max eindst.:%sX",""
|
||||
#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Min eindst.:%sy","Max eindst.:%sY",""
|
||||
#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Min eindst.:%sz","Max eindst.:%sZ",""
|
||||
#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Min eindst.:%sx","Max eindst.:%sX",""
|
||||
#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Min eindst.:%sy","Max eindst.:%sY",""
|
||||
#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Min eindst.:%sz","Max eindst.:%sZ",""
|
||||
#define UI_TEXT_ACTION_EPOSITION_FAST2 "E:%x3 mm","1 klik = 1 mm"
|
||||
#define UI_TEXT_ACTION_XPOSITION2 "X:%x0 mm","Min:%sx Max:%sX"
|
||||
#define UI_TEXT_ACTION_YPOSITION2 "Y:%x1 mm","Min:%sy Max:%sY"
|
||||
#define UI_TEXT_ACTION_ZPOSITION2 "Z:%x2 mm","Min:%sz Max:%sZ"
|
||||
#define UI_TEXT_ACTION_XPOSITION_FAST2 "X:%x0 mm","Min:%sx Max:%sX"
|
||||
#define UI_TEXT_ACTION_YPOSITION_FAST2 "Y:%x1 mm","Min:%sy Max:%sY"
|
||||
#define UI_TEXT_ACTION_ZPOSITION_FAST2 "Z:%x2 mm","Min:%sz Max:%sZ"
|
||||
#define UI_TEXT_FANSPEED "Fan snelheid"
|
||||
#define UI_TEXT_FAN_OFF "Zet Fan uit"
|
||||
#define UI_TEXT_FAN_25 "Zet Fan 25%%%"
|
||||
#define UI_TEXT_FAN_50 "Zet Fan 50%%%"
|
||||
#define UI_TEXT_FAN_75 "Zet Fan 75%%%"
|
||||
#define UI_TEXT_FAN_FULL "Zet Fan Vol aan"
|
||||
#define UI_TEXT_STEPPER_INACTIVE "Motor Inactief"
|
||||
#define UI_TEXT_STEPPER_INACTIVE2 "Uit na:%is","[s] 0=Off"
|
||||
#define UI_TEXT_POWER_INACTIVE "Max. Inactief"
|
||||
#define UI_TEXT_POWER_INACTIVE2 "Zet uit na:%ip","[s] 0=Off"
|
||||
#define UI_TEXT_GENERAL "Algemeen"
|
||||
#define UI_TEXT_BAUDRATE "Baudrate:%oc"
|
||||
#define UI_TEXT_EXTR_STEPS "Stappen/MM:%Se"
|
||||
#define UI_TEXT_EXTR_START_FEED "Start FR.:%Xf"
|
||||
#define UI_TEXT_EXTR_MAX_FEED "Max FR.:%XF"
|
||||
#define UI_TEXT_EXTR_ACCEL "Accel:%XA"
|
||||
#define UI_TEXT_EXTR_WATCH "Stab.Tijd:%Xw"
|
||||
#define UI_TEXT_EXTR_ADVANCE_L "Advance lin:Xl%"
|
||||
#define UI_TEXT_EXTR_ADVANCE_K "Advance quad:Xa%"
|
||||
#define UI_TEXT_EXTR_MANAGER "Control:%Xh"
|
||||
#define UI_TEXT_EXTR_PGAIN "PID P:%Xp"
|
||||
#define UI_TEXT_EXTR_IGAIN "PID I:%Xi"
|
||||
#define UI_TEXT_EXTR_DGAIN "PID D:%Xd"
|
||||
#define UI_TEXT_EXTR_DMIN "Drive Min:%Xm"
|
||||
#define UI_TEXT_EXTR_DMAX "Drive Max:%XM"
|
||||
#define UI_TEXT_EXTR_PMAX "PID Max:%XD"
|
||||
#define UI_TEXT_EXTR_XOFF "X-Offset:%Xx"
|
||||
#define UI_TEXT_EXTR_YOFF "Y-Offset:%Xy"
|
||||
#define UI_TEXT_STRING_HM_BANGBANG "BangBang"
|
||||
#define UI_TEXT_STRING_HM_PID "PID"
|
||||
#define UI_TEXT_STRING_ACTION "Action:%la"
|
||||
#define UI_TEXT_HEATING_EXTRUDER "Opwarmen Extru."
|
||||
#define UI_TEXT_HEATING_BED "Opwarmen Bed"
|
||||
#define UI_TEXT_KILLED "Uitgeschakeld"
|
||||
#define UI_TEXT_STEPPER_DISABLED "Motor uitgezet"
|
||||
#define UI_TEXT_EEPROM_STORED "Configuratie","saved. in EEPROM"
|
||||
#define UI_TEXT_EEPROM_LOADED "Configuratie","loaded f. EEPROM"
|
||||
#define UI_TEXT_UPLOADING "Uploaden..."
|
||||
#define UI_TEXT_PAGE_BUFFER "Buffer:%oB"
|
||||
#define UI_TEXT_PAGE_EXTRUDER "E:%ec/%Ec\002C\176%oC"
|
||||
#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0\002C\176%o0"
|
||||
#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1\002C\176%o1"
|
||||
#define UI_TEXT_PAGE_BED "B:%eb/%Eb\002C\176%ob"
|
||||
#define UI_TEXT_SPEED_MULTIPLY "Snelh. Mul.:%om%%%"
|
||||
#define UI_TEXT_FLOW_MULTIPLY "Flow Mul.:%of%%%"
|
||||
|
||||
#endif
|
||||
|
||||
// *************************************************************************************
|
||||
// User defined language
|
||||
//
|
||||
// If you need a language not mentioned above, you can translate this dummy entry.
|
||||
// If you want it added permanently to the distribution, spend it to the community under
|
||||
// GPL V3. Only new and complete translations are put into the official distribution!
|
||||
// *************************************************************************************
|
||||
|
||||
#if UI_LANGUAGE==1000
|
||||
|
||||
#define UI_TEXT_ON "On"
|
||||
#define UI_TEXT_OFF "Off"
|
||||
#define UI_TEXT_NA "N/A" // Output for not available
|
||||
#define UI_TEXT_YES "Yes"
|
||||
#define UI_TEXT_NO "No"
|
||||
#define UI_TEXT_SEL "\003"
|
||||
#define UI_TEXT_NOSEL "\004"
|
||||
#define UI_TEXT_PRINT_POS "Printing..."
|
||||
#define UI_TEXT_PRINTING "Printing"
|
||||
#define UI_TEXT_IDLE "Idle"
|
||||
#define UI_TEXT_NOSDCARD "No SD Card"
|
||||
#define UI_TEXT_ERROR "**** ERROR ****"
|
||||
#define UI_TEXT_BACK "Back \001"
|
||||
#define UI_TEXT_QUICK_SETTINGS "Quick Settings"
|
||||
#define UI_TEXT_CONFIGURATION "Configuration"
|
||||
#define UI_TEXT_POSITION "Position"
|
||||
#define UI_TEXT_EXTRUDER "Extruder"
|
||||
#define UI_TEXT_SD_CARD "SD Card"
|
||||
#define UI_TEXT_DEBUGGING "Debugging"
|
||||
#define UI_TEXT_HOME_ALL "Home All"
|
||||
#define UI_TEXT_HOME_X "Home X"
|
||||
#define UI_TEXT_HOME_Y "Home Y"
|
||||
#define UI_TEXT_HOME_Z "Home Z"
|
||||
#define UI_TEXT_PREHEAT_PLA "Preheat PLA"
|
||||
#define UI_TEXT_PREHEAT_ABS "Preheat ABS"
|
||||
#define UI_TEXT_COOLDOWN "Cooldown"
|
||||
#define UI_TEXT_SET_TO_ORIGIN "Set to Origin"
|
||||
#define UI_TEXT_DISABLE_STEPPER "Disable stepper"
|
||||
#define UI_TEXT_X_POSITION "X Position"
|
||||
#define UI_TEXT_X_POS_FAST "X Pos. Fast"
|
||||
#define UI_TEXT_Y_POSITION "Y Position"
|
||||
#define UI_TEXT_Y_POS_FAST "Y Pos. Fast"
|
||||
#define UI_TEXT_Z_POSITION "Z Position"
|
||||
#define UI_TEXT_Z_POS_FAST "Z Pos. Fast"
|
||||
#define UI_TEXT_E_POSITION "Extr. position"
|
||||
#define UI_TEXT_BED_TEMP "Bed Temp.:%Eb\002C"
|
||||
#define UI_TEXT_EXTR0_TEMP "Temp. 0 :%E0\002C"
|
||||
#define UI_TEXT_EXTR1_TEMP "Temp. 1 :%E0\002C"
|
||||
#define UI_TEXT_EXTR0_OFF "Extruder 0 Off"
|
||||
#define UI_TEXT_EXTR1_OFF "Extruder 1 Off"
|
||||
#define UI_TEXT_EXTR0_SELECT "%X0 Select Extr.0"
|
||||
#define UI_TEXT_EXTR1_SELECT "%X1 Select Extr.1"
|
||||
#define UI_TEXT_EXTR_ORIGIN "Set Origin"
|
||||
#define UI_TEXT_PRINT_X "Print X:%ax"
|
||||
#define UI_TEXT_PRINT_Y "Print Y:%ay"
|
||||
#define UI_TEXT_PRINT_Z "Print Z:%az"
|
||||
#define UI_TEXT_MOVE_X "Move X:%aX"
|
||||
#define UI_TEXT_MOVE_Y "Move Y:%aY"
|
||||
#define UI_TEXT_MOVE_Z "Move Z:%aZ"
|
||||
#define UI_TEXT_JERK "Jerk:%aj"
|
||||
#define UI_TEXT_ZJERK "Z-Jerk:%aJ"
|
||||
#define UI_TEXT_ACCELERATION "Acceleration"
|
||||
#define UI_TEXT_STORE_TO_EEPROM "Store to EEPROM"
|
||||
#define UI_TEXT_LOAD_EEPROM "Load f. EEPROM"
|
||||
#define UI_TEXT_DBG_ECHO "Echo :%do"
|
||||
#define UI_TEXT_DBG_INFO "Info :%di"
|
||||
#define UI_TEXT_DBG_ERROR "Errors :%de"
|
||||
#define UI_TEXT_DBG_DRYRUN "Dry run:%dd"
|
||||
#define UI_TEXT_OPS_OFF "%O0 OPS Off"
|
||||
#define UI_TEXT_OPS_CLASSIC "%O1 OPS Classic"
|
||||
#define UI_TEXT_OPS_FAST "%O2 OPS Fast"
|
||||
#define UI_TEXT_OPS_RETRACT "Retract :%Or"
|
||||
#define UI_TEXT_OPS_BACKSLASH "Backsl. :%Ob"
|
||||
#define UI_TEXT_OPS_MINDIST "Min.dist:%Od"
|
||||
#define UI_TEXT_OPS_MOVE_AFTER "Move after:%Oa"
|
||||
#define UI_TEXT_ANTI_OOZE "Anti Ooze"
|
||||
#define UI_TEXT_PRINT_FILE "Print file"
|
||||
#define UI_TEXT_PAUSE_PRINT "Pause Print"
|
||||
#define UI_TEXT_CONTINUE_PRINT "Continue Print"
|
||||
#define UI_TEXT_UNMOUNT_CARD "Unmount Card"
|
||||
#define UI_TEXT_MOUNT_CARD "Mount Card"
|
||||
#define UI_TEXT_DELETE_FILE "Delete file"
|
||||
#define UI_TEXT_FEEDRATE "Feedrate"
|
||||
#define UI_TEXT_FEED_MAX_X "Max X:%fx"
|
||||
#define UI_TEXT_FEED_MAX_Y "Max Y:%fy"
|
||||
#define UI_TEXT_FEED_MAX_Z "Max Z:%fz"
|
||||
#define UI_TEXT_FEED_HOME_X "Home X:%fX"
|
||||
#define UI_TEXT_FEED_HOME_Y "Home Y:%fY"
|
||||
#define UI_TEXT_FEED_HOME_Z "Home Z:%fZ"
|
||||
#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Min endstop:%sx","Max endstop:%sX",""
|
||||
#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Min endstop:%sy","Max endstop:%sY",""
|
||||
#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Min endstop:%sz","Max endstop:%sZ",""
|
||||
#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Min endstop:%sx","Max endstop:%sX",""
|
||||
#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Min endstop:%sy","Max endstop:%sY",""
|
||||
#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Min endstop:%sz","Max endstop:%sZ",""
|
||||
#define UI_TEXT_ACTION_EPOSITION_FAST2 "E:%x3 mm","1 click = 1 mm"
|
||||
#define UI_TEXT_ACTION_XPOSITION2 "X:%x0 mm","Min:%sx Max:%sX"
|
||||
#define UI_TEXT_ACTION_YPOSITION2 "Y:%x1 mm","Min:%sy Max:%sY"
|
||||
#define UI_TEXT_ACTION_ZPOSITION2 "Z:%x2 mm","Min:%sz Max:%sZ"
|
||||
#define UI_TEXT_ACTION_XPOSITION_FAST2 "X:%x0 mm","Min:%sx Max:%sX"
|
||||
#define UI_TEXT_ACTION_YPOSITION_FAST2 "Y:%x1 mm","Min:%sy Max:%sY"
|
||||
#define UI_TEXT_ACTION_ZPOSITION_FAST2 "Z:%x2 mm","Min:%sz Max:%sZ"
|
||||
#define UI_TEXT_FANSPEED "Fan speed"
|
||||
#define UI_TEXT_FAN_OFF "Turn Fan Off"
|
||||
#define UI_TEXT_FAN_25 "Set Fan 25%%%"
|
||||
#define UI_TEXT_FAN_50 "Set Fan 50%%%"
|
||||
#define UI_TEXT_FAN_75 "Set Fan 75%%%"
|
||||
#define UI_TEXT_FAN_FULL "Set Fan Full"
|
||||
#define UI_TEXT_STEPPER_INACTIVE "Stepper Inactive"
|
||||
#define UI_TEXT_STEPPER_INACTIVE2 "Dis. After:%is","[s] 0=Off"
|
||||
#define UI_TEXT_POWER_INACTIVE "Max. Inactive"
|
||||
#define UI_TEXT_POWER_INACTIVE2 "Dis. After:%ip","[s] 0=Off"
|
||||
#define UI_TEXT_GENERAL "General"
|
||||
#define UI_TEXT_BAUDRATE "Baudrate:%oc"
|
||||
#define UI_TEXT_EXTR_STEPS "Steps/MM:%Se"
|
||||
#define UI_TEXT_EXTR_START_FEED "Start FR:%Xf"
|
||||
#define UI_TEXT_EXTR_MAX_FEED "Max FR:%XF"
|
||||
#define UI_TEXT_EXTR_ACCEL "Accel:%XA"
|
||||
#define UI_TEXT_EXTR_WATCH "Stab.Time:%Xw"
|
||||
#define UI_TEXT_EXTR_ADVANCE_L "Advance lin:Xl%"
|
||||
#define UI_TEXT_EXTR_ADVANCE_K "Advance quad:Xa%"
|
||||
#define UI_TEXT_EXTR_MANAGER "Control:%Xh"
|
||||
#define UI_TEXT_EXTR_PGAIN "PID P:%Xp"
|
||||
#define UI_TEXT_EXTR_IGAIN "PID I:%Xi"
|
||||
#define UI_TEXT_EXTR_DGAIN "PID D:%Xd"
|
||||
#define UI_TEXT_EXTR_DMIN "Drive Min:%Xm"
|
||||
#define UI_TEXT_EXTR_DMAX "Drive Max:%XM"
|
||||
#define UI_TEXT_EXTR_PMAX "PID Max:%XD"
|
||||
#define UI_TEXT_EXTR_XOFF "X-Offset:%Xx"
|
||||
#define UI_TEXT_EXTR_YOFF "Y-Offset:%Xy"
|
||||
#define UI_TEXT_STRING_HM_BANGBANG "BangBang"
|
||||
#define UI_TEXT_STRING_HM_PID "PID"
|
||||
#define UI_TEXT_STRING_ACTION "Action:%la"
|
||||
#define UI_TEXT_HEATING_EXTRUDER "Heating Extruder"
|
||||
#define UI_TEXT_HEATING_BED "Heating Bed"
|
||||
#define UI_TEXT_KILLED "Killed"
|
||||
#define UI_TEXT_STEPPER_DISABLED "Stepper Disabled"
|
||||
#define UI_TEXT_EEPROM_STORED "Configuration","stored in EEPROM"
|
||||
#define UI_TEXT_EEPROM_LOADED "Configuration","loaded f. EEPROM"
|
||||
#define UI_TEXT_UPLOADING "Uploading..."
|
||||
#define UI_TEXT_PAGE_BUFFER "Buffer:%oB"
|
||||
#define UI_TEXT_PAGE_EXTRUDER "E:%ec/%Ec\002C\176%oC"
|
||||
#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0\002C\176%o0"
|
||||
#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1\002C\176%o1"
|
||||
#define UI_TEXT_PAGE_BED "B:%eb/%Eb\002C\176%ob"
|
||||
#define UI_TEXT_SPEED_MULTIPLY "Speed Mul.:%om%%%"
|
||||
#define UI_TEXT_FLOW_MULTIPLY "Flow Mul.:%of%%%"
|
||||
#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "Wait Temp.%XT\002C"
|
||||
#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Wait Units:%XUmm"
|
||||
#define UI_TEXT_PRINTER_READY "Printer ready."
|
||||
|
||||
#endif
|
||||
505
Repetier/uimenu.h
Normal file
505
Repetier/uimenu.h
Normal file
|
|
@ -0,0 +1,505 @@
|
|||
/*
|
||||
This file is part of Repetier-Firmware.
|
||||
|
||||
Repetier-Firmware is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
Repetier-Firmware is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Repetier-Firmware. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#if !defined(_UI_MENU_H) && defined(UI_MAIN)
|
||||
#define _UI_MENU_H
|
||||
|
||||
/*
|
||||
The menu configuration uses dynamic strings. These dynamic strings can contain
|
||||
a placeholder for special values. During print these placeholder are exchanged
|
||||
by their current value. Everything else is printed exactly as written.
|
||||
|
||||
A placeholder always has 3 chars. It starts with a % followed by 2 characters
|
||||
defining the value. You can use any placeholder in any position, also it doesn't
|
||||
always make sense.
|
||||
|
||||
List of placeholder:
|
||||
%ec : Current extruder temperature
|
||||
%eb : Current heated bed temperature
|
||||
%e0..9 : Temp. of extruder 0..9
|
||||
%er : Extruder relative mode
|
||||
%Ec : Target temperature of current extruder
|
||||
%Eb : Target temperature of heated bed
|
||||
%E0-9 : Target temperature of extruder 0..9
|
||||
%os : Status message
|
||||
%oe : Error message
|
||||
%oB : Buffer length
|
||||
%om : Speed multiplier
|
||||
%of : flow multiplier
|
||||
%oc : Connection baudrate
|
||||
%o0..9 : Output level extruder 0..9 is % including %sign.
|
||||
%oC : Output level current extruder
|
||||
%ob : Output level heated bed
|
||||
%%% : The % char
|
||||
%x0 : X position
|
||||
%x1 : Y position
|
||||
%x2 : Z position
|
||||
%x3 : Current extruder position
|
||||
%sx : State of x min endstop.
|
||||
%sX : State of x max endstop.
|
||||
%sy : State of y min endstop.
|
||||
%sY : State of y max endstop.
|
||||
%sz : State of z min endstop.
|
||||
%sZ : State of z max endstop.
|
||||
%do : Debug echo state.
|
||||
%di : Debug info state.
|
||||
%de : Debug error state.
|
||||
%dd : Debug dry run state.
|
||||
%O0 : OPS mode = 0
|
||||
%O1 : OPS mode = 1
|
||||
%O2 : OPS mode = 2
|
||||
%Or : OPS retract distance
|
||||
%Ob : OPS backslash distance
|
||||
%Od : OPS min distance
|
||||
%Oa : OPS move after
|
||||
%ax : X acceleration during print moves
|
||||
%ay : Y acceleration during print moves
|
||||
%az : Z acceleration during print moves
|
||||
%aX : X acceleration during travel moves
|
||||
%aY : Y acceleration during travel moves
|
||||
%aZ : Z acceleration during travel moves
|
||||
%aj : Max. jerk
|
||||
%aJ : Max. Z-jerk
|
||||
%fx : Max. feedrate x direction
|
||||
%fy : Max. feedrate y direction
|
||||
%fz : Max. feedrate z direction
|
||||
%fe : Max. feedrate current extruder
|
||||
%fX : Homing feedrate x direction
|
||||
%fY : Homing feedrate y direction
|
||||
%fZ : Homing feedrate z direction
|
||||
%Sx : Steps per mm x direction
|
||||
%Sy : Steps per mm y direction
|
||||
%Sz : Steps per mm z direction
|
||||
%Se : Steps per mm current extruder
|
||||
%is : Stepper inactive time in seconds
|
||||
%ip : Max. inactive time in seconds
|
||||
%X0..9 : Extruder selected marker
|
||||
%Xi : PID I gain
|
||||
%Xp : PID P gain
|
||||
%Xd : PID D gain
|
||||
%Xm : PID drive min
|
||||
%XM : PID drive max
|
||||
%XD : PID max
|
||||
%Xw : Extruder watch period in seconds
|
||||
%Xh : Extruder heat manager (BangBang/PID)
|
||||
%Xa : Advance K value
|
||||
%Xx : x offset in steps
|
||||
%Xy : y offset in steps
|
||||
%Xf : Extruder max. start feedrate
|
||||
%XF : Extruder max. feedrate
|
||||
%XA : Extruder max. acceleration
|
||||
*/
|
||||
|
||||
|
||||
// Define precision for temperatures. With small displays only integer values fit.
|
||||
#ifndef UI_TEMP_PRECISION
|
||||
#if UI_COLS>16
|
||||
#define UI_TEMP_PRECISION 1
|
||||
#else
|
||||
#define UI_TEMP_PRECISION 0
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/* ============= PAGES DEFINITION =============
|
||||
|
||||
If you are not iside a menu, the firmware displays pages with information.
|
||||
Especially if you have only a small display it is convenient to have
|
||||
more then one information page.
|
||||
*/
|
||||
|
||||
/* Define your pages using dynamic strings. To define a page use
|
||||
UI_PAGE4(name,row1,row2,row3,row4);
|
||||
for 4 row displays and
|
||||
UI_PAGE2(name,row1,row2);
|
||||
for 2 row displays. You can add additional pages or change the default pages like you want.
|
||||
*/
|
||||
#if UI_ROWS>=4
|
||||
#if HAVE_HEATED_BED==true
|
||||
UI_PAGE4(ui_page1,"\005%ec/%Ec\002B%eB/%Eb\002","Z:%x2","Mul:%om Buf:%oB","%os");
|
||||
//UI_PAGE4(ui_page1,UI_TEXT_PAGE_EXTRUDER,UI_TEXT_PAGE_BED,UI_TEXT_PAGE_BUFFER,"%os");
|
||||
#else
|
||||
UI_PAGE4(ui_page1,UI_TEXT_PAGE_EXTRUDER,"Z:%x2 mm",UI_TEXT_PAGE_BUFFER,"%os");
|
||||
#endif
|
||||
UI_PAGE4(ui_page2,"X:%x0 mm","Y:%x1 mm","Z:%x2 mm","%os");
|
||||
//UI_PAGE4(ui_page2,"dX:%y0 mm %sX","dY:%y1 mm %sY","dZ:%y2 mm %sZ","%os");
|
||||
UI_PAGE4(ui_page3,UI_TEXT_PAGE_EXTRUDER1,
|
||||
#if NUM_EXTRUDER>1
|
||||
UI_TEXT_PAGE_EXTRUDER2
|
||||
#else
|
||||
""
|
||||
#endif
|
||||
,UI_TEXT_PAGE_BED,"%os");
|
||||
|
||||
/*
|
||||
Merge pages together. Use the following pattern:
|
||||
#define UI_PAGES {&name1,&name2,&name3}
|
||||
*/
|
||||
#define UI_PAGES {&ui_page1,&ui_page2,&ui_page3}
|
||||
// How many pages do you want to have. Minimum is 1.
|
||||
#define UI_NUM_PAGES 3
|
||||
#else
|
||||
#if HAVE_HEATED_BED==true
|
||||
UI_PAGE2(ui_page1,UI_TEXT_PAGE_EXTRUDER,UI_TEXT_PAGE_BED);
|
||||
#else
|
||||
UI_PAGE2(ui_page1,UI_TEXT_PAGE_EXTRUDER,"%os");
|
||||
#endif
|
||||
UI_PAGE2(ui_page2,"X:%x0 Y:%x1","%os");
|
||||
UI_PAGE2(ui_page3,"Z:%x2 mm","%os");
|
||||
/*
|
||||
Merge pages together. Use the following pattern:
|
||||
#define UI_PAGES {&name1,&name2,&name3}
|
||||
*/
|
||||
#define UI_PAGES {&ui_page1,&ui_page2,&ui_page3}
|
||||
// How many pages do you want to have. Minimum is 1.
|
||||
#define UI_NUM_PAGES 3
|
||||
#endif
|
||||
/* ============ MENU definition ================
|
||||
|
||||
The menu works the same as pages. In addion you need to define what the lines do
|
||||
or where to jump to. For that reason, the menu structure needs to be entered in
|
||||
reverse order. Starting from the leaves, the menu structure is defined.
|
||||
*/
|
||||
|
||||
/*
|
||||
At first define all actions available in the menu. The actions define, what the
|
||||
next/previous button will do. All menu actions work the same:
|
||||
next/previous changes the value
|
||||
ok sets the value if not already done and goes back to previous menu.
|
||||
*/
|
||||
|
||||
// Error menu
|
||||
|
||||
UI_MENU_ACTION2(ui_menu_error,UI_ACTION_DUMMY,UI_TEXT_ERROR,"%oe");
|
||||
|
||||
// **** Positions submenus
|
||||
|
||||
#if UI_ROWS>=4
|
||||
UI_MENU_ACTION4C(ui_menu_xpos,UI_ACTION_XPOSITION,UI_TEXT_ACTION_XPOSITION4);
|
||||
UI_MENU_ACTION4C(ui_menu_ypos,UI_ACTION_YPOSITION,UI_TEXT_ACTION_YPOSITION4);
|
||||
UI_MENU_ACTION4C(ui_menu_zpos,UI_ACTION_ZPOSITION,UI_TEXT_ACTION_ZPOSITION4);
|
||||
UI_MENU_ACTION4C(ui_menu_xpos_fast,UI_ACTION_XPOSITION_FAST,UI_TEXT_ACTION_XPOSITION_FAST4);
|
||||
UI_MENU_ACTION4C(ui_menu_ypos_fast,UI_ACTION_YPOSITION_FAST,UI_TEXT_ACTION_YPOSITION_FAST4);
|
||||
UI_MENU_ACTION4C(ui_menu_zpos_fast,UI_ACTION_ZPOSITION_FAST,UI_TEXT_ACTION_ZPOSITION_FAST4);
|
||||
#else
|
||||
UI_MENU_ACTION2C(ui_menu_xpos,UI_ACTION_XPOSITION,UI_TEXT_ACTION_XPOSITION2);
|
||||
UI_MENU_ACTION2C(ui_menu_ypos,UI_ACTION_YPOSITION,UI_TEXT_ACTION_YPOSITION2);
|
||||
UI_MENU_ACTION2C(ui_menu_zpos,UI_ACTION_ZPOSITION,UI_TEXT_ACTION_ZPOSITION2);
|
||||
UI_MENU_ACTION2C(ui_menu_xpos_fast,UI_ACTION_XPOSITION_FAST,UI_TEXT_ACTION_XPOSITION_FAST2);
|
||||
UI_MENU_ACTION2C(ui_menu_ypos_fast,UI_ACTION_YPOSITION_FAST,UI_TEXT_ACTION_YPOSITION_FAST2);
|
||||
UI_MENU_ACTION2C(ui_menu_zpos_fast,UI_ACTION_ZPOSITION_FAST,UI_TEXT_ACTION_ZPOSITION_FAST2);
|
||||
#endif
|
||||
UI_MENU_ACTION2C(ui_menu_epos,UI_ACTION_EPOSITION,UI_TEXT_ACTION_EPOSITION_FAST2);
|
||||
|
||||
/*
|
||||
Next step is to define submenus leading to the action.
|
||||
*/
|
||||
|
||||
// **** Positionening menu
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_back,UI_TEXT_BACK,UI_ACTION_BACK);
|
||||
#if UI_HAS_BACK_KEY==0
|
||||
#define UI_MENU_ADDCONDBACK &ui_menu_back,
|
||||
#define UI_MENU_BACKCNT 1
|
||||
#else
|
||||
#define UI_MENU_ADDCONDBACK
|
||||
#define UI_MENU_BACKCNT 0
|
||||
#endif
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_home_all,UI_TEXT_HOME_ALL,UI_ACTION_HOME_ALL);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_home_x,UI_TEXT_HOME_X,UI_ACTION_HOME_X);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_home_y,UI_TEXT_HOME_Y,UI_ACTION_HOME_Y);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_home_z,UI_TEXT_HOME_Z,UI_ACTION_HOME_Z);
|
||||
UI_MENU_ACTIONSELECTOR(ui_menu_go_xpos,UI_TEXT_X_POSITION,ui_menu_xpos);
|
||||
UI_MENU_ACTIONSELECTOR(ui_menu_go_ypos,UI_TEXT_Y_POSITION,ui_menu_ypos);
|
||||
UI_MENU_ACTIONSELECTOR(ui_menu_go_zpos,UI_TEXT_Z_POSITION,ui_menu_zpos);
|
||||
UI_MENU_ACTIONSELECTOR(ui_menu_go_epos,UI_TEXT_E_POSITION,ui_menu_epos);
|
||||
UI_MENU_ACTIONSELECTOR(ui_menu_go_xfast,UI_TEXT_X_POS_FAST,ui_menu_xpos_fast);
|
||||
UI_MENU_ACTIONSELECTOR(ui_menu_go_yfast,UI_TEXT_Y_POS_FAST,ui_menu_ypos_fast);
|
||||
UI_MENU_ACTIONSELECTOR(ui_menu_go_zfast,UI_TEXT_Z_POS_FAST,ui_menu_zpos_fast);
|
||||
|
||||
#define UI_MENU_POSITIONS {UI_MENU_ADDCONDBACK &ui_menu_home_all,&ui_menu_home_x,&ui_menu_home_y,&ui_menu_home_z,&ui_menu_go_xfast,&ui_menu_go_xpos,&ui_menu_go_yfast,&ui_menu_go_ypos,&ui_menu_go_zfast,&ui_menu_go_zpos,&ui_menu_go_epos}
|
||||
UI_MENU(ui_menu_positions,UI_MENU_POSITIONS,11+UI_MENU_BACKCNT);
|
||||
|
||||
// **** Delta calibration menu
|
||||
#ifdef STEP_COUNTER
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_show_measurement,UI_TEXT_SHOW_MEASUREMENT,UI_ACTION_SHOW_MEASUREMENT);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_reset_measurement,UI_TEXT_RESET_MEASUREMENT,UI_ACTION_RESET_MEASUREMENT);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_set_measured_origin,UI_TEXT_SET_MEASURED_ORIGIN,UI_ACTION_SET_MEASURED_ORIGIN);
|
||||
#define UI_MENU_DELTA {UI_MENU_ADDCONDBACK &ui_menu_show_measurement,&ui_menu_reset_measurement,&ui_menu_set_measured_origin,&ui_menu_home_all,&ui_menu_go_zpos,&ui_menu_go_zfast}
|
||||
UI_MENU(ui_menu_delta,UI_MENU_DELTA,6+UI_MENU_BACKCNT);
|
||||
#endif
|
||||
|
||||
// **** Bed leveling menu
|
||||
#ifdef SOFTWARE_LEVELING
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_set_p1,UI_TEXT_SET_P1,UI_ACTION_SET_P1);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_set_p2,UI_TEXT_SET_P2,UI_ACTION_SET_P2);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_set_p3,UI_TEXT_SET_P3,UI_ACTION_SET_P3);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_calculate_leveling,UI_TEXT_CALCULATE_LEVELING,UI_ACTION_CALC_LEVEL);
|
||||
#define UI_MENU_LEVEL {UI_MENU_ADDCONDBACK &ui_menu_set_p1,&ui_menu_set_p2,&ui_menu_set_p3,&ui_menu_calculate_leveling,&ui_menu_go_xpos,&ui_menu_go_xfast,&ui_menu_go_ypos,&ui_menu_go_yfast,&ui_menu_go_zpos,&ui_menu_go_zfast}
|
||||
UI_MENU(ui_menu_level,UI_MENU_LEVEL,10+UI_MENU_BACKCNT);
|
||||
#endif
|
||||
|
||||
// **** Extruder menu
|
||||
|
||||
UI_MENU_CHANGEACTION(ui_menu_ext_temp0,UI_TEXT_EXTR0_TEMP,UI_ACTION_EXTRUDER0_TEMP);
|
||||
UI_MENU_CHANGEACTION(ui_menu_ext_temp1,UI_TEXT_EXTR1_TEMP,UI_ACTION_EXTRUDER1_TEMP);
|
||||
UI_MENU_CHANGEACTION(ui_menu_bed_temp, UI_TEXT_BED_TEMP,UI_ACTION_HEATED_BED_TEMP);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_ext_sel0,UI_TEXT_EXTR0_SELECT,UI_ACTION_SELECT_EXTRUDER0);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_ext_sel1,UI_TEXT_EXTR1_SELECT,UI_ACTION_SELECT_EXTRUDER1);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_ext_off0,UI_TEXT_EXTR0_OFF,UI_ACTION_EXTRUDER0_OFF);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_ext_off1,UI_TEXT_EXTR1_OFF,UI_ACTION_EXTRUDER1_OFF);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_ext_origin,UI_TEXT_EXTR_ORIGIN,UI_ACTION_RESET_EXTRUDER);
|
||||
|
||||
#if NUM_EXTRUDER>1
|
||||
#define UI_MENU_EXTCOND &ui_menu_ext_temp0,&ui_menu_ext_temp1,&ui_menu_ext_off0,&ui_menu_ext_off1,&ui_menu_ext_sel0,&ui_menu_ext_sel1,
|
||||
#define UI_MENU_EXTCNT 6
|
||||
#else
|
||||
#define UI_MENU_EXTCOND &ui_menu_ext_temp0,&ui_menu_ext_off0,
|
||||
#define UI_MENU_EXTCNT 2
|
||||
#endif
|
||||
#if HAVE_HEATED_BED==true
|
||||
#define UI_MENU_BEDCOND &ui_menu_bed_temp,
|
||||
#define UI_MENU_BEDCNT 1
|
||||
#else
|
||||
#define UI_MENU_BEDCOND
|
||||
#define UI_MENU_BEDCNT 0
|
||||
#endif
|
||||
|
||||
#define UI_MENU_EXTRUDER {UI_MENU_ADDCONDBACK UI_MENU_BEDCOND UI_MENU_EXTCOND &ui_menu_go_epos,&ui_menu_ext_origin}
|
||||
UI_MENU(ui_menu_extruder,UI_MENU_EXTRUDER,UI_MENU_BACKCNT+UI_MENU_BEDCNT+UI_MENU_EXTCNT+2);
|
||||
|
||||
// **** SD card menu
|
||||
|
||||
// **** Quick menu
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_quick_preheat_pla,UI_TEXT_PREHEAT_PLA,UI_ACTION_PREHEAT_PLA);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_quick_preheat_abs,UI_TEXT_PREHEAT_ABS,UI_ACTION_PREHEAT_ABS);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_quick_cooldown,UI_TEXT_COOLDOWN,UI_ACTION_COOLDOWN);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_quick_origin,UI_TEXT_SET_TO_ORIGIN,UI_ACTION_SET_ORIGIN);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_quick_stopstepper,UI_TEXT_DISABLE_STEPPER,UI_ACTION_DISABLE_STEPPER);
|
||||
UI_MENU_CHANGEACTION(ui_menu_quick_speedmultiply,UI_TEXT_SPEED_MULTIPLY,UI_ACTION_FEEDRATE_MULTIPLY);
|
||||
UI_MENU_CHANGEACTION(ui_menu_quick_flowmultiply,UI_TEXT_FLOW_MULTIPLY,UI_ACTION_FLOWRATE_MULTIPLY);
|
||||
#define UI_MENU_QUICK {UI_MENU_ADDCONDBACK &ui_menu_home_all,&ui_menu_quick_preheat_pla,&ui_menu_quick_preheat_abs,&ui_menu_quick_speedmultiply,&ui_menu_quick_flowmultiply,&ui_menu_quick_cooldown,&ui_menu_quick_origin,&ui_menu_quick_stopstepper}
|
||||
UI_MENU(ui_menu_quick,UI_MENU_QUICK,8+UI_MENU_BACKCNT);
|
||||
|
||||
// **** Fan menu
|
||||
|
||||
#if FAN_PIN>-1
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_fan_off,UI_TEXT_FAN_OFF,UI_ACTION_FAN_OFF);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_fan_25,UI_TEXT_FAN_25,UI_ACTION_FAN_25);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_fan_50,UI_TEXT_FAN_50,UI_ACTION_FAN_50);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_fan_75,UI_TEXT_FAN_75,UI_ACTION_FAN_75);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_fan_full,UI_TEXT_FAN_FULL,UI_ACTION_FAN_FULL);
|
||||
#define UI_MENU_FAN {UI_MENU_ADDCONDBACK &ui_menu_fan_off,&ui_menu_fan_25,&ui_menu_fan_50,&ui_menu_fan_75,&ui_menu_fan_full}
|
||||
UI_MENU(ui_menu_fan,UI_MENU_FAN,5+UI_MENU_BACKCNT);
|
||||
UI_MENU_SUBMENU(ui_menu_fan_sub,UI_TEXT_FANSPEED,ui_menu_fan);
|
||||
#define UI_MENU_FAN_COND &ui_menu_fan_sub,
|
||||
#define UI_MENU_FAN_CNT 1
|
||||
#else
|
||||
#define UI_MENU_FAN_COND
|
||||
#define UI_MENU_FAN_CNT 0
|
||||
#endif
|
||||
|
||||
// **** SD card menu
|
||||
|
||||
#ifdef SDSUPPORT
|
||||
#define UI_MENU_SD_FILESELECTOR {&ui_menu_back}
|
||||
UI_MENU_FILESELECT(ui_menu_sd_fileselector,UI_MENU_SD_FILESELECTOR,1);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_sd_printfile,UI_TEXT_PRINT_FILE,UI_ACTION_SD_PRINT);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_sd_pause,UI_TEXT_PAUSE_PRINT,UI_ACTION_SD_PAUSE);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_sd_continue,UI_TEXT_CONTINUE_PRINT,UI_ACTION_SD_CONTINUE);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_sd_unmount,UI_TEXT_UNMOUNT_CARD,UI_ACTION_SD_UNMOUNT);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_sd_mount,UI_TEXT_MOUNT_CARD,UI_ACTION_SD_MOUNT);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_sd_delete,UI_TEXT_DELETE_FILE,UI_ACTION_SD_DELETE);
|
||||
#define UI_MENU_SD {UI_MENU_ADDCONDBACK &ui_menu_sd_printfile,&ui_menu_sd_pause,&ui_menu_sd_continue,&ui_menu_sd_unmount,&ui_menu_sd_mount,&ui_menu_sd_delete}
|
||||
UI_MENU(ui_menu_sd,UI_MENU_SD,UI_MENU_BACKCNT+6);
|
||||
UI_MENU_SUBMENU(ui_menu_sd_sub,UI_TEXT_SD_CARD,ui_menu_sd);
|
||||
|
||||
#define UI_MENU_SD_COND &ui_menu_sd_sub,
|
||||
#define UI_MENU_SD_CNT 1
|
||||
#else
|
||||
#define UI_MENU_SD_COND
|
||||
#define UI_MENU_SD_CNT 0
|
||||
#endif
|
||||
|
||||
|
||||
// **** Debugging menu
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_debug_echo,UI_TEXT_DBG_ECHO,UI_ACTION_DEBUG_ECHO);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_debug_info,UI_TEXT_DBG_INFO,UI_ACTION_DEBUG_INFO);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_debug_error,UI_TEXT_DBG_ERROR,UI_ACTION_DEBUG_ERROR);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_debug_dryrun,UI_TEXT_DBG_DRYRUN,UI_ACTION_DEBUG_DRYRUN);
|
||||
|
||||
#define UI_MENU_DEBUGGING {UI_MENU_ADDCONDBACK &ui_menu_debug_echo,&ui_menu_debug_info,&ui_menu_debug_error,&ui_menu_debug_dryrun}
|
||||
UI_MENU(ui_menu_debugging,UI_MENU_DEBUGGING,4+UI_MENU_BACKCNT);
|
||||
|
||||
// **** OPS configuration
|
||||
#if USE_OPS==1
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_ops_off,UI_TEXT_OPS_OFF,UI_ACTION_OPS_OFF);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_ops_classic,UI_TEXT_OPS_CLASSIC,UI_ACTION_OPS_CLASSIC);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_ops_fast,UI_TEXT_OPS_FAST,UI_ACTION_OPS_FAST);
|
||||
UI_MENU_CHANGEACTION(ui_menu_ops_retract,UI_TEXT_OPS_RETRACT,UI_ACTION_OPS_RETRACTDISTANCE);
|
||||
UI_MENU_CHANGEACTION(ui_menu_ops_backslash,UI_TEXT_OPS_BACKSLASH,UI_ACTION_OPS_BACKLASH);
|
||||
UI_MENU_CHANGEACTION(ui_menu_ops_mindist,UI_TEXT_OPS_MINDIST,UI_ACTION_OPS_MINDISTANCE);
|
||||
UI_MENU_CHANGEACTION(ui_menu_ops_moveafter,UI_TEXT_OPS_MOVE_AFTER,UI_ACTION_OPS_MOVE_AFTER);
|
||||
#define UI_MENU_OPS {UI_MENU_ADDCONDBACK &ui_menu_ops_off,&ui_menu_ops_classic,&ui_menu_ops_fast,&ui_menu_ops_retract,&ui_menu_ops_backslash,&ui_menu_ops_mindist,&ui_menu_ops_moveafter}
|
||||
UI_MENU(ui_menu_ops,UI_MENU_OPS,7+UI_MENU_BACKCNT);
|
||||
UI_MENU_SUBMENU(ui_menu_ops_sub,UI_TEXT_ANTI_OOZE,ui_menu_ops);
|
||||
#define UI_MENU_ADDCONDOPS &ui_menu_ops_sub,
|
||||
#else
|
||||
#define UI_MENU_ADDCONDOPS
|
||||
#endif
|
||||
|
||||
// **** Acceleration settings
|
||||
UI_MENU_CHANGEACTION(ui_menu_accel_printx,UI_TEXT_PRINT_X,UI_ACTION_PRINT_ACCEL_X);
|
||||
UI_MENU_CHANGEACTION(ui_menu_accel_printy,UI_TEXT_PRINT_Y,UI_ACTION_PRINT_ACCEL_Y);
|
||||
UI_MENU_CHANGEACTION(ui_menu_accel_printz,UI_TEXT_PRINT_Z,UI_ACTION_PRINT_ACCEL_Z);
|
||||
UI_MENU_CHANGEACTION(ui_menu_accel_travelx,UI_TEXT_MOVE_X,UI_ACTION_MOVE_ACCEL_X);
|
||||
UI_MENU_CHANGEACTION(ui_menu_accel_travely,UI_TEXT_MOVE_Y,UI_ACTION_MOVE_ACCEL_Y);
|
||||
UI_MENU_CHANGEACTION(ui_menu_accel_travelz,UI_TEXT_MOVE_Z,UI_ACTION_MOVE_ACCEL_Z);
|
||||
UI_MENU_CHANGEACTION(ui_menu_accel_jerk,UI_TEXT_JERK,UI_ACTION_MAX_JERK);
|
||||
UI_MENU_CHANGEACTION(ui_menu_accel_zjerk,UI_TEXT_ZJERK,UI_ACTION_MAX_ZJERK);
|
||||
#define UI_MENU_ACCEL {UI_MENU_ADDCONDBACK &ui_menu_accel_printx,&ui_menu_accel_printy,&ui_menu_accel_printz,&ui_menu_accel_travelx,&ui_menu_accel_travely,&ui_menu_accel_travelz,&ui_menu_accel_jerk,&ui_menu_accel_zjerk}
|
||||
UI_MENU(ui_menu_accel,UI_MENU_ACCEL,8+UI_MENU_BACKCNT);
|
||||
|
||||
// **** Feedrates
|
||||
UI_MENU_CHANGEACTION(ui_menu_feedrate_maxx,UI_TEXT_FEED_MAX_X,UI_ACTION_MAX_FEEDRATE_X);
|
||||
UI_MENU_CHANGEACTION(ui_menu_feedrate_maxy,UI_TEXT_FEED_MAX_Y,UI_ACTION_MAX_FEEDRATE_Y);
|
||||
UI_MENU_CHANGEACTION(ui_menu_feedrate_maxz,UI_TEXT_FEED_MAX_Z,UI_ACTION_MAX_FEEDRATE_Z);
|
||||
UI_MENU_CHANGEACTION(ui_menu_feedrate_homex,UI_TEXT_FEED_HOME_X,UI_ACTION_HOMING_FEEDRATE_X);
|
||||
UI_MENU_CHANGEACTION(ui_menu_feedrate_homey,UI_TEXT_FEED_HOME_Y,UI_ACTION_HOMING_FEEDRATE_Y);
|
||||
UI_MENU_CHANGEACTION(ui_menu_feedrate_homez,UI_TEXT_FEED_HOME_Z,UI_ACTION_HOMING_FEEDRATE_Z);
|
||||
#define UI_MENU_FEEDRATE {UI_MENU_ADDCONDBACK &ui_menu_feedrate_maxx,&ui_menu_feedrate_maxy,&ui_menu_feedrate_maxz,&ui_menu_feedrate_homex,&ui_menu_feedrate_homey,&ui_menu_feedrate_homez}
|
||||
UI_MENU(ui_menu_feedrate,UI_MENU_ACCEL,6+UI_MENU_BACKCNT);
|
||||
|
||||
// **** General configuration settings
|
||||
|
||||
UI_MENU_ACTION2C(ui_menu_stepper2,UI_ACTION_STEPPER_INACTIVE,UI_TEXT_STEPPER_INACTIVE2);
|
||||
UI_MENU_ACTION2C(ui_menu_maxinactive2,UI_ACTION_MAX_INACTIVE,UI_TEXT_POWER_INACTIVE2);
|
||||
UI_MENU_CHANGEACTION(ui_menu_general_baud,UI_TEXT_BAUDRATE,UI_ACTION_BAUDRATE);
|
||||
UI_MENU_ACTIONSELECTOR(ui_menu_general_stepper_inactive,UI_TEXT_STEPPER_INACTIVE,ui_menu_stepper2);
|
||||
UI_MENU_ACTIONSELECTOR(ui_menu_general_max_inactive,UI_TEXT_POWER_INACTIVE,ui_menu_maxinactive2);
|
||||
#define UI_MENU_GENERAL {UI_MENU_ADDCONDBACK &ui_menu_general_baud,&ui_menu_general_stepper_inactive,&ui_menu_general_max_inactive}
|
||||
UI_MENU(ui_menu_general,UI_MENU_GENERAL,3+UI_MENU_BACKCNT);
|
||||
|
||||
// **** Extruder configuration
|
||||
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_steps,UI_TEXT_EXTR_STEPS,UI_ACTION_EXTR_STEPS);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_start_feedrate,UI_TEXT_EXTR_START_FEED,UI_ACTION_EXTR_START_FEEDRATE);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_max_feedrate,UI_TEXT_EXTR_MAX_FEED,UI_ACTION_EXTR_MAX_FEEDRATE);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_acceleration,UI_TEXT_EXTR_ACCEL,UI_ACTION_EXTR_ACCELERATION);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_watch_period,UI_TEXT_EXTR_WATCH,UI_ACTION_EXTR_WATCH_PERIOD);
|
||||
UI_MENU_CHANGEACTION(ui_menu_ext_wait_temp,UI_TEXT_EXTR_WAIT_RETRACT_TEMP,UI_ACTION_EXTR_WAIT_RETRACT_TEMP);
|
||||
UI_MENU_CHANGEACTION(ui_menu_ext_wait_units,UI_TEXT_EXTR_WAIT_RETRACT_UNITS,UI_ACTION_EXTR_WAIT_RETRACT_UNITS);
|
||||
#define UI_MENU_ADV_CNT 0
|
||||
#define UI_MENU_ADVANCE
|
||||
#ifdef USE_ADVANCE
|
||||
#define UI_MENU_ADV_CNT 1
|
||||
#define UI_MENU_ADVANCE ,&ui_menu_cext_advancel
|
||||
#ifdef ENABLE_QUADRATIC_ADVANCE
|
||||
#define UI_MENU_ADV_CNT 2
|
||||
#define UI_MENU_ADVANCE ,&ui_menu_cext_advancel,&ui_menu_cext_advancek
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_advancek,UI_TEXT_EXTR_ADVANCE_K,UI_ACTION_ADVANCE_K);
|
||||
#endif
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_advancel,UI_TEXT_EXTR_ADVANCE_L,UI_ACTION_ADVANCE_L);
|
||||
#endif
|
||||
#ifdef TEMP_PID
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_manager,UI_TEXT_EXTR_MANAGER,UI_ACTION_EXTR_HEATMANAGER);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_pgain,UI_TEXT_EXTR_PGAIN,UI_ACTION_PID_PGAIN);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_igain,UI_TEXT_EXTR_IGAIN,UI_ACTION_PID_IGAIN);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_dgain,UI_TEXT_EXTR_DGAIN,UI_ACTION_PID_DGAIN);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_dmin,UI_TEXT_EXTR_DMIN,UI_ACTION_DRIVE_MIN);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_dmax,UI_TEXT_EXTR_DMAX,UI_ACTION_DRIVE_MAX);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_pmax,UI_TEXT_EXTR_PMAX,UI_ACTION_PID_MAX);
|
||||
#define UI_MENU_PIDCOND ,&ui_menu_cext_manager,&ui_menu_cext_pgain,&ui_menu_cext_igain,&ui_menu_cext_dgain,&ui_menu_cext_dmin,&ui_menu_cext_dmax,&ui_menu_cext_pmax
|
||||
#define UI_MENU_PIDCNT 7
|
||||
#else
|
||||
#define UI_MENU_PIDCOND
|
||||
#define UI_MENU_PIDCNT 0
|
||||
#endif
|
||||
#if NUM_EXTRUDER>1
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_xoffset,UI_TEXT_EXTR_XOFF,UI_ACTION_X_OFFSET);
|
||||
UI_MENU_CHANGEACTION(ui_menu_cext_yoffset,UI_TEXT_EXTR_YOFF,UI_ACTION_Y_OFFSET);
|
||||
#define UI_MENU_CONFEXTCOND &ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_cext_xoffset,&ui_menu_cext_yoffset,
|
||||
#define UI_MENU_CONFEXTCNT 4
|
||||
#else
|
||||
#define UI_MENU_CONFEXTCOND
|
||||
#define UI_MENU_CONFEXTCNT 0
|
||||
#endif
|
||||
#define UI_MENU_CEXTR {UI_MENU_ADDCONDBACK UI_MENU_CONFEXTCOND &ui_menu_cext_steps,&ui_menu_cext_start_feedrate,&ui_menu_cext_max_feedrate,&ui_menu_cext_acceleration,&ui_menu_cext_watch_period,&ui_menu_ext_wait_units,&ui_menu_ext_wait_temp UI_MENU_ADVANCE UI_MENU_PIDCOND}
|
||||
UI_MENU(ui_menu_cextr,UI_MENU_CEXTR,7+UI_MENU_BACKCNT+UI_MENU_PIDCNT+UI_MENU_CONFEXTCNT+UI_MENU_ADV_CNT);
|
||||
|
||||
// **** Configuration menu
|
||||
UI_MENU_SUBMENU(ui_menu_conf_general,UI_TEXT_GENERAL,ui_menu_general);
|
||||
UI_MENU_SUBMENU(ui_menu_conf_accel,UI_TEXT_ACCELERATION,ui_menu_accel);
|
||||
UI_MENU_SUBMENU(ui_menu_conf_feed,UI_TEXT_FEEDRATE,ui_menu_feedrate);
|
||||
UI_MENU_SUBMENU(ui_menu_conf_extr,UI_TEXT_EXTRUDER,ui_menu_cextr);
|
||||
#if EEPROM_MODE!=0
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_conf_to_eeprom,UI_TEXT_STORE_TO_EEPROM,UI_ACTION_STORE_EEPROM);
|
||||
UI_MENU_ACTIONCOMMAND(ui_menu_conf_from_eeprom,UI_TEXT_LOAD_EEPROM,UI_ACTION_LOAD_EEPROM);
|
||||
#define UI_MENU_EEPROM_COND ,&ui_menu_conf_to_eeprom,&ui_menu_conf_from_eeprom
|
||||
#define UI_MENU_EEPROM_CNT 2
|
||||
UI_MENU_ACTION2C(ui_menu_eeprom_saved,UI_ACTION_DUMMY,UI_TEXT_EEPROM_STORED);
|
||||
UI_MENU_ACTION2C(ui_menu_eeprom_loaded,UI_ACTION_DUMMY,UI_TEXT_EEPROM_LOADED);
|
||||
#else
|
||||
#define UI_MENU_EEPROM_COND
|
||||
#define UI_MENU_EEPROM_CNT 0
|
||||
#endif
|
||||
#ifdef SOFTWARE_LEVELING
|
||||
#define UI_MENU_SL_COND ,&ui_menu_conf_level
|
||||
#define UI_MENU_SL_CNT 1
|
||||
UI_MENU_SUBMENU(ui_menu_conf_level, UI_TEXT_LEVEL, ui_menu_level);
|
||||
#else
|
||||
#define UI_MENU_SL_COND
|
||||
#define UI_MENU_SL_CNT 0
|
||||
#endif
|
||||
#ifdef STEP_COUNTER
|
||||
#define UI_MENU_DELTA_COND ,&ui_menu_conf_delta
|
||||
#define UI_MENU_DELTA_CNT 1
|
||||
UI_MENU_SUBMENU(ui_menu_conf_delta, UI_TEXT_DELTA, ui_menu_delta);
|
||||
#else
|
||||
#define UI_MENU_DELTA_COND
|
||||
#define UI_MENU_DELTA_CNT 0
|
||||
#endif
|
||||
#define UI_MENU_CONFIGURATION {UI_MENU_ADDCONDBACK &ui_menu_conf_general,UI_MENU_ADDCONDOPS &ui_menu_conf_accel,&ui_menu_conf_feed,&ui_menu_conf_extr UI_MENU_EEPROM_COND UI_MENU_DELTA_COND UI_MENU_SL_COND}
|
||||
UI_MENU(ui_menu_configuration,UI_MENU_CONFIGURATION,UI_MENU_BACKCNT+USE_OPS+UI_MENU_EEPROM_CNT+UI_MENU_DELTA_CNT+UI_MENU_SL_CNT+4);
|
||||
// Main menu
|
||||
UI_MENU_SUBMENU(ui_menu_main1,UI_TEXT_QUICK_SETTINGS,ui_menu_quick);
|
||||
UI_MENU_SUBMENU(ui_menu_main2, UI_TEXT_POSITION,ui_menu_positions);
|
||||
UI_MENU_SUBMENU(ui_menu_main3,UI_TEXT_EXTRUDER,ui_menu_extruder);
|
||||
UI_MENU_SUBMENU(ui_menu_main4,UI_TEXT_DEBUGGING,ui_menu_debugging);
|
||||
UI_MENU_SUBMENU(ui_menu_main5,UI_TEXT_CONFIGURATION,ui_menu_configuration);
|
||||
#define UI_MENU_MAIN {UI_MENU_ADDCONDBACK &ui_menu_main1,&ui_menu_main2,&ui_menu_main3,UI_MENU_FAN_COND UI_MENU_SD_COND &ui_menu_main4,&ui_menu_main5}
|
||||
UI_MENU(ui_menu_main,UI_MENU_MAIN,5+UI_MENU_BACKCNT+UI_MENU_SD_CNT+UI_MENU_FAN_CNT);
|
||||
|
||||
/* Define menus accessible by action commands
|
||||
|
||||
You can create up to 10 user menus which are accessible by the action commands UI_ACTION_SHOW_USERMENU1 until UI_ACTION_SHOW_USERMENU10
|
||||
You this the same way as with the menus above or you use one of the above menus. Then add a define like
|
||||
|
||||
#define UI_USERMENU1 ui_menu_conf_feed
|
||||
|
||||
which assigns the menu stored in ui_menu_conf_feed to the action UI_ACTION_SHOW_USERMENU1. Make sure only to change the numbers and not the name of the define.
|
||||
|
||||
When do you need this? You might want a fast button to change the temperature. In the default menu you have no menu
|
||||
to change the temperature and view it the same time. So you need to make an action menu for this like:
|
||||
UI_MENU_ACTION4C(ui_menu_extrtemp,UI_ACTION_EXTRUDER0_TEMP,"Temp. 0 :%E0\002C","","","");
|
||||
Then you assign this menu to a usermenu:
|
||||
#define UI_USERMENU2 ui_menu_extrtemp
|
||||
|
||||
Now you can assign the action UI_ACTION_SHOW_USERMENU2+UI_ACTION_TOPMENU to a key and that will now show the temperture screen and allows
|
||||
the change of temperature with the next/previous buttons.
|
||||
|
||||
*/
|
||||
|
||||
#endif // __UI_MENU_H
|
||||
Loading…
Reference in a new issue