From a0bb6d8315399ee43e6931602dfba34c1d0d5f26 Mon Sep 17 00:00:00 2001 From: Nis Wechselberg Date: Fri, 15 Jan 2016 20:42:10 +0100 Subject: [PATCH] Updated Repetier version --- .../ESP8266-RGB-WiFiServer.ino | 5 +- Repetier/BedLeveling.cpp | 635 ++ Repetier/Commands.cpp | 348 +- Repetier/Commands.h | 5 +- Repetier/Communication.cpp | 68 +- Repetier/Communication.h | 42 +- Repetier/Configuration.h | 268 +- Repetier/Drivers.cpp | 317 +- Repetier/Drivers.h | 85 +- Repetier/Eeprom.cpp | 50 +- Repetier/Eeprom.h | 82 +- Repetier/Events.h | 155 +- Repetier/Extruder.cpp | 442 +- Repetier/Extruder.h | 43 +- Repetier/FatStructs.h | 2 - Repetier/HAL.cpp | 2907 +++---- Repetier/HAL.h | 30 +- Repetier/Printer.cpp | 940 ++- Repetier/Printer.h | 236 +- Repetier/Repetier.cbp | 875 -- Repetier/Repetier.depend | 1696 ---- Repetier/Repetier.h | 480 +- Repetier/Repetier.ino | 24 +- Repetier/Repetier.layout | 213 - Repetier/SDCard.cpp | 248 +- Repetier/SdFat.cpp | 184 +- Repetier/SdFat.h | 9 +- Repetier/cores/CDC.cpp | 3 - Repetier/cores/HardwareSerial.cpp | 3 - Repetier/cores/IPAddress.cpp | 3 - Repetier/cores/Print.cpp | 1 - Repetier/cores/Stream.cpp | 1 - Repetier/cores/Tone.cpp | 1 - Repetier/cores/USBCore.cpp | 2 - Repetier/cores/WInterrupts.c | 1 - Repetier/cores/WMath.cpp | 1 - Repetier/cores/WString.cpp | 1 - Repetier/cores/main.cpp | 1 - Repetier/cores/new.cpp | 1 - Repetier/cores/wiring.c | 1 - Repetier/cores/wiring_analog.c | 1 - Repetier/cores/wiring_digital.c | 1 - Repetier/cores/wiring_pulse.c | 1 - Repetier/cores/wiring_shift.c | 1 - Repetier/fastio.h | 2 - Repetier/gcode.cpp | 319 +- Repetier/gcode.h | 43 +- Repetier/libraries/EEPROM.cpp | 1 - Repetier/libraries/Ethernet.cpp | 8 - Repetier/libraries/Firmata.cpp | 1 - Repetier/libraries/LiquidCrystal.cpp | 1 - Repetier/libraries/OBD.cpp | 1 - Repetier/libraries/SD.cpp | 5 - Repetier/libraries/SPI.cpp | 1 - Repetier/libraries/Servo.cpp | 1 - Repetier/libraries/SoftwareSerial.cpp | 1 - Repetier/libraries/Stepper.cpp | 1 - Repetier/libraries/TinyGPS.cpp | 1 - Repetier/libraries/U8gui.cpp | 1 - Repetier/libraries/WiFi.cpp | 7 - Repetier/libraries/Wire.cpp | 2 - Repetier/libraries/twi.c | 1 - Repetier/logo.h | 43 +- Repetier/motion.cpp | 5219 ++++++------ Repetier/motion.h | 1425 ++-- Repetier/pins.h | 893 ++- Repetier/u8glib_ex.h | 7050 +++++++++-------- Repetier/ui.cpp | 488 +- Repetier/ui.h | 651 +- Repetier/uiconfig.h | 68 +- Repetier/uilang.cpp | 6065 ++++++++++++++ Repetier/uilang.h | 5517 ++++++++----- Repetier/uimenu.h | 744 +- 73 files changed, 23884 insertions(+), 15089 deletions(-) create mode 100644 Repetier/BedLeveling.cpp delete mode 100644 Repetier/Repetier.cbp delete mode 100644 Repetier/Repetier.depend delete mode 100644 Repetier/Repetier.layout delete mode 100644 Repetier/cores/CDC.cpp delete mode 100644 Repetier/cores/HardwareSerial.cpp delete mode 100644 Repetier/cores/IPAddress.cpp delete mode 100644 Repetier/cores/Print.cpp delete mode 100644 Repetier/cores/Stream.cpp delete mode 100644 Repetier/cores/Tone.cpp delete mode 100644 Repetier/cores/USBCore.cpp delete mode 100644 Repetier/cores/WInterrupts.c delete mode 100644 Repetier/cores/WMath.cpp delete mode 100644 Repetier/cores/WString.cpp delete mode 100644 Repetier/cores/main.cpp delete mode 100644 Repetier/cores/new.cpp delete mode 100644 Repetier/cores/wiring.c delete mode 100644 Repetier/cores/wiring_analog.c delete mode 100644 Repetier/cores/wiring_digital.c delete mode 100644 Repetier/cores/wiring_pulse.c delete mode 100644 Repetier/cores/wiring_shift.c delete mode 100644 Repetier/libraries/EEPROM.cpp delete mode 100644 Repetier/libraries/Ethernet.cpp delete mode 100644 Repetier/libraries/Firmata.cpp delete mode 100644 Repetier/libraries/LiquidCrystal.cpp delete mode 100644 Repetier/libraries/OBD.cpp delete mode 100644 Repetier/libraries/SD.cpp delete mode 100644 Repetier/libraries/SPI.cpp delete mode 100644 Repetier/libraries/Servo.cpp delete mode 100644 Repetier/libraries/SoftwareSerial.cpp delete mode 100644 Repetier/libraries/Stepper.cpp delete mode 100644 Repetier/libraries/TinyGPS.cpp delete mode 100644 Repetier/libraries/U8gui.cpp delete mode 100644 Repetier/libraries/WiFi.cpp delete mode 100644 Repetier/libraries/Wire.cpp delete mode 100644 Repetier/libraries/twi.c create mode 100644 Repetier/uilang.cpp diff --git a/ESP8266-RGB-WiFiServer/ESP8266-RGB-WiFiServer.ino b/ESP8266-RGB-WiFiServer/ESP8266-RGB-WiFiServer.ino index ba3625d..d4917be 100644 --- a/ESP8266-RGB-WiFiServer/ESP8266-RGB-WiFiServer.ino +++ b/ESP8266-RGB-WiFiServer/ESP8266-RGB-WiFiServer.ino @@ -63,6 +63,9 @@ WiFiServer server(port); void setup() { + // Set wifi mode to client + WiFi.mode(WIFI_STA); + // Initialize Serial connection Serial.begin(115200); delay(10); @@ -73,8 +76,6 @@ void setup() { pinMode(bluePin, OUTPUT); // Connect to WiFi network - Serial.println(); - Serial.println(); Serial.print("Connecting to "); Serial.println(ssid); WiFi.begin(ssid, password); diff --git a/Repetier/BedLeveling.cpp b/Repetier/BedLeveling.cpp new file mode 100644 index 0000000..5925f79 --- /dev/null +++ b/Repetier/BedLeveling.cpp @@ -0,0 +1,635 @@ + +/* +More and more printers now have automatic bed leveling using an ever increasing variety of methods. +This makes the leveling routine one of the most complex parts of the firmware and there is not one +way to level but hundreds of combinations. + +First you should decide on the correction method. Once we know how our bed is tilted we want to +remove that. This correction is defined by BED_CORRECTION_METHOD and allows the following values: +BED_CORRECTION_METHOD 0 +Use a rotation matrix. This will make z axis go up/down while moving in x/y direction to compensate +the tilt. For multiple extruders make sure the height match the tilt of the bed or one will scratch. + +BED_CORRECTION_METHOD 1 +Motorized correction. This method needs a bed that is fixed on 3 points from which 2 have a motor +to change the height. The positions are defined by +BED_MOTOR_1_X, BED_MOTOR_1_Y, BED_MOTOR_2_X, BED_MOTOR_2_Y, BED_MOTOR_3_X, BED_MOTOR_3_Y +Motor 2 and 3 are the one driven by motor driver 0 and 1. These can be extra motors like Felix Pro 1 +uses them or a system with 3 z axis where motors can be controlled individually like the Sparkcube +does. + +Next we have to distinguish several methods of z probing sensors. Each have their own advantages and +disadvantages. First the z probe has a position when activated and that position is defined by +#define Z_PROBE_X_OFFSET 0 +#define Z_PROBE_Y_OFFSET 0 +This is needed since we need to know where we measure the height when the z probe triggers. When +probing is activated you will see a move to make probe go over current extruder position. The +position can be changed in eeprom later on. + +Some probes need to be activated/deactivated so we can use them. This is defined in the scripts +#define Z_PROBE_START_SCRIPT "" +#define Z_PROBE_FINISHED_SCRIPT "" + +Now when we probe we want to know the distance of the extruder to the bed. This is defined by +#define Z_PROBE_HEIGHT 4 +The 4 means that when we trigger the distance of the nozzle tip is 4mm. If your switch tends +to return different points you might repeat a measured point and use the average height: +#define Z_PROBE_SWITCHING_DISTANCE 1 +#define Z_PROBE_REPETITIONS 5 +Switching distance is the z raise needed to turn back a signal reliably to off. Inductive sensors +need only a bit while mechanical switches may require a bit more. + +Next thing to consider is the force for switching. Some beds use a cantilever design and pushing on +the outside easily bends the bed. If your sensor needs some force to trigger you add the error of +bending. For this reason you might add a bending correction. Currently you define +#define BENDING_CORRECTION_A 0 +#define BENDING_CORRECTION_B 0 +#define BENDING_CORRECTION_C 0 +which are the deflections at the 3 z probe points. For all other possible measurements these values +get interpolated. You can modify the values later on in eeprom. For force less sensors set them to 0. + +Next thing is endstop handling. Without bed leveling you normally home to minimum position for x,y and z. +With bed leveling this is not that easy any more. Since we do bed leveling we already assume the bed is +not leveled for x/y moves. So without correction we would hit the bed for different x/y positions at +different heights. As a result we have no real minimum position. That makes a z min endstop quite useless. +There is an exception to this. If your nozzle triggers z min or if a inductive sensor would trigger at a given +position we could use that signal. With nozzle triggers you need to be careful as a drop of filament +would change the height. The other problem is that while homing the auto leveling is not used. So +the only position would be if the z min sensor is directly over the 0,0 coordinate which is the rotation point +if we have matrix based correction. For motor based correction this will work everywhere correctly. + +So the only useful position for a z endstop is z max position. Apart from not having the bed tilt problem it +also allows homing with a full bed so you can continue an aborted print with some gcode tweaking. With z max +homing we adjust the error by simply changing the max. z height. One thing you need to remember is setting +#define ENDSTOP_Z_BACK_ON_HOME 4 +so we release the z max endstop. This is very important if we move xy at z max. Auto leveling might want to +increase z and the endstop might prevent it causing wrong position and a head crash if we later go down. +The value should be larger then the maximum expected tilt. + +Now it is time to define how we measure the bed rotation. Here again we have several methods to choose. +All methods need at least 3 points to define the bed rotation correctly. The quality we get comes +from the selection of the right points and method. + +BED_LEVELING_METHOD 0 +This method measures at the 3 probe points and creates a plane through these points. If you have +a really planar bed this gives the optimum result. The 3 points must not be in one line and have +a long distance to increase numerical stability. + +BED_LEVELING_METHOD 1 +This measures a grid. Probe point 1 is the origin and points 2 and 3 span a grid. We measure +BED_LEVELING_GRID_SIZE points in each direction and compute a regression plane through all +points. This gives a good overall plane if you have small bumps measuring inaccuracies. + +BED_LEVELING_METHOD 2 +Bending correcting 4 point measurement. This is for cantilevered beds that have the rotation axis +not at the side but inside the bed. Here we can assume no bending on the axis and a symmetric +bending to both sides of the axis. So probe points 2 and 3 build the symmetric axis and +point 1 is mirrored to 1m across the axis. Using the symmetry we then remove the bending +from 1 and use that as plane. + +By now the leveling process is finished. All errors that remain are measuring errors and bumps on +the bed it self. For deltas you can enable distortion correction to follow the bumps. + +*/ + +#include "Repetier.h" + +#ifndef BED_LEVELING_METHOD +#define BED_LEVELING_METHOD 0 +#endif + +#ifndef BED_CORRECTION_METHOD +#define BED_CORRECTION_METHOD 0 +#endif + +#ifndef BED_LEVELING_GRID_SIZE +#define BED_LEVELING_GRID_SIZE 5 +#endif + +#ifndef BED_LEVELING_REPETITIONS +#define BED_LEVELING_REPETITIONS 1 +#endif + +#if FEATURE_AUTOLEVEL && FEATURE_Z_PROBE + +class Plane { + public: + // f(x, y) = ax + by + c + float a,b,c; + float z(float x,float y) { + return a * x + y * b + c; + } +}; +class PlaneBuilder { + float sum_xx,sum_xy,sum_yy,sum_x,sum_y,sum_xz,sum_yz,sum_z,n; + public: + void reset() { + sum_xx = sum_xy = sum_yy = sum_x = sum_y = sum_xz = sum_yz = sum_z = n = 0; + } + void addPoint(float x,float y,float z) { + n++; + sum_xx += x * x; + sum_xy += x * y; + sum_yy += y * y; + sum_x += x; + sum_y += y; + sum_xz += x * z; + sum_yz += y * z; + sum_z += z; + } + void createPlane(Plane &plane) { + float det = (sum_x*(sum_xy*sum_y-sum_x*sum_yy)+sum_xx*(n*sum_yy-sum_y*sum_y)+sum_xy*(sum_x*sum_y-n*sum_xy)); + plane.a = ((sum_xy*sum_y-sum_x*sum_yy)*sum_z+(sum_x*sum_y-n*sum_xy)*sum_yz+sum_xz*(n*sum_yy-sum_y*sum_y)) /det; + plane.b = ((sum_x*sum_xy-sum_xx*sum_y)*sum_z+(n*sum_xx-sum_x*sum_x)*sum_yz+sum_xz*(sum_x*sum_y-n*sum_xy)) /det; + plane.c = ((sum_xx*sum_yy-sum_xy*sum_xy)*sum_z+(sum_x*sum_xy-sum_xx*sum_y)*sum_yz+sum_xz*(sum_xy*sum_y-sum_x*sum_yy))/det; + Com::printF(PSTR("plane: a = "),plane.a,4); + Com::printF(PSTR(" b = "),plane.b,4); + Com::printFLN(PSTR(" c = "),plane.c,4); + } +}; + +bool measureAutolevelPlane(Plane &plane) { + PlaneBuilder builder; + builder.reset(); + #if BED_LEVELING_METHOD == 0 // 3 point + float h; + Printer::moveTo(EEPROM::zProbeX1(),EEPROM::zProbeY1(),IGNORE_COORDINATE,IGNORE_COORDINATE,EEPROM::zProbeXYSpeed()); + h = Printer::runZProbe(false,false); + if(h < -1) + return false; + builder.addPoint(EEPROM::zProbeX1(),EEPROM::zProbeY1(),h); + Printer::moveTo(EEPROM::zProbeX2(),EEPROM::zProbeY2(),IGNORE_COORDINATE,IGNORE_COORDINATE,EEPROM::zProbeXYSpeed()); + h = Printer::runZProbe(false,false); + if(h < -1) + return false; + builder.addPoint(EEPROM::zProbeX2(),EEPROM::zProbeY2(),h); + Printer::moveTo(EEPROM::zProbeX3(),EEPROM::zProbeY3(),IGNORE_COORDINATE,IGNORE_COORDINATE,EEPROM::zProbeXYSpeed()); + h = Printer::runZProbe(false,false); + if(h < -1) + return false; + builder.addPoint(EEPROM::zProbeX3(),EEPROM::zProbeY3(),h); + #elif BED_LEVELING_METHOD == 1 // linear regression + float delta = 1.0/(BED_LEVELING_GRID_SIZE - 1); + float ox = EEPROM::zProbeX1(); + float oy = EEPROM::zProbeY1(); + float ax = delta * (EEPROM::zProbeX2() - EEPROM::zProbeX1()); + float ay = delta * (EEPROM::zProbeY2() - EEPROM::zProbeY1()); + float bx = delta * (EEPROM::zProbeX3() - EEPROM::zProbeX1()); + float by = delta * (EEPROM::zProbeY3() - EEPROM::zProbeY1()); + for(int ix = 0; ix < BED_LEVELING_GRID_SIZE; ix++) { + for(int iy = 0; iy < BED_LEVELING_GRID_SIZE; iy++) { + float px = ox + static_cast(ix) * ax + static_cast(iy) * bx; + float py = oy + static_cast(ix) * ay + static_cast(iy) * by; + Printer::moveTo(px,py,IGNORE_COORDINATE,IGNORE_COORDINATE,EEPROM::zProbeXYSpeed()); + float h = Printer::runZProbe(false,false); + if(h < -1) + return false; + builder.addPoint(px,py,h); + } + } + #elif BED_LEVELING_METHOD == 2 // 4 point symmetric + float h1,h2,h3,h4; + float apx = EEPROM::zProbeX1() - EEPROM::zProbeX2(); + float apy = EEPROM::zProbeY1() - EEPROM::zProbeY2(); + float abx = EEPROM::zProbeX3() - EEPROM::zProbeX2(); + float aby = EEPROM::zProbeY3() - EEPROM::zProbeY2(); + float ab2 = abx * abx + aby * aby; + float abap = apx * abx + apy * aby; + float t = abap / ab2; + float xx = EEPROM::zProbeX2() + t * abx; + float xy = EEPROM::zProbeY2() + t * aby; + float x1Mirror = EEPROM::zProbeX1() + 2.0 * (xx - EEPROM::zProbeX1()); + float y1Mirror = EEPROM::zProbeY1() + 2.0 * (xy - EEPROM::zProbeY1()); + Printer::moveTo(EEPROM::zProbeX1(),EEPROM::zProbeY1(),IGNORE_COORDINATE,IGNORE_COORDINATE,EEPROM::zProbeXYSpeed()); + h1 = Printer::runZProbe(false,false); + if(h1 < -1) + return false; + Printer::moveTo(EEPROM::zProbeX2(),EEPROM::zProbeY2(),IGNORE_COORDINATE,IGNORE_COORDINATE,EEPROM::zProbeXYSpeed()); + h2 = Printer::runZProbe(false,false); + if(h2 < -1) + return false; + Printer::moveTo(EEPROM::zProbeX3(),EEPROM::zProbeY3(),IGNORE_COORDINATE,IGNORE_COORDINATE,EEPROM::zProbeXYSpeed()); + h3 = Printer::runZProbe(false,false); + if(h3 < -1) + return false; + Printer::moveTo(x1Mirror,y1Mirror,IGNORE_COORDINATE,IGNORE_COORDINATE,EEPROM::zProbeXYSpeed()); + h4 = Printer::runZProbe(false,false); + if(h4 < -1) + return false; + t = h2 + (h3-h2) * t; // theoretical height for crossing point for symmetric axis + h1 = t - (h4-h1) * 0.5; // remove bending part + builder.addPoint(EEPROM::zProbeX1(),EEPROM::zProbeY1(),h1); + builder.addPoint(EEPROM::zProbeX2(),EEPROM::zProbeY2(),h2); + builder.addPoint(EEPROM::zProbeX3(),EEPROM::zProbeY3(),h3); + #else + #error Unknown bed leveling method + #endif + builder.createPlane(plane); + return true; +} + +void correctAutolevel(GCode *code,Plane &plane) { + #if BED_CORRECTION_METHOD == 0 // rotation matrix + Printer::buildTransformationMatrix(plane.z(EEPROM::zProbeX1(),EEPROM::zProbeY1()),plane.z(EEPROM::zProbeX2(),EEPROM::zProbeY2()),plane.z(EEPROM::zProbeX3(),EEPROM::zProbeY3())); + #elif BED_CORRECTION_METHOD == 1 // motorized correction + #if !defined(NUM_MOTOR_DRIVERS) || NUM_MOTOR_DRIVERS < 2 + #error You need to define 2 motors for motorized bed correction + #endif + Commands::waitUntilEndOfAllMoves(); // move steppers might be leveling steppers as well ! + float h1 = plane.z(BED_MOTOR_1_X,BED_MOTOR_1_Y); + float h2 = plane.z(BED_MOTOR_2_X,BED_MOTOR_2_Y); + float h3 = plane.z(BED_MOTOR_3_X,BED_MOTOR_3_Y); + // h1 is reference heights, h2 => motor 0, h3 => motor 1 + h2 -= h1; + h3 -= h1; + MotorDriverInterface *motor2 = getMotorDriver(0); + MotorDriverInterface *motor3 = getMotorDriver(1); + motor2->setCurrentAs(0); + motor3->setCurrentAs(0); + motor2->gotoPosition(h2); + motor3->gotoPosition(h3); + motor2->disable(); + motor3->disable(); // now bed is even + Printer::currentPositionSteps[Z_AXIS] = h1 * Printer::axisStepsPerMM[Z_AXIS]; + #else + #error Unknown bed correction method set + #endif +} + +/* +Implementation of the G32 command +G32 S<0..2> - Autolevel print bed. S = 1 measure zLength, S = 2 Measure and store new zLength +S = 0 : Do not update length - use this if you have not homed before or you mess up zlength! +S = 1 : Measure zLength so homing works +S = 2 : Like s = 1 plus store results in EEPROM for next connection. +*/ +void runBedLeveling(GCode *com) { + float h1,h2,h3,hc,oldFeedrate = Printer::feedrate; + int s = com->hasS() ? com->S : -1; + #if DISTORTION_CORRECTION + bool distEnabled = Printer::distortion.isEnabled(); + Printer::distortion.disable(false); // if level has changed, distortion is also invalid + #endif + Printer::setAutolevelActive(false); // iterate + Printer::resetTransformationMatrix(true); // in case we switch from matrix to motorized! + #if DRIVE_SYSTEM == DELTA + // It is not possible to go to the edges at the top, also users try + // it often and wonder why the coordinate system is then wrong. + // For that reason we ensure a correct behavior by code. + Printer::homeAxis(true, true, true); + Printer::moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeBedDistance() + EEPROM::zProbeHeight(), IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]); + #endif + Printer::startProbing(true); + //GCode::executeFString(Com::tZProbeStartScript); + Printer::coordinateOffset[X_AXIS] = Printer::coordinateOffset[Y_AXIS] = Printer::coordinateOffset[Z_AXIS] = 0; + Plane plane; +#if BED_CORRECTION_METHOD == 1 + for(int r = 0; r < BED_LEVELING_REPETITIONS; r++) { +#if DRIVE_SYSTEM == DELTA + if(r > 0) { + Printer::finishProbing(); + Printer::homeAxis(true, true, true); + Printer::moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeBedDistance() + EEPROM::zProbeHeight(), IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]); + Printer::startProbing(true); + } +#endif +#endif + if(!measureAutolevelPlane(plane)) { + Com::printErrorFLN(PSTR("Probing had returned errors - autoleveling canceled.")); + return; + } + correctAutolevel(com,plane); + + // Leveling is finished now update own positions and store leveling data if needed + float currentZ = plane.z((float)Printer::currentPositionSteps[X_AXIS] * Printer::invAxisStepsPerMM[X_AXIS],(float)Printer::currentPositionSteps[Y_AXIS] * Printer::invAxisStepsPerMM[Y_AXIS]); + Com::printF(PSTR("CurrentZ:"),currentZ);Com::printFLN(PSTR(" atZ:"),Printer::currentPosition[Z_AXIS]); + // With max z endstop we adjust zlength so after next homing we have also a calibrated printer + Printer::zMin = 0; + #if MAX_HARDWARE_ENDSTOP_Z + float xRot,yRot,zRot; + #if BED_CORRECTION_METHOD != 1 + Printer::transformFromPrinter(Printer::currentPosition[X_AXIS],Printer::currentPosition[Y_AXIS],Printer::currentPosition[Z_AXIS],xRot,yRot,zRot); + Com::printFLN(PSTR("Z after rotation:"),zRot); + #else + zRot = Printer::currentPosition[Z_AXIS]; + #endif + // With max z endstop we adjust zlength so after next homing we have also a calibrated printer + if(s != 0) { + Printer::zLength += currentZ - zRot; + Com::printFLN(Com::tZProbePrinterHeight, Printer::zLength); + } + #endif + Printer::currentPositionSteps[Z_AXIS] = currentZ * Printer::axisStepsPerMM[Z_AXIS]; + Printer::updateCurrentPosition(true); +#if BED_CORRECTION_METHOD == 1 + if(fabs(plane.a) < 0.00025 && fabsf(plane.b) < 0.00025 ) + break; // we reached achievable precision so we can stop + } +#endif + Printer::updateDerivedParameter(); + Printer::finishProbing(); +#if BED_CORRECTION_METHOD != 1 + Printer::setAutolevelActive(true); // only for software correction or we can spare the comp. time +#endif + if(s >= 2) { + EEPROM::storeDataIntoEEPROM(); + } + Printer::updateCurrentPosition(true); + Commands::printCurrentPosition(PSTR("G32 ")); + #if DISTORTION_CORRECTION + if(distEnabled) + Printer::distortion.enable(false); // if level has changed, distortion is also invalid + #endif + #if DRIVE_SYSTEM == DELTA + Printer::homeAxis(true, true, true); // shifting z makes positioning invalid, need to recalibrate + #endif + Printer::feedrate = oldFeedrate; +} + +#endif + +void Printer::setAutolevelActive(bool on) +{ + #if FEATURE_AUTOLEVEL + if(on == isAutolevelActive()) return; + flag0 = (on ? flag0 | PRINTER_FLAG0_AUTOLEVEL_ACTIVE : flag0 & ~PRINTER_FLAG0_AUTOLEVEL_ACTIVE); + if(on) + Com::printInfoFLN(Com::tAutolevelEnabled); + else + Com::printInfoFLN(Com::tAutolevelDisabled); + updateCurrentPosition(false); + #endif // FEATURE_AUTOLEVEL +} +#if MAX_HARDWARE_ENDSTOP_Z +float Printer::runZMaxProbe() +{ + #if NONLINEAR_SYSTEM + long startZ = realDeltaPositionSteps[Z_AXIS] = currentDeltaPositionSteps[Z_AXIS]; // update real + #endif + Commands::waitUntilEndOfAllMoves(); + long probeDepth = 2*(Printer::zMaxSteps-Printer::zMinSteps); + stepsRemainingAtZHit = -1; + setZProbingActive(true); + PrintLine::moveRelativeDistanceInSteps(0,0,probeDepth,0,EEPROM::zProbeSpeed(),true,true); + if(stepsRemainingAtZHit < 0) + { + Com::printErrorFLN(Com::tZProbeFailed); + return -1; + } + setZProbingActive(false); + currentPositionSteps[Z_AXIS] -= stepsRemainingAtZHit; + #if NONLINEAR_SYSTEM + probeDepth -= (realDeltaPositionSteps[Z_AXIS] - startZ); + #else + probeDepth -= stepsRemainingAtZHit; + #endif + float distance = (float)probeDepth * invAxisStepsPerMM[Z_AXIS]; + Com::printF(Com::tZProbeMax,distance); + Com::printF(Com::tSpaceXColon,realXPosition()); + Com::printFLN(Com::tSpaceYColon,realYPosition()); + PrintLine::moveRelativeDistanceInSteps(0,0,-probeDepth,0,EEPROM::zProbeSpeed(),true,true); + return distance; +} +#endif + +#if FEATURE_Z_PROBE +void Printer::startProbing(bool runScript) { + float oldOffX = Printer::offsetX; + float oldOffY = Printer::offsetY; + float oldOffZ = Printer::offsetZ; + if(runScript) + GCode::executeFString(Com::tZProbeStartScript); + float maxStartHeight = EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0) + 0.1; + if(currentPosition[Z_AXIS] > maxStartHeight) { + moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, maxStartHeight, IGNORE_COORDINATE, homingFeedrate[Z_AXIS]); + } + Printer::offsetX = -EEPROM::zProbeXOffset(); + Printer::offsetY = -EEPROM::zProbeYOffset(); + Printer::offsetZ = 0; // we correct this with probe height + PrintLine::moveRelativeDistanceInSteps((Printer::offsetX - oldOffX) * Printer::axisStepsPerMM[X_AXIS], + (Printer::offsetY - oldOffY) * Printer::axisStepsPerMM[Y_AXIS], + 0, 0, EEPROM::zProbeXYSpeed(), true, ALWAYS_CHECK_ENDSTOPS); +} + +void Printer::finishProbing() { + float oldOffX = Printer::offsetX; + float oldOffY = Printer::offsetY; + float oldOffZ = Printer::offsetZ; + GCode::executeFString(Com::tZProbeEndScript); + if(Extruder::current) + { + Printer::offsetX = -Extruder::current->xOffset * Printer::invAxisStepsPerMM[X_AXIS]; + Printer::offsetY = -Extruder::current->yOffset * Printer::invAxisStepsPerMM[Y_AXIS]; + Printer::offsetZ = -Extruder::current->zOffset * Printer::invAxisStepsPerMM[Z_AXIS]; + } + PrintLine::moveRelativeDistanceInSteps((Printer::offsetX - oldOffX) * Printer::axisStepsPerMM[X_AXIS], + (Printer::offsetY - oldOffY) * Printer::axisStepsPerMM[Y_AXIS], + (Printer::offsetZ - oldOffZ) * Printer::axisStepsPerMM[Z_AXIS], 0, EEPROM::zProbeXYSpeed(), true, ALWAYS_CHECK_ENDSTOPS); +} + +/* +This is the most important function for bed leveling. It does +1. Run probe start script if first = true and runStartScript = true +2. Position zProbe at current position if first = true. If we are more then maxStartHeight away from bed we also go down to that distance. +3. Measure the the steps until probe hits the bed. +4. Undo positioning to z probe and run finish script if last = true. + +Now we compute the nozzle height as follows: +a) Compute average height from repeated measurements +b) Add zProbeHeight to correct difference between triggering point and nozzle height above bed +c) If Z_PROBE_Z_OFFSET_MODE == 1 we add zProbeZOffset() that is coating thickness if we measure below coating with indictive sensor. +d) Add distortion correction. +e) Add bending correction + +Then we return the measured and corrected z distance. +*/ +float Printer::runZProbe(bool first,bool last,uint8_t repeat,bool runStartScript) +{ + float oldOffX = Printer::offsetX; + float oldOffY = Printer::offsetY; + float oldOffZ = Printer::offsetZ; + if(first) + startProbing(runStartScript); + Commands::waitUntilEndOfAllMoves(); + int32_t sum = 0, probeDepth; + int32_t shortMove = static_cast((float)Z_PROBE_SWITCHING_DISTANCE * axisStepsPerMM[Z_AXIS]); // distance to go up for repeated moves + int32_t lastCorrection = currentPositionSteps[Z_AXIS]; // starting position + #if NONLINEAR_SYSTEM + realDeltaPositionSteps[Z_AXIS] = currentDeltaPositionSteps[Z_AXIS]; // update real + #endif + //int32_t updateZ = 0; + waitForZProbeStart(); + for(int8_t r = 0; r < repeat; r++) + { + probeDepth = 2 * (Printer::zMaxSteps - Printer::zMinSteps); // probe should always hit within this distance + stepsRemainingAtZHit = -1; // Marker that we did not hit z probe + //int32_t offx = axisStepsPerMM[X_AXIS] * EEPROM::zProbeXOffset(); + //int32_t offy = axisStepsPerMM[Y_AXIS] * EEPROM::zProbeYOffset(); + //PrintLine::moveRelativeDistanceInSteps(-offx,-offy,0,0,EEPROM::zProbeXYSpeed(),true,true); + setZProbingActive(true); + PrintLine::moveRelativeDistanceInSteps(0, 0, -probeDepth, 0, EEPROM::zProbeSpeed(), true, true); + if(stepsRemainingAtZHit < 0) + { + Com::printErrorFLN(Com::tZProbeFailed); + return -1; + } + setZProbingActive(false); + #if NONLINEAR_SYSTEM + stepsRemainingAtZHit = realDeltaPositionSteps[C_TOWER] - currentDeltaPositionSteps[C_TOWER]; // nonlinear moves may split z so stepsRemainingAtZHit is only what is left from last segment not total move. This corrects the problem. + #endif + #if DRIVE_SYSTEM == DELTA + currentDeltaPositionSteps[A_TOWER] += stepsRemainingAtZHit; // Update difference + currentDeltaPositionSteps[B_TOWER] += stepsRemainingAtZHit; + currentDeltaPositionSteps[C_TOWER] += stepsRemainingAtZHit; + #endif + currentPositionSteps[Z_AXIS] += stepsRemainingAtZHit; // now current position is correct + sum += lastCorrection - currentPositionSteps[Z_AXIS]; + if(r + 1 < repeat) // go only shortest possible move up for repetitions + PrintLine::moveRelativeDistanceInSteps(0, 0, shortMove, 0, EEPROM::zProbeSpeed(), true, false); + } + float distance = static_cast(sum) * invAxisStepsPerMM[Z_AXIS] / static_cast(repeat) + EEPROM::zProbeHeight(); + #if Z_PROBE_Z_OFFSET_MODE == 1 + distance += EEPROM::zProbeZOffset(); // We measured including coating, so we need to add coating thickness! + #endif + #if DISTORTION_CORRECTION + float zCorr = 0; + if(Printer::distortion.isEnabled()) { + zCorr = distortion.correct(currentPositionSteps[X_AXIS] + EEPROM::zProbeXOffset() * axisStepsPerMM[X_AXIS],currentPositionSteps[Y_AXIS] + + EEPROM::zProbeYOffset() * axisStepsPerMM[Y_AXIS],0) * invAxisStepsPerMM[Z_AXIS]; + distance += zCorr; + } + #endif + distance += bendingCorrectionAt(currentPosition[X_AXIS], currentPosition[Y_AXIS]); + Com::printF(Com::tZProbe, distance); + Com::printF(Com::tSpaceXColon, realXPosition()); + #if DISTORTION_CORRECTION + if(Printer::distortion.isEnabled()) { + Com::printF(Com::tSpaceYColon, realYPosition()); + Com::printFLN(PSTR(" zCorr:"), zCorr); + } else { + Com::printFLN(Com::tSpaceYColon, realYPosition()); + } + #else + Com::printFLN(Com::tSpaceYColon, realYPosition()); + #endif + // Go back to start position + PrintLine::moveRelativeDistanceInSteps(0, 0, lastCorrection - currentPositionSteps[Z_AXIS], 0, EEPROM::zProbeSpeed(), true, false); + //PrintLine::moveRelativeDistanceInSteps(offx,offy,0,0,EEPROM::zProbeXYSpeed(),true,true); + if(last) + finishProbing(); + return distance; +} + +float Printer::bendingCorrectionAt(float x, float y) { + RVector3 p0(EEPROM::zProbeX1(),EEPROM::zProbeY1(),EEPROM::bendingCorrectionA()); + RVector3 p1(EEPROM::zProbeX2(),EEPROM::zProbeY2(),EEPROM::bendingCorrectionB()); + RVector3 p2(EEPROM::zProbeX3(),EEPROM::zProbeY3(),EEPROM::bendingCorrectionC()); + RVector3 a = p1-p0,b = p2 - p0; + RVector3 n = a.cross(b); + RVector3 l0(x,y,0); + return ((p0 - l0).scalar(n)) / n.z; +} + +void Printer::waitForZProbeStart() +{ + #if Z_PROBE_WAIT_BEFORE_TEST + Endstops::update(); + Endstops::update(); // double test to get right signal. Needed for crosstalk protection. + if(Endstops::zProbe()) return; + #if UI_DISPLAY_TYPE != NO_DISPLAY + uid.setStatusP(Com::tHitZProbe); + uid.refreshPage(); + #endif + #ifdef DEBUG_PRINT + debugWaitLoop = 3; + #endif + while(!Endstops::zProbe()) + { + defaultLoopActions(); + Endstops::update(); + Endstops::update(); // double test to get right signal. Needed for crosstalk protection. + } + #ifdef DEBUG_PRINT + debugWaitLoop = 4; + #endif + HAL::delayMilliseconds(30); + while(Endstops::zProbe()) + { + defaultLoopActions(); + Endstops::update(); + Endstops::update(); // double test to get right signal. Needed for crosstalk protection. + } + HAL::delayMilliseconds(30); + UI_CLEAR_STATUS; + #endif +} +#endif + +#if FEATURE_AUTOLEVEL +void Printer::transformToPrinter(float x,float y,float z,float &transX,float &transY,float &transZ) +{ + #if FEATURE_AXISCOMP + // Axis compensation: + x = x + y * EEPROM::axisCompTanXY() + z * EEPROM::axisCompTanXZ(); + y = y + z * EEPROM::axisCompTanYZ(); + #endif + transX = x * autolevelTransformation[0] + y * autolevelTransformation[3] + z * autolevelTransformation[6]; + transY = x * autolevelTransformation[1] + y * autolevelTransformation[4] + z * autolevelTransformation[7]; + transZ = x * autolevelTransformation[2] + y * autolevelTransformation[5] + z * autolevelTransformation[8]; +} + +void Printer::transformFromPrinter(float x,float y,float z,float &transX,float &transY,float &transZ) +{ + transX = x * autolevelTransformation[0] + y * autolevelTransformation[1] + z * autolevelTransformation[2]; + transY = x * autolevelTransformation[3] + y * autolevelTransformation[4] + z * autolevelTransformation[5]; + transZ = x * autolevelTransformation[6] + y * autolevelTransformation[7] + z * autolevelTransformation[8]; + #if FEATURE_AXISCOMP + // Axis compensation: + transY = transY - transZ * EEPROM::axisCompTanYZ(); + transX = transX - transY * EEPROM::axisCompTanXY() - transZ * EEPROM::axisCompTanXZ(); + #endif +} + +void Printer::resetTransformationMatrix(bool silent) +{ + autolevelTransformation[0] = autolevelTransformation[4] = autolevelTransformation[8] = 1; + autolevelTransformation[1] = autolevelTransformation[2] = autolevelTransformation[3] = + autolevelTransformation[5] = autolevelTransformation[6] = autolevelTransformation[7] = 0; + if(!silent) + Com::printInfoFLN(Com::tAutolevelReset); +} + +void Printer::buildTransformationMatrix(float h1,float h2,float h3) +{ + float ax = EEPROM::zProbeX2()-EEPROM::zProbeX1(); + float ay = EEPROM::zProbeY2()-EEPROM::zProbeY1(); + float az = h1-h2; + float bx = EEPROM::zProbeX3()-EEPROM::zProbeX1(); + float by = EEPROM::zProbeY3()-EEPROM::zProbeY1(); + float bz = h1-h3; + // First z direction + autolevelTransformation[6] = ay * bz - az * by; + autolevelTransformation[7] = az * bx - ax * bz; + autolevelTransformation[8] = ax * by - ay * bx; + float len = sqrt(autolevelTransformation[6] * autolevelTransformation[6] + autolevelTransformation[7] * autolevelTransformation[7] + autolevelTransformation[8] * autolevelTransformation[8]); + if(autolevelTransformation[8] < 0) len = -len; + autolevelTransformation[6] /= len; + autolevelTransformation[7] /= len; + autolevelTransformation[8] /= len; + autolevelTransformation[3] = 0; + autolevelTransformation[4] = autolevelTransformation[8]; + autolevelTransformation[5] = -autolevelTransformation[7]; + // cross(y,z) + autolevelTransformation[0] = autolevelTransformation[4] * autolevelTransformation[8] - autolevelTransformation[5] * autolevelTransformation[7]; + autolevelTransformation[1] = autolevelTransformation[5] * autolevelTransformation[6];// - autolevelTransformation[3] * autolevelTransformation[8]; + autolevelTransformation[2] = /*autolevelTransformation[3] * autolevelTransformation[7]*/ - autolevelTransformation[4] * autolevelTransformation[6]; + len = sqrt(autolevelTransformation[0] * autolevelTransformation[0] + autolevelTransformation[1] * autolevelTransformation[1] + autolevelTransformation[2] * autolevelTransformation[2]); + autolevelTransformation[0] /= len; + autolevelTransformation[1] /= len; + autolevelTransformation[2] /= len; + len = sqrt(autolevelTransformation[4] * autolevelTransformation[4] + autolevelTransformation[5] * autolevelTransformation[5]); + autolevelTransformation[4] /= len; + autolevelTransformation[5] /= len; + Com::printArrayFLN(Com::tTransformationMatrix,autolevelTransformation, 9, 6); +} +#endif diff --git a/Repetier/Commands.cpp b/Repetier/Commands.cpp index 14e3bb0..59a6816 100644 --- a/Repetier/Commands.cpp +++ b/Repetier/Commands.cpp @@ -21,7 +21,7 @@ #include "Repetier.h" -const uint8_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; // Sensitive pin list for M42 +const int8_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; // Sensitive pin list for M42 int Commands::lowestRAMValue = MAX_RAM; int Commands::lowestRAMValueSend = MAX_RAM; @@ -161,6 +161,7 @@ void Commands::printCurrentPosition(FSTRINGPARAM(s)) void Commands::printTemperatures(bool showRaw) { +#if NUM_EXTRUDER > 0 float temp = Extruder::current->tempControl.currentTemperatureC; #if HEATED_BED_SENSOR_TYPE == 0 Com::printF(Com::tTColon,temp); @@ -198,8 +199,15 @@ void Commands::printTemperatures(bool showRaw) Com::printF(Com::tColon,(1023 << (2 - ANALOG_REDUCE_BITS)) - extruder[i].tempControl.currentTemperature); } } +#elif NUM_EXTRUDER == 1 + if(showRaw) + { + Com::printF(Com::tSpaceRaw,(int)0); + Com::printF(Com::tColon,(1023 << (2 - ANALOG_REDUCE_BITS)) - extruder[0].tempControl.currentTemperature); + } #endif Com::println(); +#endif } void Commands::changeFeedrateMultiply(int factor) { @@ -222,27 +230,39 @@ void Commands::changeFlowrateMultiply(int factor) Com::printFLN(Com::tFlowMultiply, factor); } +#if FEATURE_FAN_CONTROL uint8_t fanKickstart; -void Commands::setFanSpeed(int speed,bool wait) +#endif +#if FEATURE_FAN2_CONTROL +uint8_t fan2Kickstart; +#endif + +void Commands::setFanSpeed(int speed, bool immediately) { -#if FAN_PIN>-1 && FEATURE_FAN_CONTROL +#if FAN_PIN >- 1 && FEATURE_FAN_CONTROL + if(Printer::fanSpeed == speed) + return; speed = constrain(speed,0,255); Printer::setMenuMode(MENU_MODE_FAN_RUNNING,speed != 0); - if(wait) - Commands::waitUntilEndOfAllMoves(); // use only if neededthis to change the speed exactly at that point, but it may cause blobs if you do! - if(speed != pwm_pos[NUM_EXTRUDER + 2]) - { - Com::printFLN(Com::tFanspeed,speed); // send only new values to break update loops! -#if FAN_KICKSTART_TIME - if(fanKickstart == 0 && speed > pwm_pos[NUM_EXTRUDER + 2] && speed < 85) - { - if(pwm_pos[NUM_EXTRUDER + 2]) fanKickstart = FAN_KICKSTART_TIME/100; - else fanKickstart = FAN_KICKSTART_TIME/25; + Printer::fanSpeed = speed; + if(PrintLine::linesCount == 0 || immediately) { + if(Printer::mode == PRINTER_MODE_FFF) + { + for(fast8_t i = 0; i < PRINTLINE_CACHE_SIZE; i++) + PrintLine::lines[i].secondSpeed = speed; // fill all printline buffers with new fan speed value } + Printer::setFanSpeedDirectly(speed); + } + Com::printFLN(Com::tFanspeed,speed); // send only new values to break update loops! #endif - } - pwm_pos[NUM_EXTRUDER + 2] = speed; -#endif +} +void Commands::setFan2Speed(int speed) +{ + #if FAN2_PIN >- 1 && FEATURE_FAN2_CONTROL + speed = constrain(speed,0,255); + Printer::setFan2SpeedDirectly(speed); + Com::printFLN(Com::tFan2speed,speed); // send only new values to break update loops! + #endif } void Commands::reportPrinterUsage() @@ -252,9 +272,10 @@ void Commands::reportPrinterUsage() Com::printF(Com::tPrintedFilament, dist, 2); Com::printF(Com::tSpacem); bool alloff = true; +#if NUM_EXTRUDER > 0 for(uint8_t i = 0; i < NUM_EXTRUDER; i++) if(tempController[i]->targetTemperatureC > 15) alloff = false; - +#endif int32_t seconds = (alloff ? 0 : (HAL::timeInMilliseconds() - Printer::msecondsPrinting) / 1000) + HAL::eprGetInt32(EPR_PRINTING_TIME); int32_t tmp = seconds / 86400; seconds -= tmp * 86400; @@ -860,7 +881,7 @@ void Commands::processArc(GCode *com) return; } // Invert the sign of h_x2_div_d if the circle is counter clockwise (see sketch below) - if (com->G==3) + if (com->G == 3) { h_x2_div_d = -h_x2_div_d; } @@ -892,8 +913,8 @@ void Commands::processArc(GCode *com) r = -r; // Finished with r. Set to positive for mc_arc } // Complete the operation by calculating the actual center of the arc - offset[0] = 0.5*(x-(y*h_x2_div_d)); - offset[1] = 0.5*(y+(x*h_x2_div_d)); + offset[0] = 0.5 * (x - (y * h_x2_div_d)); + offset[1] = 0.5 * (y + (x * h_x2_div_d)); } else // Offset mode specific computations @@ -906,7 +927,7 @@ void Commands::processArc(GCode *com) PrintLine::arc(position, target, offset, r, isclockwise); } #endif - +extern void runBedLeveling(GCode *com); /** \brief Execute the G command stored in com. */ @@ -917,6 +938,13 @@ void Commands::processGCode(GCode *com) { case 0: // G0 -> G1 case 1: // G1 +#if defined(SUPPORT_LASER) && SUPPORT_LASER + { // disable laser for G0 moves + bool laserOn = LaserDriver::laserOn; + if(com->G == 0 && Printer::mode == PRINTER_MODE_LASER) { + LaserDriver::laserOn = false; + } +#endif // defined if(com->hasS()) Printer::setNoDestinationCheck(com->S != 0); if(Printer::setDestinationStepsFromGCode(com)) // For X Y Z E F #if NONLINEAR_SYSTEM @@ -941,18 +969,33 @@ void Commands::processGCode(GCode *com) int lc = (int)PrintLine::linesCount; int lp = (int)PrintLine::linesPos; int wp = (int)PrintLine::linesWritePos; - int n = (wp-lp); + int n = (wp - lp); if(n < 0) n += PRINTLINE_CACHE_SIZE; noInts.unprotect(); if(n != lc) Com::printFLN(PSTR("Buffer corrupted")); } #endif +#if defined(SUPPORT_LASER) && SUPPORT_LASER + LaserDriver::laserOn = laserOn; + } +#endif // defined break; #if ARC_SUPPORT case 2: // CW Arc case 3: // CCW Arc MOTION_MODE_CW_ARC: case MOTION_MODE_CCW_ARC: +#if defined(SUPPORT_LASER) && SUPPORT_LASER + { // disable laser for G0 moves + bool laserOn = LaserDriver::laserOn; + if(com->G == 0 && Printer::mode == PRINTER_MODE_LASER) { + LaserDriver::laserOn = false; + } +#endif // defined processArc(com); +#if defined(SUPPORT_LASER) && SUPPORT_LASER + LaserDriver::laserOn = laserOn; + } +#endif // defined break; #endif case 4: // G4 dwell @@ -1034,7 +1077,7 @@ void Commands::processGCode(GCode *com) Printer::homeAxis(true,true,true); #else Printer::currentPositionSteps[Z_AXIS] = sum * Printer::axisStepsPerMM[Z_AXIS]; - Printer::zLength = Printer::runZMaxProbe() + sum-ENDSTOP_Z_BACK_ON_HOME; + Printer::zLength = Printer::runZMaxProbe() + sum - ENDSTOP_Z_BACK_ON_HOME; #endif Com::printInfoFLN(Com::tZProbeZReset); Com::printFLN(Com::tZProbePrinterHeight,Printer::zLength); @@ -1074,7 +1117,10 @@ void Commands::processGCode(GCode *com) break; #if FEATURE_AUTOLEVEL case 32: // G32 Auto-Bed leveling + runBedLeveling(com); +#if 0 { + #if DISTORTION_CORRECTION Printer::distortion.disable(true); // if level has changed, distortion is also invalid #endif @@ -1082,7 +1128,7 @@ void Commands::processGCode(GCode *com) #if DRIVE_SYSTEM == DELTA // It is not possible to go to the edges at the top, also users try // it often and wonder why the coordinate system is then wrong. - // For that reason we ensure a correct behaviour by code. + // For that reason we ensure a correct behavior by code. Printer::homeAxis(true, true, true); Printer::moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, EEPROM::zProbeBedDistance() + EEPROM::zProbeHeight(), IGNORE_COORDINATE, Printer::homingFeedrate[Z_AXIS]); #endif @@ -1099,18 +1145,6 @@ void Commands::processGCode(GCode *com) Printer::moveTo(EEPROM::zProbeX3(),EEPROM::zProbeY3(),IGNORE_COORDINATE,IGNORE_COORDINATE,EEPROM::zProbeXYSpeed()); h3 = Printer::runZProbe(false,true); if(h3 < -1) break; - // Zprobe with force feedback may bed bed differently for different points. - // these settings allow correction of the bending distance so leveling is correct afterwards. - // Values are normally negative with bending amount on trigger. -#ifdef ZPROBE_1_BENDING_CORRECTION - h1 += ZPROBE_1_BENDING_CORRECTION; -#endif -#ifdef ZPROBE_2_BENDING_CORRECTION - h2 += ZPROBE_2_BENDING_CORRECTION; -#endif -#ifdef ZPROBE_3_BENDING_CORRECTION - h3 += ZPROBE_3_BENDING_CORRECTION; -#endif #if defined(MOTORIZED_BED_LEVELING) && defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS >= 2 // h1 is reference heights, h2 => motor 0, h3 => motor 1 h2 -= h1; @@ -1179,8 +1213,29 @@ void Commands::processGCode(GCode *com) #endif Printer::feedrate = oldFeedrate; } +#endif break; #endif +#endif +#if DISTORTION_CORRECTION + case 33: { + if(com->hasL()) { // G33 L0 - List distortion matrix + Printer::distortion.showMatrix(); + } else if(com->hasR()) { // G33 R0 - Reset distortion matrix + Printer::distortion.resetCorrection(); + } else if(com->hasX() || com->hasY() || com->hasZ()) { // G33 X Y Z - Set correction for nearest point + if(com->hasX() && com->hasY() && com->hasZ()) { + Printer::distortion.set(com->X, com->Y, com->Z); + } else { + Com::printErrorFLN(PSTR("You need to define X, Y and Z to set a point!")); + } + } else { // G33 + float oldFeedrate = Printer::feedrate; + Printer::measureDistortion(); + Printer::feedrate = oldFeedrate; + } + } + break; #endif case 90: // G90 Printer::relativeCoordinateMode = false; @@ -1345,6 +1400,7 @@ void Commands::processGCode(GCode *com) EEPROM::setDeltaTowerZOffsetSteps(offz); } #endif + PrintLine::moveRelativeDistanceInSteps(0, 0, -5*Printer::axisStepsPerMM[Z_AXIS], 0, Printer::homingFeedrate[Z_AXIS], true, true); Printer::homeAxis(true,true,true); } break; @@ -1364,17 +1420,18 @@ void Commands::processGCode(GCode *com) // similar to comment above, this will get a different answer from any different starting point // so it is unclear how this is helpful. It must start at a well defined point. Printer::deltaMoveToTopEndstops(Printer::homingFeedrate[Z_AXIS]); - int32_t offx = HOME_DISTANCE_STEPS-Printer::stepsRemainingAtXHit; - int32_t offy = HOME_DISTANCE_STEPS-Printer::stepsRemainingAtYHit; - int32_t offz = HOME_DISTANCE_STEPS-Printer::stepsRemainingAtZHit; + int32_t offx = HOME_DISTANCE_STEPS - Printer::stepsRemainingAtXHit; + int32_t offy = HOME_DISTANCE_STEPS - Printer::stepsRemainingAtYHit; + int32_t offz = HOME_DISTANCE_STEPS - Printer::stepsRemainingAtZHit; Com::printFLN(Com::tTower1,offx); Com::printFLN(Com::tTower2,offy); Com::printFLN(Com::tTower3,offz); Printer::setAutolevelActive(oldAuto); + PrintLine::moveRelativeDistanceInSteps(0, 0, Printer::axisStepsPerMM[Z_AXIS] * -ENDSTOP_Z_BACK_MOVE, 0, Printer::homingFeedrate[Z_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, false); Printer::homeAxis(true,true,true); } break; - case 134: // G134 + case 135: // G135 Com::printF(PSTR("CompDelta:"),Printer::currentDeltaPositionSteps[A_TOWER]); Com::printF(Com::tComma,Printer::currentDeltaPositionSteps[B_TOWER]); Com::printFLN(Com::tComma,Printer::currentDeltaPositionSteps[C_TOWER]); @@ -1389,6 +1446,31 @@ void Commands::processGCode(GCode *com) break; #endif // DRIVE_SYSTEM +#if FEATURE_Z_PROBE + case 134: // - G134 Px Sx Zx - Calibrate nozzle height difference (need z probe in nozzle!) Px = reference extruder, Sx = only measure extrude x against reference, Zx = add to measured z distance for Sx for correction. + { + float z = com->hasZ() ? com->Z : 0; + int p = com->hasP() ? com->P : 0; + int s = com->hasS() ? com->S : -1; + extruder[p].zOffset = 0; + Extruder::selectExtruderById(p); + float refHeight = Printer::runZProbe(true,false,true); + for(int i = 0;i < NUM_EXTRUDER;i++) { + if(i == p) continue; + if(s >= 0 && i != s) continue; + extruder[i].zOffset = 0; + Extruder::selectExtruderById(i); + float height = Printer::runZProbe(false,false); + extruder[i].zOffset = (height - refHeight + z)*Printer::axisStepsPerMM[Z_AXIS]; + } + Extruder::selectExtruderById(p); + Printer::runZProbe(false,true); +#if EEPROM_MODE != 0 + EEPROM::storeDataIntoEEPROM(0); +#endif + } + break; +#endif #if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0 case 201: commandG201(*com); @@ -1417,13 +1499,56 @@ void Commands::processGCode(GCode *com) */ void Commands::processMCode(GCode *com) { - uint32_t codenum; //throw away variable switch( com->M ) { - + case 3: // Spindle/laser on +#if defined(SUPPORT_LASER) && SUPPORT_LASER + if(Printer::mode == PRINTER_MODE_LASER) { + if(com->hasS()) + LaserDriver::intensity = constrain(com->S,0,255); + LaserDriver::laserOn = true; + Com::printFLN(PSTR("LaserOn:"),(int)LaserDriver::intensity); + } +#endif // defined +#if defined(SUPPORT_CNC) && SUPPORT_CNC + if(Printer::mode == PRINTER_MODE_CNC) { + waitUntilEndOfAllMoves(); + CNCDriver::spindleOnCW(com->hasS() ? com->S : 0); + } +#endif // defined + break; + case 4: // Spindle CCW +#if defined(SUPPORT_CNC) && SUPPORT_CNC + if(Printer::mode == PRINTER_MODE_CNC) { + waitUntilEndOfAllMoves(); + CNCDriver::spindleOnCCW(com->hasS() ? com->S : 0); + } +#endif // defined + break; + case 5: // Spindle/laser off +#if defined(SUPPORT_LASER) && SUPPORT_LASER + if(Printer::mode == PRINTER_MODE_LASER) { + LaserDriver::laserOn = false; + } +#endif // defined +#if defined(SUPPORT_CNC) && SUPPORT_CNC + if(Printer::mode == PRINTER_MODE_CNC) { + waitUntilEndOfAllMoves(); + CNCDriver::spindleOff(); + } +#endif // defined + break; #if SDSUPPORT case 20: // M20 - list SD card +#if JSON_OUTPUT + if (com->hasString() && com->text[1] == '2') { // " S2 P/folder" + if (com->text[3] == 'P') { + sd.lsJSON(com->text + 4); + } + } else sd.ls(); +#else sd.ls(); +#endif break; case 21: // M21 - init SD card sd.mount(); @@ -1473,6 +1598,13 @@ void Commands::processMCode(GCode *com) sd.makeDirectory(com->text); } break; +#endif +#if JSON_OUTPUT && SDSUPPORT + case 36: // M36 JSON File Info + if (com->hasString()) { + sd.JSONFileInfo(com->text); + } + break; #endif case 42: //M42 -Change pin status via gcode if (com->hasP()) @@ -1687,9 +1819,10 @@ void Commands::processMCode(GCode *com) previousMillisCmd = HAL::timeInMilliseconds(); break; case 190: // M190 - Wait bed for heater to reach target. + { #if HAVE_HEATED_BED if(Printer::debugDryrun()) break; - UI_STATUS_UPD(UI_TEXT_HEATING_BED); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_HEATING_BED_ID)); Commands::waitUntilEndOfAllMoves(); #if HAVE_HEATED_BED if (com->hasS()) Extruder::setHeatedBedTemperature(com->S,com->hasF() && com->F > 0); @@ -1697,6 +1830,7 @@ void Commands::processMCode(GCode *com) if(abs(heatedBedController.currentTemperatureC - heatedBedController.targetTemperatureC) < SKIP_M190_IF_WITHIN) break; #endif EVENT_WAITING_HEATER(-1); + uint32_t codenum; //throw away variable codenum = HAL::timeInMilliseconds(); while(heatedBedController.currentTemperatureC + 0.5 < heatedBedController.targetTemperatureC && heatedBedController.targetTemperatureC > 25.0) { @@ -1712,7 +1846,9 @@ void Commands::processMCode(GCode *com) #endif UI_CLEAR_STATUS; previousMillisCmd = HAL::timeInMilliseconds(); + } break; +#if NUM_TEMPERATURE_LOOPS > 0 case 116: // Wait for temperatures to reach target temperature for(fast8_t h = 0; h < NUM_TEMPERATURE_LOOPS; h++) { @@ -1721,42 +1857,48 @@ void Commands::processMCode(GCode *com) EVENT_HEATING_FINISHED(h < NUM_EXTRUDER ? h : -1); } break; - +#endif #if FAN_PIN>-1 && FEATURE_FAN_CONTROL case 106: // M106 Fan On if(!(Printer::flag2 & PRINTER_FLAG2_IGNORE_M106_COMMAND)) { - setFanSpeed(com->hasS() ? com->S : 255, com->hasP()); + if(com->hasP() && com->P == 1) + setFan2Speed(com->hasS() ? com->S : 255); + else + setFanSpeed(com->hasS() ? com->S : 255); } break; case 107: // M107 Fan Off - setFanSpeed(0, com->hasP()); + if(com->hasP() && com->P == 1) + setFan2Speed(0); + else + setFanSpeed(0); break; #endif case 111: // M111 enable/disable run time debug flags - if(com->hasS()) Printer::debugLevel = com->S; + if(com->hasS()) Printer::setDebugLevel(static_cast(com->S)); if(com->hasP()) { - if (com->P > 0) Printer::debugLevel |= com->P; - else Printer::debugLevel &= ~(-com->P); + if (com->P > 0) Printer::debugSet(static_cast(com->P)); + else Printer::debugReset(static_cast(-com->P)); } if(Printer::debugDryrun()) // simulate movements without printing { - Extruder::setTemperatureForExtruder(0, 0); -#if NUM_EXTRUDER>1 +#if NUM_EXTRUDER > 1 for(uint8_t i = 0; i < NUM_EXTRUDER; i++) Extruder::setTemperatureForExtruder(0, i); #else Extruder::setTemperatureForExtruder(0, 0); #endif -#if HEATED_BED_TYPE!=0 - target_bed_raw = 0; +#if HAVE_HEATED_BED != 0 + Extruder::setHeatedBedTemperature(0,false); #endif } break; case 115: // M115 Com::printFLN(Com::tFirmware); reportPrinterUsage(); + Printer::reportPrinterMode(); break; case 114: // M114 printCurrentPosition(PSTR("M114 ")); @@ -1783,6 +1925,7 @@ void Commands::processMCode(GCode *com) case 163: // M163 S P - Set weight for this mixing extruder drive if(com->hasS() && com->hasP() && com->S < NUM_EXTRUDER && com->S >= 0) Extruder::setMixingWeight(com->S, com->P); + Extruder::recomputeMixingExtruderSteps(); break; case 164: /// M164 S P<0 = dont store eeprom,1 = store to eeprom> - Store weights as virtual extruder S if(!com->hasS() || com->S < 0 || com->S >= VIRTUAL_EXTRUDER) break; // ignore illigal values @@ -1847,8 +1990,8 @@ void Commands::processMCode(GCode *com) TemperatureController *temp = &Extruder::current->tempControl; if(com->hasS()) { - if(com->S<0) break; - if(com->SS].tempControl; + if(com->S < 0) break; + if(com->S < NUM_EXTRUDER) temp = &extruder[com->S].tempControl; #if HAVE_HEATED_BED else temp = &heatedBedController; #else @@ -1894,6 +2037,22 @@ void Commands::processMCode(GCode *com) case 221: // M221 S changeFlowrateMultiply(com->getS(100)); break; + case 228: // M228 P S - Wait for pin getting state S + if(!com->hasS() || !com->hasP()) + break; + { + bool comp = com->S; + if(com->hasX()) { + if(com->X == 0) + HAL::pinMode(com->S,INPUT); + else + HAL::pinMode(com->S,INPUT_PULLUP); + } + do { + Commands::checkForPeriodicalActions(true); + } while(HAL::digitalRead(com->P) != comp); + } + break; #if USE_ADVANCE case 223: // M223 Extruder interrupt test if(com->hasS()) @@ -1909,10 +2068,10 @@ void Commands::processMCode(GCode *com) #endif Com::printFLN(Com::tCommaSpeedEqual,maxadvspeed); #if ENABLE_QUADRATIC_ADVANCE - maxadv=0; + maxadv = 0; #endif - maxadv2=0; - maxadvspeed=0; + maxadv2 = 0; + maxadvspeed = 0; break; #endif #if USE_ADVANCE @@ -2088,6 +2247,38 @@ void Commands::processMCode(GCode *com) case 402: // M402 Go to stored position Printer::GoToMemoryPosition(com->hasX(),com->hasY(),com->hasZ(),com->hasE(),(com->hasF() ? com->F : Printer::feedrate)); break; +#if JSON_OUTPUT + case 408: + Printer::showJSONStatus(com->hasS() ? static_cast(com->S) : 0); + break; +#endif + case 450: + Printer::reportPrinterMode(); + break; + case 451: + Printer::mode = PRINTER_MODE_FFF; + Printer::reportPrinterMode(); + break; + case 452: +#if defined(SUPPORT_LASER) && SUPPORT_LASER + Printer::mode = PRINTER_MODE_LASER; +#endif + Printer::reportPrinterMode(); + break; + case 453: +#if defined(SUPPORT_CNC) && SUPPORT_CNC + Printer::mode = PRINTER_MODE_CNC; +#endif + Printer::reportPrinterMode(); + break; +#if FAN_THERMO_PIN > -1 + case 460: // M460 X Y : Set temperature range for thermo controlled fan + if(com->hasX()) + Printer::thermoMinTemp = com->X; + if(com->hasY()) + Printer::thermoMaxTemp = com->Y; + break; +#endif case 500: // M500 { #if EEPROM_MODE != 0 @@ -2251,6 +2442,31 @@ void Commands::processMCode(GCode *com) dacCommitEeprom(); #endif break; +#if 0 && UI_DISPLAY_TYPE != NO_DISPLAY + // some debuggingcommands normally disabled + case 888: + Com::printFLN(PSTR("Selected language:"),(int)Com::selectedLanguage); + Com::printF(PSTR("Translation:")); + Com::printFLN(Com::translatedF(0)); + break; + case 889: + uid.showLanguageSelectionWizard(); + break; + case 890: + { + if(com->hasX() && com->hasY()) { + float c = Printer::bendingCorrectionAt(com->X,com->Y); + Com::printF(PSTR("Bending at ("),com->X); + Com::printF(PSTR(","),com->Y); + Com::printFLN(PSTR(") = "),c); + } + } + break; + case 891: + if(com->hasS()) + EEPROM::setVersion(com->S); + break; +#endif default: if(!EVENT_UNHANDLED_M_CODE(com) && Printer::debugErrors()) { @@ -2291,6 +2507,14 @@ void Commands::executeGCode(GCode *com) com->printCommand(); } } +#ifdef DEBUG_DRYRUN_ERROR + if(Printer::debugDryrun()) { + Com::printFLN("Dryrun was enabled"); + com->printCommand(); + Printer::debugReset(8); + } +#endif + } void Commands::emergencyStop() @@ -2303,7 +2527,7 @@ void Commands::emergencyStop() Extruder::manageTemperatures(); for(uint8_t i = 0; i < NUM_EXTRUDER + 3; i++) pwm_pos[i] = 0; -#if EXT0_HEATER_PIN > -1 +#if EXT0_HEATER_PIN > -1 && NUM_EXTRUDER > 0 WRITE(EXT0_HEATER_PIN,HEATER_PINS_INVERTED); #endif #if defined(EXT1_HEATER_PIN) && EXT1_HEATER_PIN > -1 && NUM_EXTRUDER > 1 @@ -2324,10 +2548,10 @@ void Commands::emergencyStop() #if FAN_PIN > -1 && FEATURE_FAN_CONTROL WRITE(FAN_PIN, 0); #endif -#if HEATED_BED_HEATER_PIN > -1 +#if HAVE_HEATED_BED && HEATED_BED_HEATER_PIN > -1 WRITE(HEATED_BED_HEATER_PIN, HEATER_PINS_INVERTED); #endif - UI_STATUS_UPD(UI_TEXT_KILLED); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_KILLED_ID)); HAL::delayMilliseconds(200); InterruptProtectedBlock noInts; while(1) {} @@ -2349,5 +2573,3 @@ void Commands::writeLowestFreeRAM() Com::printFLN(Com::tFreeRAM, lowestRAMValue); } } - - diff --git a/Repetier/Commands.h b/Repetier/Commands.h index d99c675..61dad0b 100644 --- a/Repetier/Commands.h +++ b/Repetier/Commands.h @@ -37,7 +37,8 @@ public: static void waitUntilEndOfAllBuffers(); static void printCurrentPosition(FSTRINGPARAM(s)); static void printTemperatures(bool showRaw = false); - static void setFanSpeed(int speed,bool wait); /// Set fan speed 0..255 + static void setFanSpeed(int speed, bool immediately = false); /// Set fan speed 0..255 + static void setFan2Speed(int speed); /// Set fan speed 0..255 static void changeFeedrateMultiply(int factorInPercent); static void changeFlowrateMultiply(int factorInPercent); static void reportPrinterUsage(); @@ -50,5 +51,3 @@ private: }; #endif // COMMANDS_H_INCLUDED - - diff --git a/Repetier/Communication.cpp b/Repetier/Communication.cpp index 126106f..4862d1d 100644 --- a/Repetier/Communication.cpp +++ b/Repetier/Communication.cpp @@ -21,15 +21,23 @@ #include "Repetier.h" -#if DRIVE_SYSTEM == DELTA -FSTRINGVALUE(Com::tFirmware,"FIRMWARE_NAME:Repetier_" REPETIER_VERSION " FIRMWARE_URL:https://github.com/repetier/Repetier-Firmware/ PROTOCOL_VERSION:1.0 MACHINE_TYPE:Delta EXTRUDER_COUNT:" XSTR(NUM_EXTRUDER) " REPETIER_PROTOCOL:3") +#if UI_DISPLAY_TYPE != NO_DISPLAY +uint8_t Com::selectedLanguage; +#endif + +#ifndef MACHINE_TYPE +#if DRIVE_SYSTEM == DELTA +#define MACHINE_TYPE "Delta" +#elif DRIVE_SYSTEM == CARTESIAN +#define MACHINE_TYPE "Mendel" #else -#if DRIVE_SYSTEM == CARTESIAN -FSTRINGVALUE(Com::tFirmware,"FIRMWARE_NAME:Repetier_" REPETIER_VERSION " FIRMWARE_URL:https://github.com/repetier/Repetier-Firmware/ PROTOCOL_VERSION:1.0 MACHINE_TYPE:Mendel EXTRUDER_COUNT:" XSTR(NUM_EXTRUDER) " REPETIER_PROTOCOL:3") -#else -FSTRINGVALUE(Com::tFirmware,"FIRMWARE_NAME:Repetier_" REPETIER_VERSION " FIRMWARE_URL:https://github.com/repetier/Repetier-Firmware/ PROTOCOL_VERSION:1.0 MACHINE_TYPE:Core_XY EXTRUDER_COUNT:" XSTR(NUM_EXTRUDER) " REPETIER_PROTOCOL:3") -#endif -#endif +#define MACHINE_TYPE "Core_XY" +#endif +#endif +#ifndef FIRMWARE_URL +#define FIRMWARE_URL "https://github.com/repetier/Repetier-Firmware/" +#endif // FIRMWARE_URL +FSTRINGVALUE(Com::tFirmware,"FIRMWARE_NAME:Repetier_" REPETIER_VERSION " FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:1.0 MACHINE_TYPE:" MACHINE_TYPE " EXTRUDER_COUNT:" XSTR(NUM_EXTRUDER) " REPETIER_PROTOCOL:3") FSTRINGVALUE(Com::tDebug,"Debug:") FSTRINGVALUE(Com::tOk,"ok") FSTRINGVALUE(Com::tNewline,"\r\n") @@ -83,9 +91,23 @@ FSTRINGVALUE(Com::tSpaceRaw," RAW") FSTRINGVALUE(Com::tColon,":") FSTRINGVALUE(Com::tSlash,"/") FSTRINGVALUE(Com::tSpaceSlash," /") +#if JSON_OUTPUT +FSTRINGVALUE(Com::tJSONDir,"{\"dir\":\"") +FSTRINGVALUE(Com::tJSONFiles,"\",\"files\":[") +FSTRINGVALUE(Com::tJSONArrayEnd,"]}") +FSTRINGVALUE(Com::tJSONErrorStart,"{\"err\":\"") +FSTRINGVALUE(Com::tJSONErrorEnd,"\"}") +FSTRINGVALUE(Com::tJSONFileInfoStart, "{\"err\":0,\"size\":"); +FSTRINGVALUE(Com::tJSONFileInfoHeight, ",\"height\":"); +FSTRINGVALUE(Com::tJSONFileInfoLayerHeight, ",\"layerHeight\":"); +FSTRINGVALUE(Com::tJSONFileInfoFilament, ",\"filament\":["); +FSTRINGVALUE(Com::tJSONFileInfoGeneratedBy, "],\"generatedBy\":\""); +FSTRINGVALUE(Com::tJSONFileInfoName, ",\"fileName\":\""); +#endif // JSON_OUTPUT FSTRINGVALUE(Com::tSpeedMultiply,"SpeedMultiply:") FSTRINGVALUE(Com::tFlowMultiply,"FlowMultiply:") FSTRINGVALUE(Com::tFanspeed,"Fanspeed:") +FSTRINGVALUE(Com::tFan2speed,"Fanspeed2:") FSTRINGVALUE(Com::tPrintedFilament,"Printed filament:") FSTRINGVALUE(Com::tPrintingTime,"Printing time:") FSTRINGVALUE(Com::tSpacem,"m ") @@ -122,7 +144,6 @@ FSTRINGVALUE(Com::tEEPROMUpdated,"EEPROM updated") FSTRINGVALUE(Com::tLinearLColon,"linear L:") FSTRINGVALUE(Com::tQuadraticKColon," quadratic K:") -FSTRINGVALUE(Com::tExtruderJam, UI_TEXT_EXTRUDER_JAM) FSTRINGVALUE(Com::tFilamentSlipping,"Filament slipping") FSTRINGVALUE(Com::tPauseCommunication,"// action:pause") FSTRINGVALUE(Com::tContinueCommunication,"// action:resume") @@ -235,6 +256,7 @@ FSTRINGVALUE(Com::tWait,WAITING_IDENTIFIER) #if EEPROM_MODE == 0 FSTRINGVALUE(Com::tNoEEPROMSupport,"No EEPROM support compiled.\r\n") #else +FSTRINGVALUE(Com::tZProbeOffsetZ, "Coating thickness [mm]") #if FEATURE_Z_PROBE FSTRINGVALUE(Com::tZProbeHeight,"Z-probe height [mm]") FSTRINGVALUE(Com::tZProbeBedDitance,"Max. z-probe - bed dist. [mm]") @@ -242,12 +264,15 @@ FSTRINGVALUE(Com::tZProbeOffsetX,"Z-probe offset x [mm]") FSTRINGVALUE(Com::tZProbeOffsetY,"Z-probe offset y [mm]") FSTRINGVALUE(Com::tZProbeSpeed,"Z-probe speed [mm/s]") FSTRINGVALUE(Com::tZProbeSpeedXY,"Z-probe x-y-speed [mm/s]") -FSTRINGVALUE(Com::tZProbeX1,"Z-probe X1") -FSTRINGVALUE(Com::tZProbeY1,"Z-probe Y1") -FSTRINGVALUE(Com::tZProbeX2,"Z-probe X2") -FSTRINGVALUE(Com::tZProbeY2,"Z-probe Y2") -FSTRINGVALUE(Com::tZProbeX3,"Z-probe X3") -FSTRINGVALUE(Com::tZProbeY3,"Z-probe Y3") +FSTRINGVALUE(Com::tZProbeX1,"Z-probe X1 [mm]") +FSTRINGVALUE(Com::tZProbeY1,"Z-probe Y1 [mm]") +FSTRINGVALUE(Com::tZProbeX2,"Z-probe X2 [mm]") +FSTRINGVALUE(Com::tZProbeY2,"Z-probe Y2 [mm]") +FSTRINGVALUE(Com::tZProbeX3,"Z-probe X3 [mm]") +FSTRINGVALUE(Com::tZProbeY3,"Z-probe Y3 [mm]") +FSTRINGVALUE(Com::zZProbeBendingCorA,"Z-probe bending correction A [mm]") +FSTRINGVALUE(Com::zZProbeBendingCorB,"Z-probe bending correction B [mm]") +FSTRINGVALUE(Com::zZProbeBendingCorC,"Z-probe bending correction C [mm]") #endif #if FEATURE_AXISCOMP FSTRINGVALUE(Com::tAxisCompTanXY,"tanXY Axis Compensation") @@ -267,6 +292,7 @@ FSTRINGVALUE(Com::tEPR1,"EPR:1 ") FSTRINGVALUE(Com::tEPR2,"EPR:2 ") FSTRINGVALUE(Com::tEPR3,"EPR:3 ") FSTRINGVALUE(Com::tEPRBaudrate,"Baudrate") +FSTRINGVALUE(Com::tLanguage,"Language") FSTRINGVALUE(Com::tEPRFilamentPrinted,"Filament printed [m]") FSTRINGVALUE(Com::tEPRPrinterActive,"Printer active [s]") FSTRINGVALUE(Com::tEPRMaxInactiveTime,"Max. inactive time [ms,0=off]") @@ -281,6 +307,7 @@ FSTRINGVALUE(Com::tEPRXBacklash,"X backlash [mm]") FSTRINGVALUE(Com::tEPRYBacklash,"Y backlash [mm]") FSTRINGVALUE(Com::tEPRZBacklash,"Z backlash [mm]") FSTRINGVALUE(Com::tEPRMaxJerk,"Max. jerk [mm/s]") +FSTRINGVALUE(Com::tEPRAccelerationFactorAtTop,"Acceleration factor at top [%,100=like bottom]") #if DRIVE_SYSTEM==DELTA FSTRINGVALUE(Com::tEPRZAcceleration,"Acceleration [mm/s^2]") FSTRINGVALUE(Com::tEPRZTravelAcceleration,"Travel acceleration [mm/s^2]") @@ -357,8 +384,8 @@ FSTRINGVALUE(Com::tEPRAdvanceL,"advance L [0=off]") #endif #if SDSUPPORT -FSTRINGVALUE(Com::tSDRemoved,UI_TEXT_SD_REMOVED) -FSTRINGVALUE(Com::tSDInserted,UI_TEXT_SD_INSERTED) +//FSTRINGVALUE(Com::tSDRemoved,UI_TEXT_SD_REMOVED) +//FSTRINGVALUE(Com::tSDInserted,UI_TEXT_SD_INSERTED) FSTRINGVALUE(Com::tSDInitFail,"SD init fail") FSTRINGVALUE(Com::tErrorWritingToFile,"error writing to file") FSTRINGVALUE(Com::tBeginFileList,"Begin file list") @@ -401,6 +428,12 @@ FSTRINGVALUE(Com::tExtrDot,"Extr.") FSTRINGVALUE(Com::tMCPEpromSettings, "MCP4728 DAC EEPROM Settings:") FSTRINGVALUE(Com::tMCPCurrentSettings,"MCP4728 DAC Current Settings:") #endif +FSTRINGVALUE(Com::tPrinterModeFFF,"PrinterMode:FFF") +FSTRINGVALUE(Com::tPrinterModeLaser,"PrinterMode:Laser") +FSTRINGVALUE(Com::tPrinterModeCNC,"PrinterMode:CNC") +#ifdef STARTUP_GCODE +FSTRINGVALUE(Com::tStartupGCode,STARTUP_GCODE) +#endif void Com::config(FSTRINGPARAM(text)) { printF(tConfig); @@ -590,4 +623,3 @@ void Com::printFloat(float number, uint8_t digits) } } - diff --git a/Repetier/Communication.h b/Repetier/Communication.h index 51d078c..07fc6fe 100644 --- a/Repetier/Communication.h +++ b/Repetier/Communication.h @@ -66,7 +66,20 @@ FSTRINGVAR(tUnknownCommand) FSTRINGVAR(tFreeRAM) FSTRINGVAR(tXColon) FSTRINGVAR(tSlash) -FSTRINGVAR(tSpaceSlash) +FSTRINGVAR(tSpaceSlash) +#if JSON_OUTPUT +FSTRINGVAR(tJSONDir) +FSTRINGVAR(tJSONFiles) +FSTRINGVAR(tJSONArrayEnd) +FSTRINGVAR(tJSONErrorStart) +FSTRINGVAR(tJSONErrorEnd) +FSTRINGVAR(tJSONFileInfoStart) +FSTRINGVAR(tJSONFileInfoHeight) +FSTRINGVAR(tJSONFileInfoLayerHeight) +FSTRINGVAR(tJSONFileInfoFilament) +FSTRINGVAR(tJSONFileInfoGeneratedBy) +FSTRINGVAR(tJSONFileInfoName) +#endif FSTRINGVAR(tSpaceXColon) FSTRINGVAR(tSpaceYColon) FSTRINGVAR(tSpaceZColon) @@ -82,6 +95,7 @@ FSTRINGVAR(tColon) FSTRINGVAR(tSpeedMultiply) FSTRINGVAR(tFlowMultiply) FSTRINGVAR(tFanspeed) +FSTRINGVAR(tFan2speed) FSTRINGVAR(tPrintedFilament) FSTRINGVAR(tPrintingTime) FSTRINGVAR(tSpacem) @@ -117,7 +131,6 @@ FSTRINGVAR(tCommaSpeedEqual) FSTRINGVAR(tLinearLColon) FSTRINGVAR(tQuadraticKColon) FSTRINGVAR(tEEPROMUpdated) -FSTRINGVAR(tExtruderJam) FSTRINGVAR(tFilamentSlipping) FSTRINGVAR(tPauseCommunication) FSTRINGVAR(tContinueCommunication) @@ -236,6 +249,7 @@ FSTRINGVAR(tWait) #if EEPROM_MODE==0 FSTRINGVAR(tNoEEPROMSupport) #else +FSTRINGVAR(tZProbeOffsetZ) #if FEATURE_Z_PROBE FSTRINGVAR(tZProbeHeight) FSTRINGVAR(tZProbeOffsetX) @@ -248,6 +262,9 @@ FSTRINGVAR(tZProbeX2) FSTRINGVAR(tZProbeY2) FSTRINGVAR(tZProbeX3) FSTRINGVAR(tZProbeY3) +FSTRINGVAR(zZProbeBendingCorA) +FSTRINGVAR(zZProbeBendingCorB) +FSTRINGVAR(zZProbeBendingCorC) #endif #if FEATURE_AUTOLEVEL FSTRINGVAR(tAutolevelActive) @@ -265,6 +282,7 @@ FSTRINGVAR(tEPR0) FSTRINGVAR(tEPR1) FSTRINGVAR(tEPR2) FSTRINGVAR(tEPR3) +FSTRINGVAR(tLanguage) FSTRINGVAR(tEPRBaudrate) FSTRINGVAR(tEPRFilamentPrinted) FSTRINGVAR(tEPRPrinterActive) @@ -282,10 +300,11 @@ FSTRINGVAR(tEPRYBacklash) FSTRINGVAR(tEPRZBacklash) FSTRINGVAR(tEPRZAcceleration) FSTRINGVAR(tEPRZTravelAcceleration) +FSTRINGVAR(tEPRAccelerationFactorAtTop) FSTRINGVAR(tEPRZStepsPerMM) FSTRINGVAR(tEPRZMaxFeedrate) FSTRINGVAR(tEPRZHomingFeedrate) -#if DRIVE_SYSTEM!=DELTA +#if DRIVE_SYSTEM != DELTA FSTRINGVAR(tEPRMaxZJerk) FSTRINGVAR(tEPRXStepsPerMM) FSTRINGVAR(tEPRYStepsPerMM) @@ -342,8 +361,8 @@ FSTRINGVAR(tEPRAdvanceK) FSTRINGVAR(tEPRAdvanceL) #endif #if SDSUPPORT -FSTRINGVAR(tSDRemoved) -FSTRINGVAR(tSDInserted) +//FSTRINGVAR(tSDRemoved) +//FSTRINGVAR(tSDInserted) FSTRINGVAR(tSDInitFail) FSTRINGVAR(tErrorWritingToFile) FSTRINGVAR(tBeginFileList) @@ -386,6 +405,12 @@ FSTRINGVAR(tExtrDot) FSTRINGVAR(tMCPEpromSettings) FSTRINGVAR(tMCPCurrentSettings) #endif +FSTRINGVAR(tPrinterModeFFF) +FSTRINGVAR(tPrinterModeLaser) +FSTRINGVAR(tPrinterModeCNC) +#ifdef STARTUP_GCODE +FSTRINGVAR(tStartupGCode) +#endif static void config(FSTRINGPARAM(text)); static void config(FSTRINGPARAM(text),int value); @@ -422,6 +447,11 @@ static inline void print(char c) {HAL::serialWriteByte(c);} static void printFloat(float number, uint8_t digits); static inline void print(float number) {printFloat(number, 6);} static inline void println() {HAL::serialWriteByte('\r');HAL::serialWriteByte('\n');} +#if UI_DISPLAY_TYPE != NO_DISPLAY +static const char* translatedF(int textId); +static void selectLanguage(fast8_t lang); +static uint8_t selectedLanguage; +#endif protected: private: }; @@ -444,5 +474,3 @@ static inline void println() {HAL::serialWriteByte('\r');HAL::serialWriteByte('\ #endif #endif // COMMUNICATION_H - - diff --git a/Repetier/Configuration.h b/Repetier/Configuration.h index fea9705..c23fa1d 100644 --- a/Repetier/Configuration.h +++ b/Repetier/Configuration.h @@ -43,8 +43,17 @@ // ################## EDIT THESE SETTINGS MANUALLY ################ // ################ END MANUAL SETTINGS ########################## +#undef FAN_PIN #define FAN_PIN -1 +#undef FAN_BOARD_PIN #define FAN_BOARD_PIN -1 +#define FAN_THERMO_PIN -1 +#define FAN_THERMO_MIN_PWM 128 +#define FAN_THERMO_MAX_PWM 255 +#define FAN_THERMO_MIN_TEMP 45 +#define FAN_THERMO_MAX_TEMP 60 +#define FAN_THERMO_THERMISTOR_PIN -1 +#define FAN_THERMO_THERMISTOR_TYPE 1 //#define EXTERNALSERIAL use Arduino serial library instead of build in. Requires more ram, has only 63 byte input buffer. // Uncomment the following line if you are using arduino compatible firmware made for Arduino version earlier then 1.0 @@ -77,7 +86,7 @@ #define EXT0_STEP_PIN ORIG_E0_STEP_PIN #define EXT0_DIR_PIN ORIG_E0_DIR_PIN #define EXT0_INVERSE 0 -#define EXT0_ENABLE_PIN E0_ENABLE_PIN +#define EXT0_ENABLE_PIN ORIG_E0_ENABLE_PIN #define EXT0_ENABLE_ON 0 #define EXT0_MAX_FEEDRATE 50 #define EXT0_MAX_START_FEEDRATE 20 @@ -112,7 +121,7 @@ #define EXT1_STEP_PIN ORIG_E1_STEP_PIN #define EXT1_DIR_PIN ORIG_E1_DIR_PIN #define EXT1_INVERSE 0 -#define EXT1_ENABLE_PIN E1_ENABLE_PIN +#define EXT1_ENABLE_PIN ORIG_E1_ENABLE_PIN #define EXT1_ENABLE_ON 0 #define EXT1_MAX_FEEDRATE 50 #define EXT1_MAX_START_FEEDRATE 20 @@ -198,11 +207,60 @@ #define MIN_DEFECT_TEMPERATURE -10 #define MAX_DEFECT_TEMPERATURE 290 +// ########################################################################################## +// ## Laser configuration ## +// ########################################################################################## + +/* +If the firmware is in laser mode, it can control a laser output to cut or engrave materials. +Please use this feature only if you know about safety and required protection. Lasers are +dangerous and can hurt or make you blind!!! + +The default laser driver only supports laser on and off. Here you control the eíntensity with +your feedrate. For exchangeable diode lasers this is normally enough. If you need more control +you can set the intensity in a range 0-255 with a custom extension to the driver. See driver.h +and comments on how to extend the functions non invasive with our event system. + +If you have a laser - powder system you will like your E override. If moves contain a +increasing extruder position it will laser that move. With this trick you can +use existing fdm slicers to laser the output. Laser width is extrusion width. + +Other tools may use M3 and M5 to enable/disable laser. Here G1/G2/G3 moves have laser enabled +and G0 moves have it disables. + +In any case, laser only enables while moving. At the end of a move it gets +automatically disabled. +*/ + +#define SUPPORT_LASER 0 +#define LASER_PIN -1 +#define LASER_ON_HIGH 1 + +// ## CNC configuration ## + +/* +If the firmware is in CNC mode, it can control a mill with M3/M4/M5. It works +similar to laser mode, but mill keeps enabled during G0 moves and it allows +setting rpm (only with event extension that supports this) and milling direction. +It also can add a delay to wait for spindle to run on full speed. +*/ + +#define SUPPORT_CNC 0 +#define CNC_WAIT_ON_ENABLE 300 +#define CNC_WAIT_ON_DISABLE 0 +#define CNC_ENABLE_PIN -1 +#define CNC_ENABLE_WITH 1 +#define CNC_DIRECTION_PIN -1 +#define CNC_DIRECTION_CW 1 + + +#define DEFAULT_PRINTER_MODE 0 + // ################ Endstop configuration ##################### #define ENDSTOP_PULLUP_X_MIN true -#define ENDSTOP_X_MIN_INVERTING true -#define MIN_HARDWARE_ENDSTOP_X true +#define ENDSTOP_X_MIN_INVERTING false +#define MIN_HARDWARE_ENDSTOP_X false #define ENDSTOP_PULLUP_Y_MIN true #define ENDSTOP_Y_MIN_INVERTING true #define MIN_HARDWARE_ENDSTOP_Y true @@ -210,8 +268,8 @@ #define ENDSTOP_Z_MIN_INVERTING false #define MIN_HARDWARE_ENDSTOP_Z false #define ENDSTOP_PULLUP_X_MAX true -#define ENDSTOP_X_MAX_INVERTING false -#define MAX_HARDWARE_ENDSTOP_X false +#define ENDSTOP_X_MAX_INVERTING true +#define MAX_HARDWARE_ENDSTOP_X true #define ENDSTOP_PULLUP_Y_MAX true #define ENDSTOP_Y_MAX_INVERTING false #define MAX_HARDWARE_ENDSTOP_Y false @@ -220,10 +278,10 @@ #define MAX_HARDWARE_ENDSTOP_Z true #define max_software_endstop_r true -#define min_software_endstop_x false +#define min_software_endstop_x true #define min_software_endstop_y false #define min_software_endstop_z true -#define max_software_endstop_x true +#define max_software_endstop_x false #define max_software_endstop_y true #define max_software_endstop_z false #define ENDSTOP_X_BACK_MOVE 5 @@ -232,7 +290,7 @@ #define ENDSTOP_X_RETEST_REDUCTION_FACTOR 3 #define ENDSTOP_Y_RETEST_REDUCTION_FACTOR 3 #define ENDSTOP_Z_RETEST_REDUCTION_FACTOR 3 -#define ENDSTOP_X_BACK_ON_HOME 1 +#define ENDSTOP_X_BACK_ON_HOME 10 #define ENDSTOP_Y_BACK_ON_HOME 1 #define ENDSTOP_Z_BACK_ON_HOME 0 #define ALWAYS_CHECK_ENDSTOPS 0 @@ -249,23 +307,27 @@ #define INVERT_X_DIR 0 #define INVERT_Y_DIR 0 #define INVERT_Z_DIR 0 -#define X_HOME_DIR -1 +#define X_HOME_DIR 1 #define Y_HOME_DIR -1 #define Z_HOME_DIR 1 -#define X_MAX_LENGTH 200 -#define Y_MAX_LENGTH 180 -#define Z_MAX_LENGTH 135 +#define X_MAX_LENGTH 155 +#define Y_MAX_LENGTH 155 +#define Z_MAX_LENGTH 145 #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 #define DISTORTION_CORRECTION 0 -#define DISTORTION_CORRECTION_POINTS 5 +#define DISTORTION_CORRECTION_POINTS 3 #define DISTORTION_CORRECTION_R 100 -#define DISTORTION_PERMANENT 1 +#define DISTORTION_PERMANENT 0 #define DISTORTION_UPDATE_FREQUENCY 15 #define DISTORTION_START_DEGRADE 0.5 #define DISTORTION_END_HEIGHT 1 #define DISTORTION_EXTRAPOLATE_CORNERS 0 +#define DISTORTION_XMIN 0 +#define DISTORTION_YMIN 0 +#define DISTORTION_XMAX 155 +#define DISTORTION_YMAX 155 // ########################################################################################## // ## Movement settings ## @@ -312,6 +374,8 @@ #define MAX_TRAVEL_ACCELERATION_UNITS_PER_SQ_SECOND_X 1000 #define MAX_TRAVEL_ACCELERATION_UNITS_PER_SQ_SECOND_Y 1000 #define MAX_TRAVEL_ACCELERATION_UNITS_PER_SQ_SECOND_Z 500 +#define INTERPOLATE_ACCELERATION_WITH_Z 0 +#define ACCELERATION_FACTOR_TOP 100 #define MAX_JERK 20 #define MAX_ZJERK 0.3 #define PRINTLINE_CACHE_SIZE 16 @@ -320,15 +384,19 @@ #define FEATURE_TWO_XSTEPPER 0 #define X2_STEP_PIN ORIG_E1_STEP_PIN #define X2_DIR_PIN ORIG_E1_DIR_PIN -#define X2_ENABLE_PIN E1_ENABLE_PIN +#define X2_ENABLE_PIN ORIG_E1_ENABLE_PIN #define FEATURE_TWO_YSTEPPER 0 #define Y2_STEP_PIN ORIG_E1_STEP_PIN #define Y2_DIR_PIN ORIG_E1_DIR_PIN -#define Y2_ENABLE_PIN E1_ENABLE_PIN +#define Y2_ENABLE_PIN ORIG_E1_ENABLE_PIN #define FEATURE_TWO_ZSTEPPER 0 #define Z2_STEP_PIN ORIG_E1_STEP_PIN #define Z2_DIR_PIN ORIG_E1_DIR_PIN -#define Z2_ENABLE_PIN E1_ENABLE_PIN +#define Z2_ENABLE_PIN ORIG_E1_ENABLE_PIN +#define FEATURE_THREE_ZSTEPPER 0 +#define Z3_STEP_PIN ORIG_E2_STEP_PIN +#define Z3_DIR_PIN ORIG_E2_DIR_PIN +#define Z3_ENABLE_PIN ORIG_E2_ENABLE_PIN #define FEATURE_DITTO_PRINTING 0 #define USE_ADVANCE 0 #define ENABLE_QUADRATIC_ADVANCE 0 @@ -343,8 +411,10 @@ #define ACK_WITH_LINENUMBER 1 #define WAITING_IDENTIFIER "wait" #define ECHO_ON_EXECUTE 1 -#define EEPROM_MODE 0 +#define EEPROM_MODE 2 +#undef PS_ON_PIN #define PS_ON_PIN ORIG_PS_ON_PIN +#define JSON_OUTPUT 0 /* ======== Servos ======= Control the servos with @@ -379,20 +449,33 @@ WARNING: Servos can draw a considerable amount of current. Make sure your system #define Z_PROBE_X_OFFSET 6.4 #define Z_PROBE_Y_OFFSET 0 #define Z_PROBE_WAIT_BEFORE_TEST 0 -#define Z_PROBE_SPEED 8 +#define Z_PROBE_SPEED 100 #define Z_PROBE_XY_SPEED 150 #define Z_PROBE_SWITCHING_DISTANCE 1 #define Z_PROBE_REPETITIONS 1 -#define Z_PROBE_HEIGHT 7.4 +#define Z_PROBE_HEIGHT 6.9 #define Z_PROBE_START_SCRIPT "" #define Z_PROBE_FINISHED_SCRIPT "" #define FEATURE_AUTOLEVEL 1 -#define Z_PROBE_X1 20 -#define Z_PROBE_Y1 20 -#define Z_PROBE_X2 160 -#define Z_PROBE_Y2 20 -#define Z_PROBE_X3 100 -#define Z_PROBE_Y3 160 +#define Z_PROBE_X1 5 +#define Z_PROBE_Y1 5 +#define Z_PROBE_X2 150 +#define Z_PROBE_Y2 5 +#define Z_PROBE_X3 150 +#define Z_PROBE_Y3 150 +#define BED_LEVELING_METHOD 0 +#define BED_CORRECTION_METHOD 0 +#define BED_LEVELING_GRID_SIZE 5 +#define BED_LEVELING_REPETITIONS 5 +#define BED_MOTOR_1_X 0 +#define BED_MOTOR_1_Y 0 +#define BED_MOTOR_2_X 200 +#define BED_MOTOR_2_Y 0 +#define BED_MOTOR_3_X 100 +#define BED_MOTOR_3_Y 200 +#define BENDING_CORRECTION_A 0 +#define BENDING_CORRECTION_B 0 +#define BENDING_CORRECTION_C 0 #define FEATURE_AXISCOMP 0 #define AXISCOMP_TANXY 0 #define AXISCOMP_TANYZ 0 @@ -400,6 +483,7 @@ WARNING: Servos can draw a considerable amount of current. Make sure your system #ifndef SDSUPPORT // Some boards have sd support on board. These define the values already in pins.h #define SDSUPPORT 0 +#undef SDCARDDETECT #define SDCARDDETECT -1 #define SDCARDDETECTINVERTED 0 #endif @@ -410,8 +494,19 @@ WARNING: Servos can draw a considerable amount of current. Make sure your system #define FEATURE_MEMORY_POSITION 0 #define FEATURE_CHECKSUM_FORCED 0 #define FEATURE_FAN_CONTROL 0 +#define FEATURE_FAN2_CONTROL 0 #define FEATURE_CONTROLLER 0 -#define UI_LANGUAGE 0 +#define LANGUAGE_EN_ACTIVE 1 +#define LANGUAGE_DE_ACTIVE 1 +#define LANGUAGE_NL_ACTIVE 1 +#define LANGUAGE_PT_ACTIVE 1 +#define LANGUAGE_IT_ACTIVE 1 +#define LANGUAGE_ES_ACTIVE 1 +#define LANGUAGE_SE_ACTIVE 1 +#define LANGUAGE_FR_ACTIVE 1 +#define LANGUAGE_CZ_ACTIVE 1 +#define LANGUAGE_PL_ACTIVE 1 +#define LANGUAGE_TR_ACTIVE 1 #define UI_PRINTER_NAME "RepRap" #define UI_PRINTER_COMPANY "Home made" #define UI_PAGES_DURATION 4000 @@ -471,7 +566,7 @@ Values must be in range 1..255 "zStepsPerMM": 200, "xInvert": 0, "xInvertEnable": 0, - "eepromMode": 0, + "eepromMode": 2, "yInvert": 0, "yInvertEnable": 0, "zInvert": 0, @@ -515,7 +610,7 @@ Values must be in range 1..255 "name": "Extruder 0", "step": "ORIG_E0_STEP_PIN", "dir": "ORIG_E0_DIR_PIN", - "enable": "E0_ENABLE_PIN" + "enable": "ORIG_E0_ENABLE_PIN" }, "advanceBacklashSteps": 0, "decoupleTestPeriod": 12, @@ -560,7 +655,7 @@ Values must be in range 1..255 "name": "Extruder 1", "step": "ORIG_E1_STEP_PIN", "dir": "ORIG_E1_DIR_PIN", - "enable": "E1_ENABLE_PIN" + "enable": "ORIG_E1_ENABLE_PIN" }, "advanceBacklashSteps": 0, "decoupleTestPeriod": 12, @@ -570,10 +665,10 @@ Values must be in range 1..255 ], "uiLanguage": 0, "uiController": 0, - "xMinEndstop": 1, + "xMinEndstop": 0, "yMinEndstop": 1, "zMinEndstop": 0, - "xMaxEndstop": 0, + "xMaxEndstop": 1, "yMaxEndstop": 0, "zMaxEndstop": 1, "motherboard": 33, @@ -617,18 +712,18 @@ Values must be in range 1..255 "xMinPos": 0, "yMinPos": 0, "zMinPos": 0, - "xLength": 200, - "yLength": 180, - "zLength": 135, + "xLength": 155, + "yLength": 155, + "zLength": 145, "alwaysCheckEndstops": "0", "disableX": "0", "disableY": "0", "disableZ": "0", "disableE": "0", - "xHomeDir": "-1", + "xHomeDir": "1", "yHomeDir": "-1", "zHomeDir": "1", - "xEndstopBack": 1, + "xEndstopBack": 10, "yEndstopBack": 1, "zEndstopBack": 0, "deltaSegmentsPerSecondPrint": 180, @@ -673,21 +768,28 @@ Values must be in range 1..255 "name": "Extruder 1", "step": "ORIG_E1_STEP_PIN", "dir": "ORIG_E1_DIR_PIN", - "enable": "E1_ENABLE_PIN" + "enable": "ORIG_E1_ENABLE_PIN" }, "mirrorY": 0, "mirrorYMotor": { "name": "Extruder 1", "step": "ORIG_E1_STEP_PIN", "dir": "ORIG_E1_DIR_PIN", - "enable": "E1_ENABLE_PIN" + "enable": "ORIG_E1_ENABLE_PIN" }, "mirrorZ": 0, "mirrorZMotor": { "name": "Extruder 1", "step": "ORIG_E1_STEP_PIN", "dir": "ORIG_E1_DIR_PIN", - "enable": "E1_ENABLE_PIN" + "enable": "ORIG_E1_ENABLE_PIN" + }, + "mirrorZ3": "0", + "mirrorZ3Motor": { + "name": "Extruder 2", + "step": "ORIG_E2_STEP_PIN", + "dir": "ORIG_E2_DIR_PIN", + "enable": "ORIG_E2_ENABLE_PIN" }, "dittoPrinting": "0", "featureServos": "0", @@ -766,17 +868,20 @@ Values must be in range 1..255 "userTable0": { "r1": 0, "r2": 4700, - "temps": [] + "temps": [], + "numEntries": 0 }, "userTable1": { "r1": 0, "r2": 4700, - "temps": [] + "temps": [], + "numEntries": 0 }, "userTable2": { "r1": 0, "r2": 4700, - "temps": [] + "temps": [], + "numEntries": 0 }, "tempHysteresis": 0, "pidControlRange": 20, @@ -792,6 +897,15 @@ Values must be in range 1..255 "sdExtendedDir": "1", "featureFanControl": "0", "fanPin": -1, + "featureFan2Control": "0", + "fan2Pin": "ORIG_FAN2_PIN", + "fanThermoPin": -1, + "fanThermoMinPWM": 128, + "fanThermoMaxPWM": 255, + "fanThermoMinTemp": 45, + "fanThermoMaxTemp": 60, + "fanThermoThermistorPin": -1, + "fanThermoThermistorType": 1, "scalePidToMax": 0, "zProbePin": "ORIG_Z_MIN_PIN", "zProbeBedDistance": 10, @@ -800,18 +914,18 @@ Values must be in range 1..255 "zProbeXOffset": 6.4, "zProbeYOffset": 0, "zProbeWaitBeforeTest": "0", - "zProbeSpeed": 8, + "zProbeSpeed": 100, "zProbeXYSpeed": 150, - "zProbeHeight": 7.4, + "zProbeHeight": 6.9, "zProbeStartScript": "", "zProbeFinishedScript": "", "featureAutolevel": "1", - "zProbeX1": 20, - "zProbeY1": 20, - "zProbeX2": 160, - "zProbeY2": 20, - "zProbeX3": 100, - "zProbeY3": 160, + "zProbeX1": 5, + "zProbeY1": 5, + "zProbeX2": 150, + "zProbeY2": 5, + "zProbeX3": 150, + "zProbeY3": 150, "zProbeSwitchingDistance": 1, "zProbeRepetitions": 1, "sdSupport": "0", @@ -849,13 +963,17 @@ Values must be in range 1..255 "pauseStartCommands": "", "pauseEndCommands": "", "distortionCorrection": "0", - "distortionCorrectionPoints": 5, + "distortionCorrectionPoints": 3, "distortionCorrectionR": 100, - "distortionPermanent": "1", + "distortionPermanent": "0", "distortionUpdateFrequency": 15, "distortionStartDegrade": 0.5, "distortionEndDegrade": 1, "distortionExtrapolateCorners": "0", + "distortionXMin": 0, + "distortionXMax": 155, + "distortionYMin": 0, + "distortionYMax": 155, "sdRunOnStop": "", "sdStopHeaterMotorsOnStop": "1", "featureRetraction": "0", @@ -966,6 +1084,46 @@ Values must be in range 1..255 "zProbeZOffsetMode": 0, "zProbeZOffset": 0, "uiBedCoating": "1", + "langEN": "1", + "langDE": "1", + "langNL": "1", + "langPT": "1", + "langIT": "1", + "langES": "1", + "langSE": "1", + "langFR": "1", + "langCZ": "1", + "langPL": "1", + "langTR": "1", + "interpolateAccelerationWithZ": 0, + "accelerationFactorTop": 100, + "bendingCorrectionA": 0, + "bendingCorrectionB": 0, + "bendingCorrectionC": 0, + "preventZDisableOnStepperTimeout": "0", + "supportLaser": "0", + "laserPin": -1, + "laserOnHigh": "1", + "defaultPrinterMode": 0, + "supportCNC": "0", + "cncWaitOnEnable": 300, + "cncWaitOnDisable": 0, + "cncEnablePin": -1, + "cncEnableWith": "1", + "cncDirectionPin": -1, + "cncDirectionCW": "1", + "startupGCode": "", + "jsonOutput": "0", + "bedLevelingMethod": 0, + "bedCorrectionMethod": 0, + "bedLevelingGridSize": 5, + "bedLevelingRepetitions": 5, + "bedMotor1X": 0, + "bedMotor1Y": 0, + "bedMotor2X": 200, + "bedMotor2Y": 0, + "bedMotor3X": 100, + "bedMotor3Y": 200, "hasMAX6675": false, "hasMAX31855": false, "hasGeneric1": false, @@ -975,7 +1133,7 @@ Values must be in range 1..255 "hasUser1": false, "hasUser2": false, "numExtruder": 2, - "version": 92.4, + "version": 92.8, "primaryPortName": "" } ========== End configuration string ========== diff --git a/Repetier/Drivers.cpp b/Repetier/Drivers.cpp index 335d259..d8e4efa 100644 --- a/Repetier/Drivers.cpp +++ b/Repetier/Drivers.cpp @@ -1,102 +1,215 @@ -#include "Repetier.h" - -#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0 -MOTOR_DRIVER_1(motorDriver1); -#if NUM_MOTOR_DRIVERS > 1 -MOTOR_DRIVER_2(motorDriver2); -#endif -#if NUM_MOTOR_DRIVERS > 2 -MOTOR_DRIVER_3(motorDriver3); -#endif -#if NUM_MOTOR_DRIVERS > 3 -MOTOR_DRIVER_4(motorDriver4); -#endif -#if NUM_MOTOR_DRIVERS > 4 -MOTOR_DRIVER_5(motorDriver5); -#endif -#if NUM_MOTOR_DRIVERS > 5 -MOTOR_DRIVER_6(motorDriver6); -#endif - -MotorDriverInterface *motorDrivers[NUM_MOTOR_DRIVERS] = { - &motorDriver1 -#if NUM_MOTOR_DRIVERS > 1 - , &motorDriver2 -#endif -#if NUM_MOTOR_DRIVERS > 2 - , &motorDriver3 -#endif -#if NUM_MOTOR_DRIVERS > 3 - , &motorDriver4 -#endif -#if NUM_MOTOR_DRIVERS > 4 - , &motorDriver5 -#endif -#if NUM_MOTOR_DRIVERS > 5 - , &motorDriver6 -#endif -}; - -MotorDriverInterface *getMotorDriver(int idx) { - return motorDrivers[idx]; -} - -/** -Run motor P until it is at position X -*/ -void commandG201(GCode &code) { - int id = 0; - if(code.hasP()) - id = code.P; - if(id < 0) id = 0; - if(id >= NUM_MOTOR_DRIVERS) id = 0; - if(!code.hasX()) return; - motorDrivers[id]->gotoPosition(code.X); -} - -//G202 P X - Mark current position as X -void commandG202(GCode &code) { - int id = 0; - if(code.hasP()) - id = code.P; - if(id < 0) id = 0; - if(id >= NUM_MOTOR_DRIVERS) id = 0; - if(!code.hasX()) return; - motorDrivers[id]->setCurrentAs(code.X); -} -//G203 P - Report current motor position -void commandG203(GCode &code) { - int id = 0; - if(code.hasP()) - id = code.P; - if(id < 0) id = 0; - if(id >= NUM_MOTOR_DRIVERS) id = 0; - Com::printF(PSTR("Motor"),id); - Com::printFLN(PSTR("Pos:"),motorDrivers[id]->getPosition()); -} -//G204 P S<0/1> - Enable/disable motor -void commandG204(GCode &code) { - int id = 0; - if(code.hasP()) - id = code.P; - if(id < 0) id = 0; - if(id >= NUM_MOTOR_DRIVERS) id = 0; - if(!code.hasS()) return; - if(code.S) - motorDrivers[id]->enable(); - else - motorDrivers[id]->disable(); -} - -void disableAllMotorDrivers() { - for(int i = 0; i < NUM_MOTOR_DRIVERS; i++) - motorDrivers[i]->disable(); -} -void initializeAllMotorDrivers() { - for(int i = 0; i < NUM_MOTOR_DRIVERS; i++) - motorDrivers[i]->initialize(); -} - -#endif // NUM_MOTOR_DRIVERS - - +#include "Repetier.h" + +#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0 +MOTOR_DRIVER_1(motorDriver1); +#if NUM_MOTOR_DRIVERS > 1 +MOTOR_DRIVER_2(motorDriver2); +#endif +#if NUM_MOTOR_DRIVERS > 2 +MOTOR_DRIVER_3(motorDriver3); +#endif +#if NUM_MOTOR_DRIVERS > 3 +MOTOR_DRIVER_4(motorDriver4); +#endif +#if NUM_MOTOR_DRIVERS > 4 +MOTOR_DRIVER_5(motorDriver5); +#endif +#if NUM_MOTOR_DRIVERS > 5 +MOTOR_DRIVER_6(motorDriver6); +#endif + +MotorDriverInterface *motorDrivers[NUM_MOTOR_DRIVERS] = +{ + &motorDriver1 +#if NUM_MOTOR_DRIVERS > 1 + , &motorDriver2 +#endif +#if NUM_MOTOR_DRIVERS > 2 + , &motorDriver3 +#endif +#if NUM_MOTOR_DRIVERS > 3 + , &motorDriver4 +#endif +#if NUM_MOTOR_DRIVERS > 4 + , &motorDriver5 +#endif +#if NUM_MOTOR_DRIVERS > 5 + , &motorDriver6 +#endif +}; + +MotorDriverInterface *getMotorDriver(int idx) +{ + return motorDrivers[idx]; +} + +/** +Run motor P until it is at position X +*/ +void commandG201(GCode &code) +{ + int id = 0; + if(code.hasP()) + id = code.P; + if(id < 0) id = 0; + if(id >= NUM_MOTOR_DRIVERS) id = 0; + if(!code.hasX()) return; + motorDrivers[id]->gotoPosition(code.X); +} + +//G202 P X - Mark current position as X +void commandG202(GCode &code) +{ + int id = 0; + if(code.hasP()) + id = code.P; + if(id < 0) id = 0; + if(id >= NUM_MOTOR_DRIVERS) id = 0; + if(!code.hasX()) return; + motorDrivers[id]->setCurrentAs(code.X); +} +//G203 P - Report current motor position +void commandG203(GCode &code) +{ + int id = 0; + if(code.hasP()) + id = code.P; + if(id < 0) id = 0; + if(id >= NUM_MOTOR_DRIVERS) id = 0; + Com::printF(PSTR("Motor"),id); + Com::printFLN(PSTR("Pos:"),motorDrivers[id]->getPosition()); +} +//G204 P S<0/1> - Enable/disable motor +void commandG204(GCode &code) +{ + int id = 0; + if(code.hasP()) + id = code.P; + if(id < 0) id = 0; + if(id >= NUM_MOTOR_DRIVERS) id = 0; + if(!code.hasS()) return; + if(code.S) + motorDrivers[id]->enable(); + else + motorDrivers[id]->disable(); +} + +void disableAllMotorDrivers() +{ + for(int i = 0; i < NUM_MOTOR_DRIVERS; i++) + motorDrivers[i]->disable(); +} +void initializeAllMotorDrivers() +{ + for(int i = 0; i < NUM_MOTOR_DRIVERS; i++) + motorDrivers[i]->initialize(); +} + +#endif // NUM_MOTOR_DRIVERS + +#if defined(SUPPORT_LASER) && SUPPORT_LASER +uint8_t LaserDriver::intensity = 255; // Intensity to use for next move queued if we want lasers. This is NOT the current value! +bool LaserDriver::laserOn = false; +void LaserDriver::initialize() +{ + if(EVENT_INITALIZE_LASER) + { +#if LASER_PIN > -1 + SET_OUTPUT(LASER_PIN); +#endif + } + changeIntensity(0); +} +void LaserDriver::changeIntensity(uint8_t newIntensity) +{ + if(EVENT_SET_LASER(newIntensity)) + { + // Default implementation +#if LASER_PIN > -1 + WRITE(LASER_PIN,(LASER_ON_HIGH ? newIntensity > 199 : newIntensity < 200)); +#endif + } +} +#endif // SUPPORT_LASER + +#if defined(SUPPORT_CNC) && SUPPORT_CNC +/** +The CNC driver differs a bit from laser driver. Here only M3,M4,M5 have an influence on the spindle. +The motor also keeps running for G0 moves. M3 and M4 wait for old moves to be finished and then enables +the motor. It then waits CNC_WAIT_ON_ENABLE milliseconds for the spindle to reach target speed. +*/ + +int8_t CNCDriver::direction = 0; +/** Initialize cnc pins. EVENT_INITALIZE_CNC should return false to prevent default initalization.*/ +void CNCDriver::initialize() +{ + if(EVENT_INITALIZE_CNC) + { +#if CNC_ENABLE_PIN > -1 + SET_OUTPUT(CNC_ENABLE_PIN); + WRITE(CNC_ENABLE_PIN,!CNC_ENABLE_WITH); +#endif +#if CNC_DIRECTION_PIN > -1 + SET_OUTPUT(CNC_DIRECTION_PIN); +#endif + } +} +/** Turns off spindle. For event override implement +EVENT_SPINDLE_OFF +returning false. +*/ +void CNCDriver::spindleOff() +{ + if(direction == 0) return; // already off + if(EVENT_SPINDLE_OFF) + { +#if CNC_ENABLE_PIN > -1 + WRITE(CNC_ENABLE_PIN,!CNC_ENABLE_WITH); +#endif + } + HAL::delayMilliseconds(CNC_WAIT_ON_DISABLE); + direction = 0; +} +/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If +CNC_DIRECTION_PIN is not -1 it sets direction to CNC_DIRECTION_CW. rpm is ignored. +To override with event system, return false for the event +EVENT_SPINDLE_CW(rpm) +*/ +void CNCDriver::spindleOnCW(int32_t rpm) +{ + if(direction == 1) + return; + spindleOff(); + direction = 1; + if(EVENT_SPINDLE_CW(rpm)) { +#if CNC_DIRECTION_PIN > -1 + WRITE(CNC_DIRECTION_PIN, CNC_DIRECTION_CW); +#endif +#if CNC_ENABLE_PIN > -1 + WRITE(CNC_ENABLE_PIN, CNC_ENABLE_WITH); +#endif + } + HAL::delayMilliseconds(CNC_WAIT_ON_ENABLE); +} +/** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If +CNC_DIRECTION_PIN is not -1 it sets direction to !CNC_DIRECTION_CW. rpm is ignored. +To override with event system, return false for the event +EVENT_SPINDLE_CCW(rpm) +*/ +void CNCDriver::spindleOnCCW(int32_t rpm) +{ + if(direction == -1) + return; + spindleOff(); + direction = -1; + if(EVENT_SPINDLE_CW(rpm)) { +#if CNC_DIRECTION_PIN > -1 + WRITE(CNC_DIRECTION_PIN, !CNC_DIRECTION_CW); +#endif +#if CNC_ENABLE_PIN > -1 + WRITE(CNC_ENABLE_PIN, CNC_ENABLE_WITH); +#endif + } + HAL::delayMilliseconds(CNC_WAIT_ON_ENABLE); +} +#endif diff --git a/Repetier/Drivers.h b/Repetier/Drivers.h index 3c112af..ecf52e5 100644 --- a/Repetier/Drivers.h +++ b/Repetier/Drivers.h @@ -20,7 +20,7 @@ the main code. */ class MotorDriverInterface { -public: +public: virtual void initialize() = 0; virtual float getPosition() = 0; virtual void setCurrentAs(float newPos) = 0; @@ -43,12 +43,12 @@ public: { stepsPerMM = _stepsPerMM; delayUS = 500000 / (speed * stepsPerMM); - } - void initialize() { + } + void initialize() { HAL::pinMode(enablePin, OUTPUT); HAL::pinMode(stepPin, OUTPUT); HAL::pinMode(dirPin, OUTPUT); - HAL::digitalWrite(enablePin, !invertEnable); + HAL::digitalWrite(enablePin, !invertEnable); } float getPosition() { @@ -59,7 +59,7 @@ public: position = floor(newPos * stepsPerMM + 0.5f); } void gotoPosition(float newPos) - { + { enable(); int32_t target = floor(newPos * stepsPerMM + 0.5f) - position; position += target; @@ -74,9 +74,9 @@ public: HAL::delayMicroseconds(delayUS); HAL::digitalWrite(stepPin, LOW); HAL::delayMicroseconds(delayUS); - target--; - HAL::pingWatchdog(); - if((target & 127) == 0) + target--; + HAL::pingWatchdog(); + if((target & 127) == 0) Commands::checkForPeriodicalActions(false); } } @@ -88,19 +88,66 @@ public: { HAL::digitalWrite(enablePin, !invertEnable); } -}; - -#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0 -class GCode; +}; + +#if defined(NUM_MOTOR_DRIVERS) && NUM_MOTOR_DRIVERS > 0 +class GCode; extern void commandG201(GCode &code); extern void commandG202(GCode &code); extern void commandG203(GCode &code); -extern void commandG204(GCode &code); -extern void disableAllMotorDrivers(); -extern MotorDriverInterface *getMotorDriver(int idx); -extern void initializeAllMotorDrivers(); -#endif +extern void commandG204(GCode &code); +extern void disableAllMotorDrivers(); +extern MotorDriverInterface *getMotorDriver(int idx); +extern void initializeAllMotorDrivers(); +#endif + + +#if defined(SUPPORT_LASER) && SUPPORT_LASER +/** +With laser support you can exchange a extruder by a laser. A laser gets controlled by a digital pin. +By default all intensities > 200 are always on, and lower values are always off. You can overwrite +this with a programmed event EVENT_SET_LASER(intensity) that return false to signal the default +implementation that it has set it's value already. +EVENT_INITALIZE_LASER should return false to prevent default initialization. +*/ +class LaserDriver { +public: + static uint8_t intensity; // Intensity to use for next move queued. This is NOT the current value! + static bool laserOn; // Enabled by M3? + static void initialize(); + static void changeIntensity(uint8_t newIntensity); +}; +#endif + +#if defined(SUPPORT_CNC) && SUPPORT_CNC +/** +The CNC driver differs a bit from laser driver. Here only M3,M4,M5 have an influence on the spindle. +The motor also keeps running for G0 moves. M3 and M4 wait for old moves to be finished and then enables +the motor. It then waits CNC_WAIT_ON_ENABLE milliseconds for the spindle to reach target speed. +*/ +class CNCDriver { +public: + static int8_t direction; + /** Initialize cnc pins. EVENT_INITALIZE_CNC should return false to prevent default initalization.*/ + static void initialize(); + /** Turns off spindle. For event override implement + EVENT_SPINDLE_OFF + returning false. + */ + static void spindleOff(); + /** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If + CNC_DIRECTION_PIN is not -1 it sets direction to CNC_DIRECTION_CW. rpm is ignored. + To override with event system, return false for the event + EVENT_SPINDLE_CW(rpm) + */ + static void spindleOnCW(int32_t rpm); + /** Turns spindle on. Default implementation uses a enable pin CNC_ENABLE_PIN. If + CNC_DIRECTION_PIN is not -1 it sets direction to !CNC_DIRECTION_CW. rpm is ignored. + To override with event system, return false for the event + EVENT_SPINDLE_CCW(rpm) + */ + static void spindleOnCCW(int32_t rpm); +}; +#endif #endif // DRIVERS_H_INCLUDED - - diff --git a/Repetier/Eeprom.cpp b/Repetier/Eeprom.cpp index 219ec4c..ab7f3e2 100644 --- a/Repetier/Eeprom.cpp +++ b/Repetier/Eeprom.cpp @@ -232,7 +232,7 @@ void EEPROM::restoreEEPROMSettingsFromConfiguration() e->advanceL = EXT3_ADVANCE_L; #endif #endif // NUM_EXTRUDER > 3 -#if NUM_EXTRUDER>4 +#if NUM_EXTRUDER > 4 e = &extruder[4]; e->stepsPerMM = EXT4_STEPS_PER_MM; e->maxFeedrate = EXT4_MAX_FEEDRATE; @@ -262,7 +262,7 @@ void EEPROM::restoreEEPROMSettingsFromConfiguration() e->advanceL = EXT4_ADVANCE_L; #endif #endif // NUM_EXTRUDER > 4 -#if NUM_EXTRUDER>5 +#if NUM_EXTRUDER > 5 e = &extruder[5]; e->stepsPerMM = EXT5_STEPS_PER_MM; e->maxFeedrate = EXT5_MAX_FEEDRATE; @@ -385,6 +385,9 @@ void EEPROM::storeDataIntoEEPROM(uint8_t corrupted) HAL::eprSetByte(EPR_AUTOLEVEL_ACTIVE,Printer::isAutolevelActive()); for(uint8_t i = 0; i < 9; i++) HAL::eprSetFloat(EPR_AUTOLEVEL_MATRIX + (((int)i) << 2),Printer::autolevelTransformation[i]); +#endif +#if UI_DISPLAY_TYPE != NO_DISPLAY + HAL::eprSetByte(EPR_SELECTED_LANGUAGE,Com::selectedLanguage); #endif // now the extruder for(uint8_t i = 0; i < NUM_EXTRUDER; i++) @@ -453,6 +456,7 @@ void EEPROM::initalizeUncached() HAL::eprSetFloat(EPR_Z_PROBE_XY_SPEED,Z_PROBE_XY_SPEED); HAL::eprSetFloat(EPR_Z_PROBE_X_OFFSET,Z_PROBE_X_OFFSET); HAL::eprSetFloat(EPR_Z_PROBE_Y_OFFSET,Z_PROBE_Y_OFFSET); + HAL::eprSetFloat(EPR_Z_PROBE_Z_OFFSET,Z_PROBE_Z_OFFSET); HAL::eprSetFloat(EPR_Z_PROBE_X1,Z_PROBE_X1); HAL::eprSetFloat(EPR_Z_PROBE_Y1,Z_PROBE_Y1); HAL::eprSetFloat(EPR_Z_PROBE_X2,Z_PROBE_X2); @@ -463,6 +467,7 @@ void EEPROM::initalizeUncached() HAL::eprSetFloat(EPR_AXISCOMP_TANYZ,AXISCOMP_TANYZ); HAL::eprSetFloat(EPR_AXISCOMP_TANXZ,AXISCOMP_TANXZ); HAL::eprSetFloat(EPR_Z_PROBE_BED_DISTANCE,Z_PROBE_BED_DISTANCE); + Printer::zBedOffset = HAL::eprGetFloat(EPR_Z_PROBE_Z_OFFSET); #if DRIVE_SYSTEM == DELTA HAL::eprSetFloat(EPR_DELTA_DIAGONAL_ROD_LENGTH,DELTA_DIAGONAL_ROD); HAL::eprSetFloat(EPR_DELTA_HORIZONTAL_RADIUS,ROD_RADIUS); @@ -495,6 +500,10 @@ void EEPROM::initalizeUncached() HAL::eprSetFloat(EPR_RETRACTION_UNDO_EXTRA_LONG_LENGTH,RETRACTION_UNDO_EXTRA_LONG_LENGTH); HAL::eprSetFloat(EPR_RETRACTION_UNDO_SPEED,RETRACTION_UNDO_SPEED); HAL::eprSetByte(EPR_AUTORETRACT_ENABLED,AUTORETRACT_ENABLED); + HAL::eprSetFloat(EPR_BENDING_CORRECTION_A,BENDING_CORRECTION_A); + HAL::eprSetFloat(EPR_BENDING_CORRECTION_B,BENDING_CORRECTION_B); + HAL::eprSetFloat(EPR_BENDING_CORRECTION_C,BENDING_CORRECTION_C); + HAL::eprSetFloat(EPR_ACCELERATION_FACTOR_TOP,Z_ACCELERATION_TOP); } @@ -502,6 +511,7 @@ void EEPROM::readDataFromEEPROM(bool includeExtruder) { #if EEPROM_MODE != 0 uint8_t version = HAL::eprGetByte(EPR_VERSION); // This is the saved version. Don't copy data not set in older versions! + //Com::printFLN(PSTR("Detected EEPROM version:"),(int)version); baudrate = HAL::eprGetInt32(EPR_BAUDRATE); maxInactiveTime = HAL::eprGetInt32(EPR_MAX_INACTIVE_TIME); stepperInactiveTime = HAL::eprGetInt32(EPR_STEPPER_INACTIVE_TIME); @@ -705,6 +715,21 @@ void EEPROM::readDataFromEEPROM(bool includeExtruder) HAL::eprSetFloat(EPR_RETRACTION_UNDO_SPEED,RETRACTION_UNDO_SPEED); HAL::eprSetByte(EPR_AUTORETRACT_ENABLED,AUTORETRACT_ENABLED); } + if(version < 14) { + HAL::eprSetFloat(EPR_Z_PROBE_Z_OFFSET,Z_PROBE_Z_OFFSET); + } + if(version < 15) { + HAL::eprSetByte(EPR_SELECTED_LANGUAGE, 254); // activate selector on startup +#if UI_DISPLAY_TYPE != NO_DISPLAY + Com::selectedLanguage = 254; +#endif + } + if(version < 16) { + HAL::eprSetFloat(EPR_BENDING_CORRECTION_A,BENDING_CORRECTION_A); + HAL::eprSetFloat(EPR_BENDING_CORRECTION_B,BENDING_CORRECTION_B); + HAL::eprSetFloat(EPR_BENDING_CORRECTION_C,BENDING_CORRECTION_C); + HAL::eprSetFloat(EPR_ACCELERATION_FACTOR_TOP,ACCELERATION_FACTOR_TOP); + } /* if (version<8) { #if DRIVE_SYSTEM==DELTA // Prior to verion 8, the cartesian max was stored in the zmax @@ -723,6 +748,10 @@ void EEPROM::readDataFromEEPROM(bool includeExtruder) storeDataIntoEEPROM(false); // Store new fields for changed version } + Printer::zBedOffset = HAL::eprGetFloat(EPR_Z_PROBE_Z_OFFSET); +#if UI_DISPLAY_TYPE != NO_DISPLAY + Com::selectLanguage(HAL::eprGetByte(EPR_SELECTED_LANGUAGE)); +#endif Printer::updateDerivedParameter(); Extruder::initHeatedBed(); #endif @@ -733,7 +762,7 @@ void EEPROM::initBaudrate() // Invariant - baudrate is intitalized with or without eeprom! baudrate = BAUDRATE; #if EEPROM_MODE != 0 - if(HAL::eprGetByte(EPR_MAGIC_BYTE)==EEPROM_MODE) + if(HAL::eprGetByte(EPR_MAGIC_BYTE) == EEPROM_MODE) { baudrate = HAL::eprGetInt32(EPR_BAUDRATE); } @@ -762,7 +791,7 @@ void EEPROM::init() if(newcheck != HAL::eprGetByte(EPR_INTEGRITY_BYTE)) HAL::eprSetByte(EPR_INTEGRITY_BYTE,newcheck); } - Com::printFLN(PSTR("EEprom baud rate restored from configuration.")); + Com::printFLN(PSTR("EEPROM baud rate restored from configuration.")); Com::printFLN(PSTR("RECOMPILE WITH USE_CONFIGURATION_BAUD_RATE == 0 to alter baud rate via EEPROM")); } } @@ -805,6 +834,7 @@ With void EEPROM::writeSettings() { #if EEPROM_MODE != 0 + writeByte(EPR_SELECTED_LANGUAGE,Com::tLanguage); writeLong(EPR_BAUDRATE, Com::tEPRBaudrate); writeFloat(EPR_PRINTING_DISTANCE, Com::tEPRFilamentPrinted); writeLong(EPR_PRINTING_TIME, Com::tEPRPrinterActive); @@ -852,6 +882,9 @@ void EEPROM::writeSettings() #if DRIVE_SYSTEM == DELTA writeFloat(EPR_Z_MAX_ACCEL, Com::tEPRZAcceleration); writeFloat(EPR_Z_MAX_TRAVEL_ACCEL, Com::tEPRZTravelAcceleration); +#if defined(INTERPOLATE_ACCELERATION_WITH_Z) && INTERPOLATE_ACCELERATION_WITH_Z != 0 + writeFloat(EPR_ACCELERATION_FACTOR_TOP, Com::tEPRAccelerationFactorAtTop); +#endif writeFloat(EPR_DELTA_DIAGONAL_ROD_LENGTH, Com::tEPRDiagonalRodLength); writeFloat(EPR_DELTA_HORIZONTAL_RADIUS, Com::tEPRHorizontalRadius); writeFloat(EPR_DELTA_MAX_RADIUS, Com::tEPRDeltaMaxRadius); @@ -876,8 +909,12 @@ void EEPROM::writeSettings() writeFloat(EPR_X_MAX_TRAVEL_ACCEL, Com::tEPRXTravelAcceleration); writeFloat(EPR_Y_MAX_TRAVEL_ACCEL, Com::tEPRYTravelAcceleration); writeFloat(EPR_Z_MAX_TRAVEL_ACCEL, Com::tEPRZTravelAcceleration); +#if defined(INTERPOLATE_ACCELERATION_WITH_Z) && INTERPOLATE_ACCELERATION_WITH_Z != 0 + writeFloat(EPR_ACCELERATION_FACTOR_TOP, Com::tEPRAccelerationFactorAtTop); #endif #endif +#endif + writeFloat(EPR_Z_PROBE_Z_OFFSET, Com::tZProbeOffsetZ); #if FEATURE_Z_PROBE writeFloat(EPR_Z_PROBE_HEIGHT, Com::tZProbeHeight); writeFloat(EPR_Z_PROBE_BED_DISTANCE, Com::tZProbeBedDitance); @@ -891,6 +928,9 @@ void EEPROM::writeSettings() writeFloat(EPR_Z_PROBE_Y2, Com::tZProbeY2); writeFloat(EPR_Z_PROBE_X3, Com::tZProbeX3); writeFloat(EPR_Z_PROBE_Y3, Com::tZProbeY3); + writeFloat(EPR_BENDING_CORRECTION_A, Com::zZProbeBendingCorA); + writeFloat(EPR_BENDING_CORRECTION_B, Com::zZProbeBendingCorB); + writeFloat(EPR_BENDING_CORRECTION_C, Com::zZProbeBendingCorC); #endif #if FEATURE_AUTOLEVEL writeByte(EPR_AUTOLEVEL_ACTIVE, Com::tAutolevelActive); @@ -1092,5 +1132,3 @@ void EEPROM::setZCorrection(int32_t c,int index) #endif - - diff --git a/Repetier/Eeprom.h b/Repetier/Eeprom.h index 670c91f..62229f9 100644 --- a/Repetier/Eeprom.h +++ b/Repetier/Eeprom.h @@ -20,7 +20,7 @@ #define _EEPROM_H // Id to distinguish version changes -#define EEPROM_PROTOCOL_VERSION 13 +#define EEPROM_PROTOCOL_VERSION 16 /** Where to start with our datablock in memory. Can be moved if you have problems with other modules using the eeprom */ @@ -112,15 +112,21 @@ have problems with other modules using the eeprom */ #define EPR_AXISCOMP_TANYZ 980 #define EPR_AXISCOMP_TANXZ 984 -#define EPR_DISTORTION_CORRECTION_ENABLED 988 -#define EPR_RETRACTION_LENGTH 992 -#define EPR_RETRACTION_LONG_LENGTH 996 -#define EPR_RETRACTION_SPEED 1000 -#define EPR_RETRACTION_Z_LIFT 1004 -#define EPR_RETRACTION_UNDO_EXTRA_LENGTH 1008 +#define EPR_DISTORTION_CORRECTION_ENABLED 988 +#define EPR_RETRACTION_LENGTH 992 +#define EPR_RETRACTION_LONG_LENGTH 996 +#define EPR_RETRACTION_SPEED 1000 +#define EPR_RETRACTION_Z_LIFT 1004 +#define EPR_RETRACTION_UNDO_EXTRA_LENGTH 1008 #define EPR_RETRACTION_UNDO_EXTRA_LONG_LENGTH 1012 -#define EPR_RETRACTION_UNDO_SPEED 1016 -#define EPR_AUTORETRACT_ENABLED 1020 +#define EPR_RETRACTION_UNDO_SPEED 1016 +#define EPR_AUTORETRACT_ENABLED 1020 +#define EPR_Z_PROBE_Z_OFFSET 1024 +#define EPR_SELECTED_LANGUAGE 1028 +#define EPR_ACCELERATION_FACTOR_TOP 1032 +#define EPR_BENDING_CORRECTION_A 1036 +#define EPR_BENDING_CORRECTION_B 1040 +#define EPR_BENDING_CORRECTION_C 1044 #if EEPROM_MODE != 0 #define EEPROM_FLOAT(x) HAL::eprGetFloat(EPR_##x) @@ -128,9 +134,9 @@ have problems with other modules using the eeprom */ #define EEPROM_BYTE(x) HAL::eprGetByte(EPR_##x) #define EEPROM_SET_BYTE(x,val) HAL::eprSetByte(EPR_##x,val) #else -#define EEPROM_FLOAT(x) (x) -#define EEPROM_INT32(x) (x) -#define EEPROM_BYTE(x) (x) +#define EEPROM_FLOAT(x) (float)(x) +#define EEPROM_INT32(x) (int32_t)(x) +#define EEPROM_BYTE(x) (uint8_t)(x) #define EEPROM_SET_BYTE(x,val) #endif @@ -189,7 +195,26 @@ public: static void writeSettings(); static void update(GCode *com); static void updatePrinterUsage(); - + static inline void setVersion(uint8_t v) { +#if EEPROM_MODE != 0 + HAL::eprSetByte(EPR_VERSION,v); + HAL::eprSetByte(EPR_INTEGRITY_BYTE,computeChecksum()); +#endif + } + static inline uint8_t getStoredLanguage() { +#if EEPROM_MODE != 0 + return HAL::eprGetByte(EPR_SELECTED_LANGUAGE); +#else + return 0; +#endif + } + static inline float zProbeZOffset() { +#if EEPROM_MODE != 0 + return HAL::eprGetFloat(EPR_Z_PROBE_Z_OFFSET); +#else + return Z_PROBE_Z_OFFSET; +#endif + } static inline float zProbeSpeed() { #if EEPROM_MODE != 0 return HAL::eprGetFloat(EPR_Z_PROBE_SPEED); @@ -516,7 +541,34 @@ static inline void setTowerZFloor(float newZ) { return 0; #endif } + static inline float bendingCorrectionA() { +#if EEPROM_MODE != 0 + return HAL::eprGetFloat(EPR_BENDING_CORRECTION_A); +#else + return BENDING_CORRECTION_A; +#endif + } + static inline float bendingCorrectionB() { +#if EEPROM_MODE != 0 + return HAL::eprGetFloat(EPR_BENDING_CORRECTION_B); +#else + return BENDING_CORRECTION_B; +#endif + } + static inline float bendingCorrectionC() { +#if EEPROM_MODE != 0 + return HAL::eprGetFloat(EPR_BENDING_CORRECTION_C); +#else + return BENDING_CORRECTION_C; +#endif + } + static inline float accelarationFactorTop() { +#if EEPROM_MODE != 0 + return HAL::eprGetFloat(EPR_ACCELERATION_FACTOR_TOP); +#else + return ACCELERATION_FACTOR_TOP; +#endif + } + }; #endif - - diff --git a/Repetier/Events.h b/Repetier/Events.h index eb004c9..3871232 100644 --- a/Repetier/Events.h +++ b/Repetier/Events.h @@ -1,71 +1,84 @@ -#ifndef EVENTS_H_INCLUDED -#define EVENTS_H_INCLUDED - -/* -Event system in a nutshell: - -All printers are different and my need additions in th eone or other place. -It is not very convenient to add these code parts across the firmware. For this -reason repetier-firmware uses a simple event system that comes at no cost if -a event is not used. - -- simple: Only one subscriber is possible -- cost effective: Macros work as event caller. By default all macros are empty - -How to use the system: - -1. In Configuration.h add -#define CUSTOM_EVENTS -2. Add a file "CustomEvents.h" which overrides all event macros you need. - It shoudl also include the function declarations used. -3. Add a file "CustomEventsImpl.h" which includes all function definitions. - Also it is named .h it will be included inside a cpp file only once. - This is to compile only when selected and still keep ArduinoIDE happy. - -Each of the following events describe the parameter and when it is called. -*/ - -// Catch heating events. id is extruder id or -1 for heated bed. -#define EVENT_WAITING_HEATER(id) {} -#define EVENT_HEATING_FINISHED(id) {} - -// This gets called every 0.1 second -#define EVENT_TIMER_100MS {} -// This gets called every 0.5 second -#define EVENT_TIMER_500MS {} -// Gets called on a regular basis as time allows -#define EVENT_PERIODICAL {} -// Gets called when kill gets called. only_steppes = true -> we only want to disable steppers, not everything. -#define EVENT_KILL(only_steppers) {} -// Gets called when a jam was detected. -#define EVENT_JAM_DETECTED {} -// Gets called everytime the jam detection signal switches. Steps are the extruder steps since last change. -#define EVENT_JAM_SIGNAL_CHANGED(extruderId,steps) {} -// Gets called if a heater decoupling is detected. -#define EVENT_HEATER_DECOUPLED(id) {} -// Gets called if a missing/shorted thermistor is detected. -#define EVENT_HEATER_DEFECT(id) {} -// Gets called if a action in ui.cpp okAction gets executed. -#define EVENT_START_UI_ACTION(shortAction) {} -// Gets called if a nextPrevius actions gets executed. -#define EVENT_START_NEXTPREVIOUS(action,increment) {} - -// Allow adding new G and M codes. To implement it create a function -// bool eventUnhandledGCode(GCode *com) -// that returns true if it handled the code, otherwise false. -// Event define would then be -// #define EVENT_UNHANDLED_G_CODE(c) eventUnhandledGCode(c) -#define EVENT_UNHANDLED_G_CODE(c) false -#define EVENT_UNHANDLED_M_CODE(c) false - -// This gets called every time the user has saved a value to eeprom -// or any other reason why dependent values may need recomputation. -#define EVENT_UPDATE_DERIVED {} - -// This gets called after the basic firmware functions have initialized. -// Use this to initalize your hardware etc. -#define EVENT_INITIALIZE {} - -#endif // EVENTS_H_INCLUDED - - +#ifndef EVENTS_H_INCLUDED +#define EVENTS_H_INCLUDED + +/* +Event system in a nutshell: + +All printers are different and my need additions in th eone or other place. +It is not very convenient to add these code parts across the firmware. For this +reason repetier-firmware uses a simple event system that comes at no cost if +a event is not used. + +- simple: Only one subscriber is possible +- cost effective: Macros work as event caller. By default all macros are empty + +How to use the system: + +1. In Configuration.h add +#define CUSTOM_EVENTS +2. Add a file "CustomEvents.h" which overrides all event macros you need. + It shoudl also include the function declarations used. +3. Add a file "CustomEventsImpl.h" which includes all function definitions. + Also it is named .h it will be included inside a cpp file only once. + This is to compile only when selected and still keep ArduinoIDE happy. + +Each of the following events describe the parameter and when it is called. +*/ + +// Catch heating events. id is extruder id or -1 for heated bed. +#define EVENT_WAITING_HEATER(id) {} +#define EVENT_HEATING_FINISHED(id) {} + +// This gets called every 0.1 second +#define EVENT_TIMER_100MS {} +// This gets called every 0.5 second +#define EVENT_TIMER_500MS {} +// Gets called on a regular basis as time allows +#define EVENT_PERIODICAL {} +// Gets called when kill gets called. only_steppes = true -> we only want to disable steppers, not everything. +#define EVENT_KILL(only_steppers) {} +// Gets called when a jam was detected. +#define EVENT_JAM_DETECTED {} +// Gets called everytime the jam detection signal switches. Steps are the extruder steps since last change. +#define EVENT_JAM_SIGNAL_CHANGED(extruderId,steps) {} +// Gets called if a heater decoupling is detected. +#define EVENT_HEATER_DECOUPLED(id) {} +// Gets called if a missing/shorted thermistor is detected. +#define EVENT_HEATER_DEFECT(id) {} +// Gets called if a action in ui.cpp okAction gets executed. +#define EVENT_START_UI_ACTION(shortAction) {} +// Gets called if a nextPrevius actions gets executed. +#define EVENT_START_NEXTPREVIOUS(action,increment) {} + +// Called to initalize laser pins. Return false to prevent default initalization. +#define EVENT_INITALIZE_LASER true +// Set laser to intensity level 0 = off, 255 = full. Return false if you have overridden the setting routine. +// with true the default solution will set it as digital value. +#define EVENT_SET_LASER(intensity) true + +// Called to initalize cnc pins. Return false to prevent default initalization. +#define EVENT_INITALIZE_CNC true +// Turn off spindle +#define EVENT_SPINDLE_OFF true +// Turn spindle clockwise +#define EVENT_SPINDLE_CW(rpm) true +// Turn spindle counter clockwise +#define EVENT_SPINDLE_CCW(rpm) true + +// Allow adding new G and M codes. To implement it create a function +// bool eventUnhandledGCode(GCode *com) +// that returns true if it handled the code, otherwise false. +// Event define would then be +// #define EVENT_UNHANDLED_G_CODE(c) eventUnhandledGCode(c) +#define EVENT_UNHANDLED_G_CODE(c) false +#define EVENT_UNHANDLED_M_CODE(c) false + +// This gets called every time the user has saved a value to eeprom +// or any other reason why dependent values may need recomputation. +#define EVENT_UPDATE_DERIVED {} + +// This gets called after the basic firmware functions have initialized. +// Use this to initalize your hardware etc. +#define EVENT_INITIALIZE {} + +#endif // EVENTS_H_INCLUDED diff --git a/Repetier/Extruder.cpp b/Repetier/Extruder.cpp index 360d577..c75cfed 100644 --- a/Repetier/Extruder.cpp +++ b/Repetier/Extruder.cpp @@ -66,11 +66,35 @@ void Extruder::manageTemperatures() HAL::pingWatchdog(); #endif // FEATURE_WATCHDOG uint8_t errorDetected = 0; +#ifdef RED_BLUE_STATUS_LEDS bool hot = false; +#endif + bool newDefectFound = false; millis_t time = HAL::timeInMilliseconds(); // compare time for decouple tests +#if NUM_TEMPERATURE_LOOPS > 0 for(uint8_t controller = 0; controller < NUM_TEMPERATURE_LOOPS; controller++) { TemperatureController *act = tempController[controller]; + // Get Temperature + act->updateCurrentTemperature(); +#if FAN_THERMO_PIN > -1 + // Special case thermistor controlled fan + if(act == &thermoController) { + if(act->currentTemperatureC < Printer::thermoMinTemp) + pwm_pos[PWM_FAN_THERMO] = 0; + else if(act->currentTemperatureC > Printer::thermoMaxTemp) + pwm_pos[PWM_FAN_THERMO] = FAN_THERMO_MAX_PWM; + else { + // Interpolate target speed + float out = FAN_THERMO_MIN_PWM + (FAN_THERMO_MAX_PWM-FAN_THERMO_MIN_PWM) * (act->currentTemperatureC - Printer::thermoMinTemp) / (Printer::thermoMaxTemp - Printer::thermoMinTemp); + if(out > 255) + pwm_pos[PWM_FAN_THERMO] = FAN_THERMO_MAX_PWM; + else + pwm_pos[PWM_FAN_THERMO] = static_cast(out); + } + continue; + } +#endif // Handle automatic cooling of extruders if(controller < NUM_EXTRUDER) { @@ -87,25 +111,22 @@ void Extruder::manageTemperatures() } } #if SHARED_COOLER_BOARD_EXT - if(pwm_pos[NUM_EXTRUDER + 1]) enable = true; + if(pwm_pos[PWM_BOARD_FAN]) enable = true; #endif extruder[0].coolerPWM = (enable ? extruder[0].coolerSpeed : 0); - } + } // controller == 0 #else if(act->currentTemperatureC < EXTRUDER_FAN_COOL_TEMP && act->targetTemperatureC < EXTRUDER_FAN_COOL_TEMP) extruder[controller].coolerPWM = 0; else extruder[controller].coolerPWM = extruder[controller].coolerSpeed; #endif // NUM_EXTRUDER - } + } // extruder controller // do skip temperature control while auto tuning is in progress if(controller == autotuneIndex) continue; #if MIXING_EXTRUDER if(controller > 0 && controller < NUM_EXTRUDER) continue; // Mixing extruder only test for ext 0 -#endif - - // Get Temperature - act->updateCurrentTemperature(); +#endif // MIXING_EXTRUDER // Check for obvious sensor errors @@ -119,14 +140,36 @@ void Extruder::manageTemperatures() act->flags |= TEMPERATURE_CONTROLLER_FLAG_SENSDEFECT; if(!Printer::isAnyTempsensorDefect()) { + newDefectFound = true; Printer::setAnyTempsensorDefect(); reportTempsensorError(); } EVENT_HEATER_DEFECT(controller); } } +#if HAVE_HEATED_BED + else if(controller == NUM_EXTRUDER && Extruder::getHeatedBedTemperature() > HEATED_BED_MAX_TEMP + 5) { + errorDetected = 1; + if(extruderTempErrors < 10) // Ignore short temporary failures + extruderTempErrors++; + else + { + act->flags |= TEMPERATURE_CONTROLLER_FLAG_SENSDEFECT; + Com::printErrorFLN(PSTR("Heated bed exceeded max temperature!")); + if(!Printer::isAnyTempsensorDefect()) + { + newDefectFound = true; + Printer::setAnyTempsensorDefect(); + reportTempsensorError(); + } + EVENT_HEATER_DEFECT(controller); + } + } +#endif // HAVE_HEATED_BED +#ifdef RED_BLUE_STATUS_LEDS if(act->currentTemperatureC > 50) hot = true; +#endif // RED_BLUE_STATUS_LEDS if(Printer::isAnyTempsensorDefect()) continue; uint8_t on = act->currentTemperatureC >= act->targetTemperatureC ? LOW : HIGH; // Make a sound if alarm was set on reaching target temperature @@ -137,7 +180,7 @@ void Extruder::manageTemperatures() } // Run test if heater and sensor are decoupled - bool decoupleTestRequired = act->decoupleTestPeriod > 0 && (time - act->lastDecoupleTest) > act->decoupleTestPeriod; // time enough for temperature change? + bool decoupleTestRequired = !errorDetected && act->decoupleTestPeriod > 0 && (time - act->lastDecoupleTest) > act->decoupleTestPeriod; // time enough for temperature change? if(decoupleTestRequired && act->isDecoupleFullOrHold() && Printer::isPowerOn()) // Only test when powered { if(act->isDecoupleFull()) // Phase 1: Heating fully until target range is reached @@ -149,7 +192,12 @@ void Extruder::manageTemperatures() if(extruderTempErrors > 10) // Ignore short temporary failures { act->flags |= TEMPERATURE_CONTROLLER_FLAG_SENSDECOUPLED; - Printer::setAnyTempsensorDefect(); + + if(!Printer::isAnyTempsensorDefect()) + { + Printer::setAnyTempsensorDefect(); + newDefectFound = true; + } UI_ERROR_P(Com::tHeaterDecoupled); Com::printErrorFLN(Com::tHeaterDecoupledWarning); Com::printF(PSTR("Error:Temp. raised to slow. Rise = "),act->currentTemperatureC - act->lastDecoupleTemp); @@ -173,7 +221,11 @@ void Extruder::manageTemperatures() if(extruderTempErrors > 10) // Ignore short temporary failures { act->flags |= TEMPERATURE_CONTROLLER_FLAG_SENSDECOUPLED; - Printer::setAnyTempsensorDefect(); + if(!Printer::isAnyTempsensorDefect()) + { + Printer::setAnyTempsensorDefect(); + newDefectFound = true; + } UI_ERROR_P(Com::tHeaterDecoupled); Com::printErrorFLN(Com::tHeaterDecoupledWarning); Com::printF(PSTR("Error:Could not hold temperature "),act->lastDecoupleTemp); @@ -218,7 +270,7 @@ void Extruder::manageTemperatures() pidTerm += dgain; #if SCALE_PID_TO_MAX == 1 pidTerm = (pidTerm * act->pidMax) * 0.0039215; -#endif +#endif // SCALE_PID_TO_MAX output = constrain((int)pidTerm, 0, act->pidMax); } else if(act->heatManager == HTR_DEADTIME) // dead-time control @@ -229,7 +281,7 @@ void Extruder::manageTemperatures() output = (act->currentTemperatureC + act->tempIState * act->deadTime > act->targetTemperatureC ? 0 : act->pidDriveMax); } else // bang bang and slow bang bang -#endif +#endif // TEMP_PID if(act->heatManager == HTR_SLOWBANG) // Bang-bang with reduced change frequency to save relais life { if (time - act->lastTemperatureUpdate > HEATED_BED_SET_INTERVAL) @@ -251,19 +303,22 @@ void Extruder::manageTemperatures() #ifdef MAXTEMP if(act->currentTemperatureC > MAXTEMP) // Force heater off if MAXTEMP is exceeded output = 0; -#endif +#endif // MAXTEMP pwm_pos[act->pwmIndex] = output; // set pwm signal #if LED_PIN > -1 if(act == &Extruder::current->tempControl) WRITE(LED_PIN,on); -#endif +#endif // LED_PIN } // for controller #ifdef RED_BLUE_STATUS_LEDS - if(Printer::isAnyTempsensorDefect()) { + if(Printer::isAnyTempsensorDefect()) + { WRITE(BLUE_STATUS_LED,HIGH); WRITE(RED_STATUS_LED,HIGH); - } else { + } + else + { WRITE(BLUE_STATUS_LED,!hot); WRITE(RED_STATUS_LED,hot); } @@ -271,14 +326,12 @@ void Extruder::manageTemperatures() if(errorDetected == 0 && extruderTempErrors > 0) extruderTempErrors--; - if(Printer::isAnyTempsensorDefect() -#if HAVE_HEATED_BED - || Extruder::getHeatedBedTemperature() > HEATED_BED_MAX_TEMP + 5 -#endif - ) + if(newDefectFound) { + Com::printFLN(PSTR("Disabling all heaters due to detected sensor defect.")); for(uint8_t i = 0; i < NUM_TEMPERATURE_LOOPS; i++) { + tempController[i]->targetTemperatureC = 0; pwm_pos[tempController[i]->pwmIndex] = 0; } #if defined(KILL_IF_SENSOR_DEFECT) && KILL_IF_SENSOR_DEFECT > 0 @@ -286,12 +339,13 @@ void Extruder::manageTemperatures() { #if SDSUPPORT sd.stopPrint(); -#endif +#endif // SDSUPPORT Printer::kill(0); } -#endif - Printer::debugLevel |= 8; // Go into dry mode - } +#endif // KILL_IF_SENSOR_DEFECT + Printer::debugSet(8); // Go into dry mode + } // any sensor defect +#endif // NUM_TEMPERATURE_LOOPS } @@ -509,7 +563,7 @@ void TemperatureController::updateTempControlVars() /** \brief Select extruder ext_num. -This function changes and initalizes a new extruder. This is also called, after the eeprom values are changed. +This function changes and initializes a new extruder. This is also called, after the eeprom values are changed. */ void Extruder::selectExtruderById(uint8_t extruderId) { @@ -520,10 +574,14 @@ void Extruder::selectExtruderById(uint8_t extruderId) activeMixingExtruder = extruderId; for(uint8_t i = 0; i < NUM_EXTRUDER; i++) Extruder::setMixingWeight(i, extruder[i].virtualWeights[extruderId]); + Com::printFLN(PSTR("SelectExtruder:"),static_cast(extruderId)); extruderId = 0; #endif if(extruderId >= NUM_EXTRUDER) extruderId = 0; +#if !MIXING_EXTRUDER + Com::printFLN(PSTR("SelectExtruder:"),static_cast(extruderId)); +#endif #if NUM_EXTRUDER > 1 && MIXING_EXTRUDER == 0 bool executeSelect = false; if(extruderId != Extruder::current->id) @@ -536,19 +594,23 @@ void Extruder::selectExtruderById(uint8_t extruderId) Extruder::current->extrudePosition = Printer::currentPositionSteps[E_AXIS]; Extruder::current = &extruder[extruderId]; #ifdef SEPERATE_EXTRUDER_POSITIONS - // Use seperate extruder positions only if beeing told. Slic3r e.g. creates a continuous extruder position increment + // Use separate extruder positions only if being told. Slic3r e.g. creates a continuous extruder position increment Printer::currentPositionSteps[E_AXIS] = Extruder::current->extrudePosition; #endif - Printer::destinationSteps[E_AXIS] = Printer::currentPositionSteps[E_AXIS]; - Printer::axisStepsPerMM[E_AXIS] = Extruder::current->stepsPerMM; - Printer::invAxisStepsPerMM[E_AXIS] = 1.0f / Printer::axisStepsPerMM[E_AXIS]; + #if MIXING_EXTRUDER + recomputeMixingExtruderSteps(); + #else + Printer::destinationSteps[E_AXIS] = Printer::currentPositionSteps[E_AXIS]; + Printer::axisStepsPerMM[E_AXIS] = Extruder::current->stepsPerMM; + Printer::invAxisStepsPerMM[E_AXIS] = 1.0f / Printer::axisStepsPerMM[E_AXIS]; + #endif Printer::maxFeedrate[E_AXIS] = Extruder::current->maxFeedrate; // max_start_speed_units_per_second[E_AXIS] = Extruder::current->maxStartFeedrate; Printer::maxAccelerationMMPerSquareSecond[E_AXIS] = Printer::maxTravelAccelerationMMPerSquareSecond[E_AXIS] = Extruder::current->maxAcceleration; Printer::maxTravelAccelerationStepsPerSquareSecond[E_AXIS] = Printer::maxPrintAccelerationStepsPerSquareSecond[E_AXIS] = Printer::maxAccelerationMMPerSquareSecond[E_AXIS] * Printer::axisStepsPerMM[E_AXIS]; #if USE_ADVANCE - Printer::maxExtruderSpeed = (uint8_t)floor(HAL::maxExtruderTimerFrequency() / (Extruder::current->maxFeedrate*Extruder::current->stepsPerMM)); + Printer::maxExtruderSpeed = (ufast8_t)floor(HAL::maxExtruderTimerFrequency() / (Extruder::current->maxFeedrate * Extruder::current->stepsPerMM)); #if CPU_ARCH == ARCH_ARM if(Printer::maxExtruderSpeed > 40) Printer::maxExtruderSpeed = 40; #else @@ -581,9 +643,25 @@ void Extruder::selectExtruderById(uint8_t extruderId) #endif #endif } +#if MIXING_EXTRUDER + void Extruder::recomputeMixingExtruderSteps() { + int32_t sum_w = 0; + float sum = 0; + for(fast8_t i = 0; i < NUM_EXTRUDER; i++) { + sum_w += extruder[i].mixingW; + sum += extruder[i].stepsPerMM * extruder[i].mixingW; + } + sum /= sum_w; + Printer::currentPositionSteps[E_AXIS] = Printer::currentPositionSteps[E_AXIS] * sum / Printer::axisStepsPerMM[E_AXIS]; // reposition according resolution change + Printer::destinationSteps[E_AXIS] = Printer::currentPositionSteps[E_AXIS]; + Printer::axisStepsPerMM[E_AXIS] = sum; + Printer::invAxisStepsPerMM[E_AXIS] = 1.0f / Printer::axisStepsPerMM[E_AXIS]; + } +#endif void Extruder::setTemperatureForExtruder(float temperatureInCelsius, uint8_t extr, bool beep, bool wait) { +#if NUM_EXTRUDER > 0 #if MIXING_EXTRUDER extr = 0; // map any virtual extruder number to 0 #endif // MIXING_EXTRUDER @@ -608,13 +686,15 @@ void Extruder::setTemperatureForExtruder(float temperatureInCelsius, uint8_t ext if(Extruder::dittoMode && extr == 0) { TemperatureController *tc2 = tempController[1]; - tc2->setTargetTemperature(temperatureInCelsius); + tc2->setTargetTemperature(temperatureInCelsius); + tc2->updateTempControlVars(); if(temperatureInCelsius >= EXTRUDER_FAN_COOL_TEMP) extruder[1].coolerPWM = extruder[1].coolerSpeed; #if NUM_EXTRUDER > 2 if(Extruder::dittoMode > 1 && extr == 0) { TemperatureController *tc2 = tempController[2]; tc2->setTargetTemperature(temperatureInCelsius); + tc2->updateTempControlVars(); if(temperatureInCelsius >= EXTRUDER_FAN_COOL_TEMP) extruder[2].coolerPWM = extruder[2].coolerSpeed; } #endif @@ -623,6 +703,7 @@ void Extruder::setTemperatureForExtruder(float temperatureInCelsius, uint8_t ext { TemperatureController *tc2 = tempController[3]; tc2->setTargetTemperature(temperatureInCelsius); + tc2->updateTempControlVars(); if(temperatureInCelsius >= EXTRUDER_FAN_COOL_TEMP) extruder[3].coolerPWM = extruder[3].coolerSpeed; } #endif @@ -635,7 +716,7 @@ void Extruder::setTemperatureForExtruder(float temperatureInCelsius, uint8_t ext ) { Extruder *actExtruder = &extruder[extr]; - UI_STATUS_UPD(UI_TEXT_HEATING_EXTRUDER); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_HEATING_EXTRUDER_ID)); EVENT_WAITING_HEATER(actExtruder->id); bool dirRising = actExtruder->tempControl.targetTemperature > actExtruder->tempControl.currentTemperature; millis_t printedTime = HAL::timeInMilliseconds(); @@ -695,7 +776,8 @@ void Extruder::setTemperatureForExtruder(float temperatureInCelsius, uint8_t ext Printer::msecondsPrinting = HAL::timeInMilliseconds(); Printer::filamentPrinted = 0; // new print, new counter Printer::flag2 &= ~PRINTER_FLAG2_RESET_FILAMENT_USAGE; - } + } +#endif } void Extruder::setHeatedBedTemperature(float temperatureInCelsius,bool beep) @@ -708,9 +790,9 @@ void Extruder::setHeatedBedTemperature(float temperatureInCelsius,bool beep) if(beep && temperatureInCelsius>30) heatedBedController.setAlarm(true); Com::printFLN(Com::tTargetBedColon,heatedBedController.targetTemperatureC,0); if(temperatureInCelsius > 15) - pwm_pos[NUM_EXTRUDER + 1] = 255; // turn on the mainboard cooling fan + pwm_pos[PWM_BOARD_FAN] = 255; // turn on the mainboard cooling fan else if(Printer::areAllSteppersDisabled()) - pwm_pos[NUM_EXTRUDER + 1] = 0; // turn off the mainboard cooling fan only if steppers disabled + pwm_pos[PWM_BOARD_FAN] = 0; // turn off the mainboard cooling fan only if steppers disabled #endif } @@ -737,7 +819,46 @@ void Extruder::setMixingWeight(uint8_t extr,int weight) } } void Extruder::step() -{ +{ + if(PrintLine::cur != NULL && PrintLine::cur->isAllEMotors()) { +#if NUM_EXTRUDER > 0 + WRITE(EXT0_STEP_PIN, START_STEP_WITH_HIGH); +#if EXTRUDER_JAM_CONTROL && defined(EXT0_JAM_PIN) && EXT0_JAM_PIN > -1 + TEST_EXTRUDER_JAM(0) +#endif +#endif +#if NUM_EXTRUDER > 1 + WRITE(EXT1_STEP_PIN, START_STEP_WITH_HIGH); +#if EXTRUDER_JAM_CONTROL && defined(EXT1_JAM_PIN) && EXT1_JAM_PIN > -1 + TEST_EXTRUDER_JAM(1) +#endif +#endif +#if NUM_EXTRUDER > 2 + WRITE(EXT2_STEP_PIN, START_STEP_WITH_HIGH); +#if EXTRUDER_JAM_CONTROL && defined(EXT2_JAM_PIN) && EXT2_JAM_PIN > -1 + TEST_EXTRUDER_JAM(2) +#endif +#endif +#if NUM_EXTRUDER > 3 + WRITE(EXT3_STEP_PIN, START_STEP_WITH_HIGH); +#if EXTRUDER_JAM_CONTROL && defined(EXT3_JAM_PIN) && EXT3_JAM_PIN > -1 + TEST_EXTRUDER_JAM(3) +#endif +#endif +#if NUM_EXTRUDER > 4 + WRITE(EXT4_STEP_PIN, START_STEP_WITH_HIGH); +#if EXTRUDER_JAM_CONTROL && defined(EXT4_JAM_PIN) && EXT4_JAM_PIN > -1 + TEST_EXTRUDER_JAM(4) +#endif +#endif +#if NUM_EXTRUDER > 5 + WRITE(EXT5_STEP_PIN, START_STEP_WITH_HIGH); +#if EXTRUDER_JAM_CONTROL && defined(EXT5_JAM_PIN) && EXT5_JAM_PIN > -1 + TEST_EXTRUDER_JAM(5) +#endif +#endif + return; + } uint8_t best = 255,i; int bestError; if(mixingDir) @@ -775,7 +896,7 @@ void Extruder::step() #if NUM_EXTRUDER > 0 if(best == 0) { - WRITE(EXT0_STEP_PIN, HIGH); + WRITE(EXT0_STEP_PIN, START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT0_JAM_PIN) && EXT0_JAM_PIN > -1 TEST_EXTRUDER_JAM(0) #endif @@ -784,7 +905,7 @@ void Extruder::step() #if NUM_EXTRUDER > 1 if(best == 1) { - WRITE(EXT1_STEP_PIN, HIGH); + WRITE(EXT1_STEP_PIN, START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT1_JAM_PIN) && EXT1_JAM_PIN > -1 TEST_EXTRUDER_JAM(1) #endif @@ -793,7 +914,7 @@ void Extruder::step() #if NUM_EXTRUDER > 2 if(best == 2) { - WRITE(EXT2_STEP_PIN, HIGH); + WRITE(EXT2_STEP_PIN, START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT2_JAM_PIN) && EXT2_JAM_PIN > -1 TEST_EXTRUDER_JAM(2) #endif @@ -802,7 +923,7 @@ void Extruder::step() #if NUM_EXTRUDER > 3 if(best == 3) { - WRITE(EXT3_STEP_PIN, HIGH); + WRITE(EXT3_STEP_PIN, START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT3_JAM_PIN) && EXT3_JAM_PIN > -1 TEST_EXTRUDER_JAM(3) #endif @@ -811,7 +932,7 @@ void Extruder::step() #if NUM_EXTRUDER > 4 if(best == 4) { - WRITE(EXT4_STEP_PIN, HIGH); + WRITE(EXT4_STEP_PIN, START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT4_JAM_PIN) && EXT4_JAM_PIN > -1 TEST_EXTRUDER_JAM(4) #endif @@ -820,7 +941,7 @@ void Extruder::step() #if NUM_EXTRUDER > 5 if(best == 5) { - WRITE(EXT5_STEP_PIN, HIGH); + WRITE(EXT5_STEP_PIN, START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT5_JAM_PIN) && EXT5_JAM_PIN > -1 TEST_EXTRUDER_JAM(5) #endif @@ -831,22 +952,22 @@ void Extruder::step() void Extruder::unstep() { #if NUM_EXTRUDER > 0 - WRITE(EXT0_STEP_PIN, LOW); + WRITE(EXT0_STEP_PIN, !START_STEP_WITH_HIGH); #endif #if NUM_EXTRUDER > 1 - WRITE(EXT1_STEP_PIN, LOW); + WRITE(EXT1_STEP_PIN, !START_STEP_WITH_HIGH); #endif #if NUM_EXTRUDER > 2 - WRITE(EXT2_STEP_PIN, LOW); + WRITE(EXT2_STEP_PIN, !START_STEP_WITH_HIGH); #endif #if NUM_EXTRUDER > 3 - WRITE(EXT3_STEP_PIN, LOW); + WRITE(EXT3_STEP_PIN, !START_STEP_WITH_HIGH); #endif #if NUM_EXTRUDER > 4 - WRITE(EXT4_STEP_PIN, LOW); + WRITE(EXT4_STEP_PIN, !START_STEP_WITH_HIGH); #endif #if NUM_EXTRUDER > 5 - WRITE(EXT5_STEP_PIN, LOW); + WRITE(EXT5_STEP_PIN, !START_STEP_WITH_HIGH); #endif } @@ -925,7 +1046,7 @@ Call this function only, if interrupts are disabled. void Extruder::step() { #if NUM_EXTRUDER == 1 - WRITE(EXT0_STEP_PIN, HIGH); + WRITE(EXT0_STEP_PIN, START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT0_JAM_PIN) && EXT0_JAM_PIN > -1 TEST_EXTRUDER_JAM(0) #endif @@ -934,21 +1055,21 @@ void Extruder::step() { case 0: #if NUM_EXTRUDER > 0 - WRITE(EXT0_STEP_PIN,HIGH); + WRITE(EXT0_STEP_PIN,START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT0_JAM_PIN) && EXT0_JAM_PIN > -1 TEST_EXTRUDER_JAM(0) #endif #if FEATURE_DITTO_PRINTING if(Extruder::dittoMode) { - WRITE(EXT1_STEP_PIN,HIGH); + WRITE(EXT1_STEP_PIN,START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT1_JAM_PIN) && EXT1_JAM_PIN > -1 TEST_EXTRUDER_JAM(1) #endif #if NUM_EXTRUDER > 2 if(Extruder::dittoMode > 1) { - WRITE(EXT2_STEP_PIN,HIGH); + WRITE(EXT2_STEP_PIN,START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT2_JAM_PIN) && EXT2_JAM_PIN > -1 TEST_EXTRUDER_JAM(2) #endif @@ -957,7 +1078,7 @@ void Extruder::step() #if NUM_EXTRUDER > 3 if(Extruder::dittoMode > 2) { - WRITE(EXT3_STEP_PIN,HIGH); + WRITE(EXT3_STEP_PIN,START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT3_JAM_PIN) && EXT3_JAM_PIN > -1 TEST_EXTRUDER_JAM(3) #endif @@ -969,7 +1090,7 @@ void Extruder::step() break; #if defined(EXT1_STEP_PIN) && NUM_EXTRUDER > 1 case 1: - WRITE(EXT1_STEP_PIN,HIGH); + WRITE(EXT1_STEP_PIN,START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT1_JAM_PIN) && EXT1_JAM_PIN > -1 TEST_EXTRUDER_JAM(1) #endif @@ -977,7 +1098,7 @@ void Extruder::step() #endif #if defined(EXT2_STEP_PIN) && NUM_EXTRUDER > 2 case 2: - WRITE(EXT2_STEP_PIN,HIGH); + WRITE(EXT2_STEP_PIN,START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT2_JAM_PIN) && EXT2_JAM_PIN > -1 TEST_EXTRUDER_JAM(2) #endif @@ -985,7 +1106,7 @@ void Extruder::step() #endif #if defined(EXT3_STEP_PIN) && NUM_EXTRUDER > 3 case 3: - WRITE(EXT3_STEP_PIN,HIGH); + WRITE(EXT3_STEP_PIN,START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT3_JAM_PIN) && EXT3_JAM_PIN > -1 TEST_EXTRUDER_JAM(3) #endif @@ -993,7 +1114,7 @@ void Extruder::step() #endif #if defined(EXT4_STEP_PIN) && NUM_EXTRUDER > 4 case 4: - WRITE(EXT4_STEP_PIN,HIGH); + WRITE(EXT4_STEP_PIN,START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT4_JAM_PIN) && EXT4_JAM_PIN > -1 TEST_EXTRUDER_JAM(4) #endif @@ -1001,7 +1122,7 @@ void Extruder::step() #endif #if defined(EXT5_STEP_PIN) && NUM_EXTRUDER > 5 case 5: - WRITE(EXT5_STEP_PIN,HIGH); + WRITE(EXT5_STEP_PIN,START_STEP_WITH_HIGH); #if EXTRUDER_JAM_CONTROL && defined(EXT5_JAM_PIN) && EXT5_JAM_PIN > -1 TEST_EXTRUDER_JAM(5) #endif @@ -1019,27 +1140,27 @@ Call this function only, if interrupts are disabled. void Extruder::unstep() { #if NUM_EXTRUDER == 1 - WRITE(EXT0_STEP_PIN,LOW); + WRITE(EXT0_STEP_PIN,!START_STEP_WITH_HIGH); #else switch(Extruder::current->id) { case 0: #if NUM_EXTRUDER > 0 - WRITE(EXT0_STEP_PIN,LOW); + WRITE(EXT0_STEP_PIN,!START_STEP_WITH_HIGH); #if FEATURE_DITTO_PRINTING if(Extruder::dittoMode) { - WRITE(EXT1_STEP_PIN,LOW); + WRITE(EXT1_STEP_PIN,!START_STEP_WITH_HIGH); #if NUM_EXTRUDER > 2 if(Extruder::dittoMode > 1) { - WRITE(EXT2_STEP_PIN,LOW); + WRITE(EXT2_STEP_PIN,!START_STEP_WITH_HIGH); } #endif #if NUM_EXTRUDER > 3 if(Extruder::dittoMode > 2) { - WRITE(EXT3_STEP_PIN,LOW); + WRITE(EXT3_STEP_PIN,!START_STEP_WITH_HIGH); } #endif // NUM_EXTRUDER > 3 } @@ -1048,27 +1169,27 @@ void Extruder::unstep() break; #if defined(EXT1_STEP_PIN) && NUM_EXTRUDER > 1 case 1: - WRITE(EXT1_STEP_PIN,LOW); + WRITE(EXT1_STEP_PIN,!START_STEP_WITH_HIGH); break; #endif #if defined(EXT2_STEP_PIN) && NUM_EXTRUDER > 2 case 2: - WRITE(EXT2_STEP_PIN,LOW); + WRITE(EXT2_STEP_PIN,!START_STEP_WITH_HIGH); break; #endif #if defined(EXT3_STEP_PIN) && NUM_EXTRUDER > 3 case 3: - WRITE(EXT3_STEP_PIN,LOW); + WRITE(EXT3_STEP_PIN,!START_STEP_WITH_HIGH); break; #endif #if defined(EXT4_STEP_PIN) && NUM_EXTRUDER > 4 case 4: - WRITE(EXT4_STEP_PIN,LOW); + WRITE(EXT4_STEP_PIN,!START_STEP_WITH_HIGH); break; #endif #if defined(EXT5_STEP_PIN) && NUM_EXTRUDER > 5 case 5: - WRITE(EXT5_STEP_PIN,LOW); + WRITE(EXT5_STEP_PIN,!START_STEP_WITH_HIGH); break; #endif } @@ -1283,7 +1404,7 @@ const short temptable_4[NUMTEMPS_4][2] PROGMEM = {478*4, 46*8},{531*4, 41*8},{584*4, 35*8},{637*4, 30*8},{690*4, 25*8},{743*4, 20*8},{796*4, 14*8},{849*4, 7*8},{902*4, 0*8}, {955*4, -11*8},{1008*4, -35*8} }; - +// ATC 104GT #define NUMTEMPS_8 34 const short temptable_8[NUMTEMPS_8][2] PROGMEM = { @@ -1325,6 +1446,12 @@ const short temptable_12[NUMTEMPS_12][2] PROGMEM = {351*4, 140*8},{386*4, 134*8},{421*4, 128*8},{456*4, 122*8},{491*4, 117*8},{526*4, 112*8},{561*4, 107*8},{596*4, 102*8},{631*4, 97*8},{666*4, 91*8}, {701*4, 86*8},{736*4, 81*8},{771*4, 76*8},{806*4, 70*8},{841*4, 63*8},{876*4, 56*8},{911*4, 48*8},{946*4, 38*8},{981*4, 23*8},{1005*4, 5*8},{1016*4, 0*8} }; +#define NUMTEMPS_13 19 +const short temptable_13[NUMTEMPS_13][2] PROGMEM = +{ + {0,0},{908,8},{942,10*8},{982,20*8},{1015,8*30},{1048,8*40},{1080,8*50},{1113,8*60},{1146,8*70},{1178,8*80},{1211,8*90},{1276,8*110},{1318,8*120} + ,{1670,8*230},{2455,8*500},{3445,8*900},{3666,8*1000},{3871,8*1100},{4095,8*2000} +}; #if NUM_TEMPS_USERTHERMISTOR0 > 0 const short temptable_5[NUM_TEMPS_USERTHERMISTOR0][2] PROGMEM = USER_THERMISTORTABLE0 ; #endif @@ -1334,7 +1461,7 @@ const short temptable_6[NUM_TEMPS_USERTHERMISTOR1][2] PROGMEM = USER_THERMISTORT #if NUM_TEMPS_USERTHERMISTOR2 > 0 const short temptable_7[NUM_TEMPS_USERTHERMISTOR2][2] PROGMEM = USER_THERMISTORTABLE2 ; #endif -const short * const temptables[12] PROGMEM = {(short int *)&temptable_1[0][0],(short int *)&temptable_2[0][0],(short int *)&temptable_3[0][0],(short int *)&temptable_4[0][0] +const short * const temptables[13] PROGMEM = {(short int *)&temptable_1[0][0],(short int *)&temptable_2[0][0],(short int *)&temptable_3[0][0],(short int *)&temptable_4[0][0] #if NUM_TEMPS_USERTHERMISTOR0 > 0 ,(short int *)&temptable_5[0][0] #else @@ -1355,9 +1482,10 @@ const short * const temptables[12] PROGMEM = {(short int *)&temptable_1[0][0],(s ,(short int *)&temptable_10[0][0] ,(short int *)&temptable_11[0][0] ,(short int *)&temptable_12[0][0] + ,(short int *)&temptable_13[0][0] }; -const uint8_t temptables_num[12] PROGMEM = {NUMTEMPS_1,NUMTEMPS_2,NUMTEMPS_3,NUMTEMPS_4,NUM_TEMPS_USERTHERMISTOR0,NUM_TEMPS_USERTHERMISTOR1,NUM_TEMPS_USERTHERMISTOR2,NUMTEMPS_8, - NUMTEMPS_9,NUMTEMPS_10,NUMTEMPS_11,NUMTEMPS_12 +const uint8_t temptables_num[13] PROGMEM = {NUMTEMPS_1,NUMTEMPS_2,NUMTEMPS_3,NUMTEMPS_4,NUM_TEMPS_USERTHERMISTOR0,NUM_TEMPS_USERTHERMISTOR1,NUM_TEMPS_USERTHERMISTOR2,NUMTEMPS_8, + NUMTEMPS_9,NUMTEMPS_10,NUMTEMPS_11,NUMTEMPS_12,NUMTEMPS_13 }; @@ -1370,7 +1498,7 @@ void TemperatureController::updateCurrentTemperature() case 0: currentTemperature = 25; break; -#if ANALOG_INPUTS>0 +#if ANALOG_INPUTS > 0 case 1: case 2: case 3: @@ -1388,12 +1516,13 @@ void TemperatureController::updateCurrentTemperature() case 99: currentTemperature = (1023 << (2 - ANALOG_REDUCE_BITS)) - (osAnalogInputValues[sensorPin] >> (ANALOG_REDUCE_BITS)); // Convert to 10 bit result break; + case 13: // PT100 E3D case 50: // User defined PTC table case 51: case 52: case 60: // HEATER_USES_AD8495 (Delivers 5mV/degC) case 61: // HEATER_USES_AD8495 (Delivers 5mV/degC) 1.25v offset - case 100: // AD595 + case 100: // AD595 / AD597 currentTemperature = (osAnalogInputValues[sensorPin] >> (ANALOG_REDUCE_BITS)); break; #endif @@ -1431,14 +1560,14 @@ void TemperatureController::updateCurrentTemperature() case 12: { type--; - uint8_t num = pgm_read_byte(&temptables_num[type])<<1; - uint8_t i=2; - const short *temptable = (const short *)pgm_read_word(&temptables[type]); //pgm_read_word_near(&temptables[type]); - short oldraw = pgm_read_word(&temptable[0]); - short oldtemp = pgm_read_word(&temptable[1]); - short newraw,newtemp; - currentTemperature = (1023<<(2-ANALOG_REDUCE_BITS))-currentTemperature; - while(i 49) + type -= 46; + else + type--; + uint8_t num = pgm_read_byte(&temptables_num[type]) << 1; + uint8_t i = 2; + const int16_t *temptable = (const int16_t *)pgm_read_word(&temptables[type]); //pgm_read_word_near(&temptables[type]); + int16_t oldraw = pgm_read_word(&temptable[0]); + int16_t oldtemp = pgm_read_word(&temptable[1]); + int16_t newraw,newtemp = 0; + while(i < num) { newraw = pgm_read_word(&temptable[i++]); newtemp = pgm_read_word(&temptable[i++]); @@ -1497,12 +1630,16 @@ void TemperatureController::updateCurrentTemperature() currentTemperatureC = ((float)currentTemperature * 660.0f / (1024 << (2 - ANALOG_REDUCE_BITS))) - 250.0f; #endif break; - case 100: // AD595 + case 100: // AD595 / AD597 10mV/°C //return (int)((long)raw_temp * 500/(1024<<(2-ANALOG_REDUCE_BITS))); #if CPU_ARCH == ARCH_AVR currentTemperatureC = ((float)currentTemperature * 500.0f / (1024 << (2 - ANALOG_REDUCE_BITS))); +#else +#if FEATURE_CONTROLLER == CONTROLLER_LCD_MP_PHARAOH_DUE + currentTemperatureC = ((float)currentTemperature * 500.0f / (1024 << (2 - ANALOG_REDUCE_BITS))); #else currentTemperatureC = ((float)currentTemperature * 330.0f / (1024 << (2 - ANALOG_REDUCE_BITS))); +#endif #endif break; #ifdef SUPPORT_MAX6675 @@ -1607,24 +1744,28 @@ void TemperatureController::setTargetTemperature(float target) targetTemperature = (1023<<(2-ANALOG_REDUCE_BITS))-newraw; break; } + case 13: // PT100 E3D case 50: // user defined PTC thermistor case 51: case 52: { - type -= 46; + if(type > 49) + type -= 46; + else + type--; uint8_t num = pgm_read_byte(&temptables_num[type]) << 1; uint8_t i = 2; const short *temptable = (const short *)pgm_read_word(&temptables[type]); //pgm_read_word(&temptables[type]); short oldraw = pgm_read_word(&temptable[0]); short oldtemp = pgm_read_word(&temptable[1]); short newraw = 0,newtemp; - while(i temp) { - targetTemperature = oldraw + (int32_t)(oldtemp-temp) * (int32_t)(oldraw-newraw) / (oldtemp-newtemp); + targetTemperature = oldraw + (int32_t)(oldtemp - temp) * (int32_t)(oldraw - newraw) / (oldtemp-newtemp); return; } oldtemp = newtemp; @@ -1694,14 +1835,16 @@ void TemperatureController::setTargetTemperature(float target) uint8_t autotuneIndex = 255; void Extruder::disableAllHeater() -{ - for(uint8_t i=0; i 0 + for(uint8_t i = 0; i < NUM_TEMPERATURE_LOOPS; i++) { TemperatureController *c = tempController[i]; c->targetTemperature = 0; c->targetTemperatureC = 0; pwm_pos[c->pwmIndex] = 0; - } + } +#endif autotuneIndex = 255; } @@ -1862,7 +2005,8 @@ void writeMonitor() } bool reportTempsensorError() -{ +{ +#if NUM_TEMPERATURE_LOOPS > 0 if(!Printer::isAnyTempsensorDefect()) return false; for(uint8_t i = 0; i < NUM_TEMPERATURE_LOOPS; i++) { @@ -1875,20 +2019,29 @@ bool reportTempsensorError() Com::printFLN(Com::tTempSensorWorking); } Com::printErrorFLN(Com::tDryModeUntilRestart); - return true; + return true; +#else + return false; +#endif } #ifdef SUPPORT_MAX6675 + int16_t read_max6675(uint8_t ss_pin) { - int16_t max6675_temp = 0; - HAL::spiInit(2); - HAL::digitalWrite(ss_pin, 0); // enable TT_MAX6675 - HAL::delayMicroseconds(1); // ensure 100ns delay - a bit extra is fine - max6675_temp = HAL::spiReceive(0); - max6675_temp <<= 8; - max6675_temp |= HAL::spiReceive(0); - HAL::digitalWrite(ss_pin, 1); // disable TT_MAX6675 + static millis_t last_max6675_read = 0; + static int16_t max6675_temp = 0; + if (HAL::timeInMilliseconds() - last_max6675_read > 230) + { + HAL::spiInit(2); + HAL::digitalWrite(ss_pin, 0); // enable TT_MAX6675 + HAL::delayMicroseconds(1); // ensure 100ns delay - a bit extra is fine + max6675_temp = HAL::spiReceive(0); + max6675_temp <<= 8; + max6675_temp |= HAL::spiReceive(0); + HAL::digitalWrite(ss_pin, 1); // disable TT_MAX6675 + last_max6675_read = HAL::timeInMilliseconds(); + } return max6675_temp & 4 ? 2000 : max6675_temp >> 3; // thermocouple open? } #endif @@ -1934,7 +2087,13 @@ void Extruder::retractDistance(float dist) int32_t distance = static_cast(dist * stepsPerMM / Printer::extrusionFactor); int32_t oldEPos = Printer::currentPositionSteps[E_AXIS]; float speed = distance > 0 ? EEPROM_FLOAT(RETRACTION_SPEED) : EEPROM_FLOAT(RETRACTION_UNDO_SPEED); +#if MIXING_EXTRUDER + Printer::setAllEMotors(true); +#endif PrintLine::moveRelativeDistanceInSteps(0, 0, 0, -distance, RMath::max(speed, 1.f), false, false); +#if MIXING_EXTRUDER + Printer::setAllEMotors(false); +#endif Printer::currentPositionSteps[E_AXIS] = oldEPos; // restore previous extruder position Printer::feedrate = oldFeedrate; } @@ -1942,27 +2101,28 @@ void Extruder::retractDistance(float dist) void Extruder::retract(bool isRetract,bool isLong) { float oldFeedrate = Printer::feedrate; - float distance = (isLong ? EEPROM_FLOAT( RETRACTION_LONG_LENGTH) : EEPROM_FLOAT(RETRACTION_LENGTH)); - int32_t zlift = static_cast(EEPROM_FLOAT(RETRACTION_Z_LIFT) * Printer::axisStepsPerMM[Z_AXIS]); - int32_t oldZPos = Printer::currentPositionSteps[Z_AXIS]; - float oldZPosF = Printer::currentPosition[Z_AXIS]; + float distance = (isLong ? EEPROM_FLOAT( RETRACTION_LONG_LENGTH) : EEPROM_FLOAT(RETRACTION_LENGTH)); + float zLiftF = EEPROM_FLOAT(RETRACTION_Z_LIFT); + int32_t zlift = static_cast(zLiftF * Printer::axisStepsPerMM[Z_AXIS]); if(isRetract && !isRetracted()) { retractDistance(distance); setRetracted(true); - if(zlift > 0) - PrintLine::moveRelativeDistanceInStepsReal(0,0,zlift,0,Printer::maxFeedrate[Z_AXIS], false); + if(zlift > 0) { + PrintLine::moveRelativeDistanceInStepsReal(0,0,zlift,0,Printer::maxFeedrate[Z_AXIS], false); + Printer::coordinateOffset[Z_AXIS] -= zLiftF; + } } else if(!isRetract && isRetracted()) { distance += (isLong ? EEPROM_FLOAT(RETRACTION_UNDO_EXTRA_LONG_LENGTH) : EEPROM_FLOAT(RETRACTION_UNDO_EXTRA_LENGTH) ); - if(zlift > 0) - PrintLine::moveRelativeDistanceInStepsReal(0,0,-zlift,0,Printer::maxFeedrate[Z_AXIS], false); + if(zlift > 0) { + PrintLine::moveRelativeDistanceInStepsReal(0,0,-zlift,0,Printer::maxFeedrate[Z_AXIS], false); + Printer::coordinateOffset[Z_AXIS] += zLiftF; + } retractDistance(-distance); setRetracted(false); } - Printer::currentPositionSteps[Z_AXIS] = oldZPos; // z lift should have no visible impact - Printer::currentPosition[Z_AXIS] = oldZPosF; Printer::feedrate = oldFeedrate; } #endif @@ -2165,45 +2325,55 @@ Extruder extruder[NUM_EXTRUDER] = #endif // NUM_EXTRUDER #if HAVE_HEATED_BED -#define NUM_TEMPERATURE_LOOPS NUM_EXTRUDER+1 -TemperatureController heatedBedController = {NUM_EXTRUDER,HEATED_BED_SENSOR_TYPE,BED_SENSOR_INDEX,0,0,0,0,0,HEATED_BED_HEAT_MANAGER +TemperatureController heatedBedController = {PWM_HEATED_BED,HEATED_BED_SENSOR_TYPE,BED_SENSOR_INDEX,0,0,0,0,0,HEATED_BED_HEAT_MANAGER #if TEMP_PID ,0,HEATED_BED_PID_INTEGRAL_DRIVE_MAX,HEATED_BED_PID_INTEGRAL_DRIVE_MIN,HEATED_BED_PID_PGAIN_OR_DEAD_TIME,HEATED_BED_PID_IGAIN,HEATED_BED_PID_DGAIN,HEATED_BED_PID_MAX,0,0,0,{0,0,0,0} #endif - ,0,0,0,HEATED_BED_DECOUPLE_TEST_PERIOD - }; -#else -#define NUM_TEMPERATURE_LOOPS NUM_EXTRUDER + ,0,0,0,HEATED_BED_DECOUPLE_TEST_PERIOD}; #endif - + +#if FAN_THERMO_PIN > -1 +TemperatureController thermoController = {PWM_FAN_THERMO,FAN_THERMO_THERMISTOR_TYPE,THERMO_ANALOG_INDEX,0,0,0,0,0,0 + #if TEMP_PID + ,0,255,0,10,1,1,255,0,0,0,{0,0,0,0} + #endif +,0,0,0,0}; +#endif + +#if NUM_TEMPERATURE_LOOPS > 0 TemperatureController *tempController[NUM_TEMPERATURE_LOOPS] = { -#if NUM_EXTRUDER>0 +#if NUM_EXTRUDER > 0 &extruder[0].tempControl #endif -#if NUM_EXTRUDER>1 +#if NUM_EXTRUDER > 1 ,&extruder[1].tempControl #endif -#if NUM_EXTRUDER>2 +#if NUM_EXTRUDER > 2 ,&extruder[2].tempControl #endif -#if NUM_EXTRUDER>3 +#if NUM_EXTRUDER > 3 ,&extruder[3].tempControl #endif -#if NUM_EXTRUDER>4 +#if NUM_EXTRUDER > 4 ,&extruder[4].tempControl #endif -#if NUM_EXTRUDER>5 +#if NUM_EXTRUDER > 5 ,&extruder[5].tempControl #endif #if HAVE_HEATED_BED -#if NUM_EXTRUDER==0 +#if NUM_EXTRUDER == 0 &heatedBedController #else ,&heatedBedController #endif #endif +#if FAN_THERMO_PIN > -1 +#if NUM_EXTRUDER == 0 && !HAVE_HEATED_BED + &thermoController +#else + ,&thermoController +#endif +#endif // FAN_THERMO_PIN }; - - - +#endif diff --git a/Repetier/Extruder.h b/Repetier/Extruder.h index 62280cb..29627b5 100644 --- a/Repetier/Extruder.h +++ b/Repetier/Extruder.h @@ -147,7 +147,8 @@ public: class Extruder; extern Extruder extruder[]; -#if EXTRUDER_JAM_CONTROL +#if EXTRUDER_JAM_CONTROL +#if JAM_METHOD == 1 #define _TEST_EXTRUDER_JAM(x,pin) {\ uint8_t sig = READ(pin);extruder[x].jamStepsSinceLastSignal += extruder[x].jamLastDir;\ if(extruder[x].jamLastSignal != sig && abs(extruder[x].jamStepsSinceLastSignal - extruder[x].jamLastChangeAt) > JAM_MIN_STEPS) {\ @@ -156,10 +157,23 @@ extern Extruder extruder[]; } else if(abs(extruder[x].jamStepsSinceLastSignal) > JAM_ERROR_STEPS && !Printer::isDebugJamOrDisabled() && !extruder[x].tempControl.isJammed()) \ extruder[x].tempControl.setJammed(true);\ } +#define RESET_EXTRUDER_JAM(x,dir) extruder[x].jamLastDir = dir ? 1 : -1; +#elif JAM_METHOD == 2 +#define _TEST_EXTRUDER_JAM(x,pin) {\ + uint8_t sig = READ(pin);\ + if(sig){extruder[x].tempControl.setJammed(true);} else if(!Printer::isDebugJamOrDisabled() && !extruder[x].tempControl.isJammed()) {extruder[x].resetJamSteps();}} +#define RESET_EXTRUDER_JAM(x,dir) +#elif JAM_METHOD == 3 +#define _TEST_EXTRUDER_JAM(x,pin) {\ + uint8_t sig = !READ(pin);\ + if(sig){extruder[x].tempControl.setJammed(true);} else if(!Printer::isDebugJamOrDisabled() && !extruder[x].tempControl.isJammed()) {extruder[x].resetJamSteps();}} +#define RESET_EXTRUDER_JAM(x,dir) +#else +#error Unknown value for JAM_METHOD +#endif #define ___TEST_EXTRUDER_JAM(x,y) _TEST_EXTRUDER_JAM(x,y) #define __TEST_EXTRUDER_JAM(x) ___TEST_EXTRUDER_JAM(x,EXT ## x ## _JAM_PIN) -#define TEST_EXTRUDER_JAM(x) __TEST_EXTRUDER_JAM(x) -#define RESET_EXTRUDER_JAM(x,dir) extruder[x].jamLastDir = dir ? 1 : -1; +#define TEST_EXTRUDER_JAM(x) __TEST_EXTRUDER_JAM(x) #else #define TEST_EXTRUDER_JAM(x) #define RESET_EXTRUDER_JAM(x,dir) @@ -184,10 +198,11 @@ public: static int mixingS; ///< Sum of all weights static uint8_t mixingDir; ///< Direction flag static uint8_t activeMixingExtruder; + static void recomputeMixingExtruderSteps(); #endif uint8_t id; int32_t xOffset; - int32_t yOffset; + int32_t yOffset; int32_t zOffset; float stepsPerMM; ///< Steps per mm. int8_t enablePin; ///< Pin to enable extruder stepper motor. @@ -274,19 +289,27 @@ public: }; #if HAVE_HEATED_BED -#define NUM_TEMPERATURE_LOOPS NUM_EXTRUDER+1 +#define HEATED_BED_INDEX NUM_EXTRUDER extern TemperatureController heatedBedController; #else -#define NUM_TEMPERATURE_LOOPS NUM_EXTRUDER +#define HEATED_BED_INDEX NUM_EXTRUDER-1 #endif +#if FAN_THERMO_PIN > -1 +#define THERMO_CONTROLLER_INDEX HEATED_BED_INDEX+1 +extern TemperatureController thermoController; +#else +#define THERMO_CONTROLLER_INDEX HEATED_BED_INDEX +#endif +#define NUM_TEMPERATURE_LOOPS THERMO_CONTROLLER_INDEX+1 + #define TEMP_INT_TO_FLOAT(temp) ((float)(temp)/(float)(1< 0 +extern TemperatureController *tempController[NUM_TEMPERATURE_LOOPS]; +#endif extern uint8_t autotuneIndex; #endif // EXTRUDER_H_INCLUDED - - diff --git a/Repetier/FatStructs.h b/Repetier/FatStructs.h index adac699..5713467 100644 --- a/Repetier/FatStructs.h +++ b/Repetier/FatStructs.h @@ -416,5 +416,3 @@ static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) { return (dir->attributes & DIR_ATT_VOLUME_ID) == 0; } #endif // FatStructs_h - - diff --git a/Repetier/HAL.cpp b/Repetier/HAL.cpp index 0f96086..f745431 100644 --- a/Repetier/HAL.cpp +++ b/Repetier/HAL.cpp @@ -1,1437 +1,1470 @@ -#include "Repetier.h" -#include - -#if ANALOG_INPUTS > 0 -uint8 osAnalogInputCounter[ANALOG_INPUTS]; -uint osAnalogInputBuildup[ANALOG_INPUTS]; -uint8 osAnalogInputPos = 0; // Current sampling position -#endif - -//extern "C" void __cxa_pure_virtual() { } - -HAL::HAL() -{ - //ctor -} - -HAL::~HAL() -{ - //dtor -} - -uint16_t HAL::integerSqrt(uint32_t a) -{ -// http://www.mikrocontroller.net/articles/AVR_Arithmetik#32_Bit_.2F_32_Bit -//----------------------------------------------------------- -// Fast and short 32 bits AVR sqrt routine, avr-gcc ABI compliant -// R25:R24 = SQRT (R25:R24:R23:R22) rounded to the -// nearest integer (0.5 rounds up) -// Destroys R18-R19,R22-R23,R26-R27 -// Cycles incl call & ret = 265-310 -// Stack incl call = 2-3 -//----------------------------------------------------------- - - uint16_t b; - - __asm__ __volatile__ ( - "ldi R19, 0xc0 \n\t" - "clr R18 \n\t" // rotation mask in R19:R18 - "ldi R27, 0x40 \n\t" - "sub R26, R26 \n\t" // developing sqrt in R27:R26, C=0 - "1: brcs 2f \n\t" // C --> Bit is always 1 - "cp %C1, R26 \n\t" - "cpc %D1, R27 \n\t" // Does test value fit? - "brcs 3f \n\t" // C --> nope, bit is 0 - "2: sub %C1, R26 \n\t" - "sbc %D1, R27 \n\t" // Adjust argument for next bit - "or R26, R18 \n\t" - "or R27, R19 \n\t" // Set bit to 1 - "3: lsr R19 \n\t" - "ror R18 \n\t" // Shift right mask, C --> end loop - "eor R27, R19 \n\t" - "eor R26, R18 \n\t" // Shift right only test bit in result - "rol %A1 \n\t" // Bit 0 only set if end of loop - "rol %B1 \n\t" - "rol %C1 \n\t" - "rol %D1 \n\t" // Shift left remaining argument (C used at 1:) - "sbrs %A1, 0 \n\t" // Skip if 15 bits developed - "rjmp 1b \n\t" // Develop 15 bits of the sqrt - "brcs 4f \n\t" // C--> Last bits always 1 - "cp R26, %C1 \n\t" - "cpc R27, %D1 \n\t" // Test for last bit 1 - "brcc 5f \n\t" // NC --> bit is 0 - "4: sbc %B1, R19 \n\t" // Subtract C (any value from 1 to 0x7f will do) - "sbc %C1, R26 \n\t" - "sbc %D1, R27 \n\t" // Update argument for test - "inc R26 \n\t" // Last bit is 1 - "5: lsl %B1 \n\t" // Only bit 7 matters - "rol %C1 \n\t" - "rol %D1 \n\t" // Remainder * 2 + C - "brcs 6f \n\t" // C --> Always round up - "cp R26, %C1 \n\t" - "cpc R27, %D1 \n\t" // C decides rounding - "6: adc R26, R19 \n\t" - "adc R27, R19 \n\t" // Round up if C (R19=0) - "mov %B0, R27 \n\t" // return in R25:R24 for avr-gcc ABI compliance - "mov %A0, R26 \n\t" - :"=r"(b) - :"r"(a) - :"r18","r19","r27","r26" ); - return b; -} - - - -const uint16_t fast_div_lut[17] PROGMEM = {0,F_CPU/4096,F_CPU/8192,F_CPU/12288,F_CPU/16384,F_CPU/20480,F_CPU/24576,F_CPU/28672,F_CPU/32768,F_CPU/36864 - ,F_CPU/40960,F_CPU/45056,F_CPU/49152,F_CPU/53248,F_CPU/57344,F_CPU/61440,F_CPU/65536 - }; - -const uint16_t slow_div_lut[257] PROGMEM = {0,0,0,0,0,0,0,0,F_CPU/256,F_CPU/288,F_CPU/320,F_CPU/352 - ,F_CPU/384,F_CPU/416,F_CPU/448,F_CPU/480,F_CPU/512,F_CPU/544,F_CPU/576,F_CPU/608,F_CPU/640,F_CPU/672,F_CPU/704,F_CPU/736,F_CPU/768,F_CPU/800,F_CPU/832 - ,F_CPU/864,F_CPU/896,F_CPU/928,F_CPU/960,F_CPU/992,F_CPU/1024,F_CPU/1056,F_CPU/1088,F_CPU/1120,F_CPU/1152,F_CPU/1184,F_CPU/1216,F_CPU/1248,F_CPU/1280,F_CPU/1312 - ,F_CPU/1344,F_CPU/1376,F_CPU/1408,F_CPU/1440,F_CPU/1472,F_CPU/1504,F_CPU/1536,F_CPU/1568,F_CPU/1600,F_CPU/1632,F_CPU/1664,F_CPU/1696,F_CPU/1728,F_CPU/1760,F_CPU/1792 - ,F_CPU/1824,F_CPU/1856,F_CPU/1888,F_CPU/1920,F_CPU/1952,F_CPU/1984,F_CPU/2016 - ,F_CPU/2048,F_CPU/2080,F_CPU/2112,F_CPU/2144,F_CPU/2176,F_CPU/2208,F_CPU/2240,F_CPU/2272,F_CPU/2304,F_CPU/2336,F_CPU/2368,F_CPU/2400 - ,F_CPU/2432,F_CPU/2464,F_CPU/2496,F_CPU/2528,F_CPU/2560,F_CPU/2592,F_CPU/2624,F_CPU/2656,F_CPU/2688,F_CPU/2720,F_CPU/2752,F_CPU/2784,F_CPU/2816,F_CPU/2848,F_CPU/2880 - ,F_CPU/2912,F_CPU/2944,F_CPU/2976,F_CPU/3008,F_CPU/3040,F_CPU/3072,F_CPU/3104,F_CPU/3136,F_CPU/3168,F_CPU/3200,F_CPU/3232,F_CPU/3264,F_CPU/3296,F_CPU/3328,F_CPU/3360 - ,F_CPU/3392,F_CPU/3424,F_CPU/3456,F_CPU/3488,F_CPU/3520,F_CPU/3552,F_CPU/3584,F_CPU/3616,F_CPU/3648,F_CPU/3680,F_CPU/3712,F_CPU/3744,F_CPU/3776,F_CPU/3808,F_CPU/3840 - ,F_CPU/3872,F_CPU/3904,F_CPU/3936,F_CPU/3968,F_CPU/4000,F_CPU/4032,F_CPU/4064 - ,F_CPU/4096,F_CPU/4128,F_CPU/4160,F_CPU/4192,F_CPU/4224,F_CPU/4256,F_CPU/4288,F_CPU/4320,F_CPU/4352,F_CPU/4384,F_CPU/4416,F_CPU/4448,F_CPU/4480,F_CPU/4512,F_CPU/4544 - ,F_CPU/4576,F_CPU/4608,F_CPU/4640,F_CPU/4672,F_CPU/4704,F_CPU/4736,F_CPU/4768,F_CPU/4800,F_CPU/4832,F_CPU/4864,F_CPU/4896,F_CPU/4928,F_CPU/4960,F_CPU/4992,F_CPU/5024 - ,F_CPU/5056,F_CPU/5088,F_CPU/5120,F_CPU/5152,F_CPU/5184,F_CPU/5216,F_CPU/5248,F_CPU/5280,F_CPU/5312,F_CPU/5344,F_CPU/5376,F_CPU/5408,F_CPU/5440,F_CPU/5472,F_CPU/5504 - ,F_CPU/5536,F_CPU/5568,F_CPU/5600,F_CPU/5632,F_CPU/5664,F_CPU/5696,F_CPU/5728,F_CPU/5760,F_CPU/5792,F_CPU/5824,F_CPU/5856,F_CPU/5888,F_CPU/5920,F_CPU/5952,F_CPU/5984 - ,F_CPU/6016,F_CPU/6048,F_CPU/6080,F_CPU/6112,F_CPU/6144,F_CPU/6176,F_CPU/6208,F_CPU/6240,F_CPU/6272,F_CPU/6304,F_CPU/6336,F_CPU/6368,F_CPU/6400,F_CPU/6432,F_CPU/6464 - ,F_CPU/6496,F_CPU/6528,F_CPU/6560,F_CPU/6592,F_CPU/6624,F_CPU/6656,F_CPU/6688,F_CPU/6720,F_CPU/6752,F_CPU/6784,F_CPU/6816,F_CPU/6848,F_CPU/6880,F_CPU/6912,F_CPU/6944 - ,F_CPU/6976,F_CPU/7008,F_CPU/7040,F_CPU/7072,F_CPU/7104,F_CPU/7136,F_CPU/7168,F_CPU/7200,F_CPU/7232,F_CPU/7264,F_CPU/7296,F_CPU/7328,F_CPU/7360,F_CPU/7392,F_CPU/7424 - ,F_CPU/7456,F_CPU/7488,F_CPU/7520,F_CPU/7552,F_CPU/7584,F_CPU/7616,F_CPU/7648,F_CPU/7680,F_CPU/7712,F_CPU/7744,F_CPU/7776,F_CPU/7808,F_CPU/7840,F_CPU/7872,F_CPU/7904 - ,F_CPU/7936,F_CPU/7968,F_CPU/8000,F_CPU/8032,F_CPU/8064,F_CPU/8096,F_CPU/8128,F_CPU/8160,F_CPU/8192 - }; -/** \brief approximates division of F_CPU/divisor - -In the stepper interrupt a division is needed, which is a slow operation. -The result is used for timer calculation where small errors are ok. This -function uses lookup tables to find a fast approximation of the result. - -*/ -int32_t HAL::CPUDivU2(unsigned int divisor) -{ -#if CPU_ARCH==ARCH_AVR - int32_t res; - unsigned short table; - if(divisor<8192) - { - if(divisor<512) - { - if(divisor<10) divisor = 10; - return Div4U2U(F_CPU,divisor); // These entries have overflows in lookuptable! - } - table = (unsigned short)&slow_div_lut[0]; - __asm__ __volatile__( // needs 64 ticks neu 49 Ticks - "mov r18,%A1 \n\t" - "andi r18,31 \n\t" // divisor & 31 in r18 - "lsr %B1 \n\t" // divisor >> 4 - "ror %A1 \n\t" - "lsr %B1 \n\t" - "ror %A1 \n\t" - "lsr %B1 \n\t" - "ror %A1 \n\t" - "lsr %B1 \n\t" - "ror %A1 \n\t" - "andi %A1,254 \n\t" - "add %A2,%A1 \n\t" // table+divisor>>3 - "adc %B2,%B1 \n\t" - "lpm %A0,Z+ \n\t" // y0 in res - "lpm %B0,Z+ \n\t" // %C0,%D0 are 0 - "movw r4,%A0 \n\t" // y0 nach gain (r4-r5) - "lpm r0,Z+ \n\t" // gain = gain-y1 - "sub r4,r0 \n\t" - "lpm r0,Z+ \n\t" - "sbc r5,r0 \n\t" - "mul r18,r4 \n\t" // gain*(divisor & 31) - "movw %A1,r0 \n\t" // divisor not needed any more, use for byte 0,1 of result - "mul r18,r5 \n\t" - "add %B1,r0 \n\t" - "mov %A2,r1 \n\t" - "lsl %A1 \n\t" - "rol %B1 \n\t" - "rol %A2 \n\t" - "lsl %A1 \n\t" - "rol %B1 \n\t" - "rol %A2 \n\t" - "lsl %A1 \n\t" - "rol %B1 \n\t" - "rol %A2 \n\t" - "sub %A0,%B1 \n\t" - "sbc %B0,%A2 \n\t" - "clr %C0 \n\t" - "clr %D0 \n\t" - "clr r1 \n\t" - : "=&r" (res),"=&d"(divisor),"=&z"(table) : "1"(divisor),"2"(table) : "r18","r4","r5"); - return res; - /*unsigned short adr0 = (unsigned short)&slow_div_lut+(divisor>>4)&1022; - long y0= pgm_read_dword_near(adr0); - long gain = y0-pgm_read_dword_near(adr0+2); - return y0-((gain*(divisor & 31))>>5);*/ - } - else - { - table = (unsigned short)&fast_div_lut[0]; - __asm__ __volatile__( // needs 49 ticks - "movw r18,%A1 \n\t" - "andi r19,15 \n\t" // divisor & 4095 in r18,r19 - "lsr %B1 \n\t" // divisor >> 3, then %B1 is 2*(divisor >> 12) - "lsr %B1 \n\t" - "lsr %B1 \n\t" - "andi %B1,254 \n\t" - "add %A2,%B1 \n\t" // table+divisor>>11 - "adc %B2,r1 \n\t" // - "lpm %A0,Z+ \n\t" // y0 in res - "lpm %B0,Z+ \n\t" - "movw r4,%A0 \n\t" // y0 to gain (r4-r5) - "lpm r0,Z+ \n\t" // gain = gain-y1 - "sub r4,r0 \n\t" - "lpm r0,Z+ \n\t" - "sbc r5,r0 \n\t" // finished - result has max. 16 bit - "mul r18,r4 \n\t" // gain*(divisor & 4095) - "movw %A1,r0 \n\t" // divisor not needed any more, use for byte 0,1 of result - "mul r19,r5 \n\t" - "mov %A2,r0 \n\t" // %A2 = byte 3 of result - "mul r18,r5 \n\t" - "add %B1,r0 \n\t" - "adc %A2,r1 \n\t" - "mul r19,r4 \n\t" - "add %B1,r0 \n\t" - "adc %A2,r1 \n\t" - "andi %B1,240 \n\t" // >> 12 - "swap %B1 \n\t" - "swap %A2 \r\n" - "mov %A1,%A2 \r\n" - "andi %A1,240 \r\n" - "or %B1,%A1 \r\n" - "andi %A2,15 \r\n" - "sub %A0,%B1 \n\t" - "sbc %B0,%A2 \n\t" - "clr %C0 \n\t" - "clr %D0 \n\t" - "clr r1 \n\t" - : "=&r" (res),"=&d"(divisor),"=&z"(table) : "1"(divisor),"2"(table) : "r18","r19","r4","r5"); - return res; - /* - // The asm mimics the following code - unsigned short adr0 = (unsigned short)&fast_div_lut+(divisor>>11)&254; - unsigned short y0= pgm_read_word_near(adr0); - unsigned short gain = y0-pgm_read_word_near(adr0+2); - return y0-(((long)gain*(divisor & 4095))>>12);*/ - } -#else - return F_CPU/divisor; -#endif -} - -void HAL::setupTimer() -{ -#if USE_ADVANCE - EXTRUDER_TCCR = 0; // need Normal not fastPWM set by arduino init - EXTRUDER_TIMSK |= (1<-1 - SET_OUTPUT(SERVO0_PIN); - WRITE(SERVO0_PIN,LOW); -#endif -#if SERVO1_PIN>-1 - SET_OUTPUT(SERVO1_PIN); - WRITE(SERVO1_PIN,LOW); -#endif -#if SERVO2_PIN>-1 - SET_OUTPUT(SERVO2_PIN); - WRITE(SERVO2_PIN,LOW); -#endif -#if SERVO3_PIN>-1 - SET_OUTPUT(SERVO3_PIN); - WRITE(SERVO3_PIN,LOW); -#endif - TCCR3A = 0; // normal counting mode - TCCR3B = _BV(CS31); // set prescaler of 8 - TCNT3 = 0; // clear the timer count -#if defined(__AVR_ATmega128__) - TIFR |= _BV(OCF3A); // clear any pending interrupts; - ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt -#else - TIFR3 = _BV(OCF3A); // clear any pending interrupts; - TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt -#endif -#endif -} - -void HAL::showStartReason() -{ - // Check startup - does nothing if bootloader sets MCUSR to 0 - uint8_t mcu = MCUSR; - if(mcu & 1) Com::printInfoFLN(Com::tPowerUp); - if(mcu & 2) Com::printInfoFLN(Com::tExternalReset); - if(mcu & 4) Com::printInfoFLN(Com::tBrownOut); - if(mcu & 8) Com::printInfoFLN(Com::tWatchdog); - if(mcu & 32) Com::printInfoFLN(Com::tSoftwareReset); - MCUSR=0; -} -int HAL::getFreeRam() -{ - int freeram = 0; - InterruptProtectedBlock noInts; - uint8_t * heapptr, * stackptr; - heapptr = (uint8_t *)malloc(4); // get heap pointer - free(heapptr); // free up the memory again (sets heapptr to 0) - stackptr = (uint8_t *)(SP); // save value of stack pointer - freeram = (int)stackptr-(int)heapptr; - return freeram; -} - -void(* resetFunc) (void) = 0; //declare reset function @ address 0 - -void HAL::resetHardware() -{ - resetFunc(); -} - -void HAL::analogStart() -{ -#if ANALOG_INPUTS > 0 - ADMUX = ANALOG_REF; // refernce voltage - for(uint8_t i = 0; i < ANALOG_INPUTS; i++) - { - osAnalogInputCounter[i] = 0; - osAnalogInputBuildup[i] = 0; - osAnalogInputValues[i] = 0; - } - ADCSRA = _BV(ADEN)|_BV(ADSC)|ANALOG_PRESCALER; - //ADCSRA |= _BV(ADSC); // start ADC-conversion - while (ADCSRA & _BV(ADSC) ) {} // wait for conversion - /* ADCW must be read once, otherwise the next result is wrong. */ - uint dummyADCResult; - dummyADCResult = ADCW; - // Enable interrupt driven conversion loop - uint8_t channel = pgm_read_byte(&osAnalogInputChannels[osAnalogInputPos]); -#if defined(ADCSRB) && defined(MUX5) - if(channel & 8) // Reading channel 0-7 or 8-15? - ADCSRB |= _BV(MUX5); - else - ADCSRB &= ~_BV(MUX5); -#endif - ADMUX = (ADMUX & ~(0x1F)) | (channel & 7); - ADCSRA |= _BV(ADSC); // start conversion without interrupt! -#endif -} - -/************************************************************************* -* Title: I2C master library using hardware TWI interface -* Author: Peter Fleury http://jump.to/fleury -* File: $Id: twimaster.c,v 1.3 2005/07/02 11:14:21 Peter Exp $ -* Software: AVR-GCC 3.4.3 / avr-libc 1.2.3 -* Target: any AVR device with hardware TWI -* Usage: API compatible with I2C Software Library i2cmaster.h -**************************************************************************/ -#if (__GNUC__ * 100 + __GNUC_MINOR__) < 304 -#error "This library requires AVR-GCC 3.4 or later, update to newer AVR-GCC compiler !" -#endif - -#include - -/************************************************************************* - Initialization of the I2C bus interface. Need to be called only once -*************************************************************************/ -void HAL::i2cInit(unsigned long clockSpeedHz) -{ - /* initialize TWI clock: 100 kHz clock, TWPS = 0 => prescaler = 1 */ - TWSR = 0; /* no prescaler */ - TWBR = ((F_CPU/clockSpeedHz)-16)/2; /* must be > 10 for stable operation */ -} - - -/************************************************************************* - Issues a start condition and sends address and transfer direction. - return 0 = device accessible, 1= failed to access device -*************************************************************************/ -unsigned char HAL::i2cStart(unsigned char address) -{ - uint8_t twst; - - // send START condition - TWCR = (1<2500) ms = 2500; - servoTimings[servo] = (unsigned int)(((F_CPU/1000000)*(long)ms)>>3); - servoAutoOff[servo] = (ms) ? (autoOff / 20) : 0; -} -SIGNAL (TIMER3_COMPA_vect) -{ - switch(servoIndex) - { - case 0: - TCNT3 = 0; - if(HAL::servoTimings[0]) - { -#if SERVO0_PIN>-1 - WRITE(SERVO0_PIN,HIGH); -#endif - OCR3A = HAL::servoTimings[0]; - } - else OCR3A = SERVO2500US; - break; - case 1: -#if SERVO0_PIN>-1 - WRITE(SERVO0_PIN,LOW); -#endif - OCR3A = SERVO5000US; - break; - case 2: - TCNT3 = 0; - if(HAL::servoTimings[1]) - { -#if SERVO1_PIN>-1 - WRITE(SERVO1_PIN,HIGH); -#endif - OCR3A = HAL::servoTimings[1]; - } - else OCR3A = SERVO2500US; - break; - case 3: -#if SERVO1_PIN>-1 - WRITE(SERVO1_PIN,LOW); -#endif - OCR3A = SERVO5000US; - break; - case 4: - TCNT3 = 0; - if(HAL::servoTimings[2]) - { -#if SERVO2_PIN>-1 - WRITE(SERVO2_PIN,HIGH); -#endif - OCR3A = HAL::servoTimings[2]; - } - else OCR3A = SERVO2500US; - break; - case 5: -#if SERVO2_PIN>-1 - WRITE(SERVO2_PIN,LOW); -#endif - OCR3A = SERVO5000US; - break; - case 6: - TCNT3 = 0; - if(HAL::servoTimings[3]) - { -#if SERVO3_PIN>-1 - WRITE(SERVO3_PIN,HIGH); -#endif - OCR3A = HAL::servoTimings[3]; - } - else OCR3A = SERVO2500US; - break; - case 7: -#if SERVO3_PIN>-1 - WRITE(SERVO3_PIN,LOW); -#endif - OCR3A = SERVO5000US; - break; - } - if(servoIndex & 1) - { - uint8_t nr = servoIndex >> 1; - if(servoAutoOff[nr]) - { - servoAutoOff[nr]--; - if(servoAutoOff[nr] == 0) HAL::servoTimings[nr] = 0; - } - } - servoIndex++; - if(servoIndex>7) - servoIndex = 0; -} -#else -#error No servo support for your board, please diable FEATURE_SERVO -#endif -#endif - -// ================== Interrupt handling ====================== - -/** \brief Sets the timer 1 compare value to delay ticks. - -This function sets the OCR1A compare counter to get the next interrupt -at delay ticks measured from the last interrupt. delay must be << 2^24 -*/ -inline void setTimer(uint32_t delay) -{ - __asm__ __volatile__ ( - "cli \n\t" - "tst %C[delay] \n\t" //if(delay<65536) { - "brne else%= \n\t" - "cpi %B[delay],255 \n\t" - "breq else%= \n\t" // delay <65280 - "sts stepperWait,r1 \n\t" // stepperWait = 0; - "sts stepperWait+1,r1 \n\t" - "sts stepperWait+2,r1 \n\t" - "lds %C[delay],%[time] \n\t" // Read TCNT1 - "lds %D[delay],%[time]+1 \n\t" - "ldi r18,100 \n\t" // Add 100 to TCNT1 - "add %C[delay],r18 \n\t" - "adc %D[delay],r1 \n\t" - "cp %A[delay],%C[delay] \n\t" // delay 65535 - "lds r23,stepperWait+1 \n\t" - "tst r23 \n\t" - "brne last%= \n\t" // Still not 0, go ahead - "lds r22,stepperWait \n\t" - "breq end%= \n\t" // stepperWait is 0, do your work - "last%=: \n\t" - "sts %[ocr]+1,r23 \n\t" // OCR1A = stepper wait; - "sts %[ocr],r22 \n\t" - "sts stepperWait,r1 \n\t" - "sts stepperWait+1,r1 \n\t" - "rjmp end1%= \n\t" - "else%=: lds r22,stepperWait+1 \n\t" //} else { stepperWait = stepperWait-32768; - "subi r22, 0x80 \n\t" - "sbci r23, 0x00 \n\t" - "sts stepperWait+1,r22 \n\t" // ocr1a stays 32768 - "sts stepperWait+2,r23 \n\t" - "end1%=: ldi %[ex],1 \n\t" - "end%=: \n\t" - :[ex]"=&d"(doExit):[ocr]"i" (_SFR_MEM_ADDR(OCR1A)):"r22","r23" ); - if(doExit) return; - insideTimer1 = 1; - OCR1A = 61000; - if(PrintLine::hasLines()) - { - setTimer(PrintLine::bresenhamStep()); - } - else if(FEATURE_BABYSTEPPING && Printer::zBabystepsMissing) - { - Printer::zBabystep(); - setTimer(Printer::interval); - } - else - { - if(waitRelax == 0) - { -#if USE_ADVANCE - if(Printer::advanceStepsSet) - { - Printer::extruderStepsNeeded -= Printer::advanceStepsSet; -#if ENABLE_QUADRATIC_ADVANCE - Printer::advanceExecuted = 0; -#endif - Printer::advanceStepsSet = 0; - } -#endif -#if USE_ADVANCE - if(!Printer::extruderStepsNeeded) if(DISABLE_E) Extruder::disableCurrentExtruderMotor(); -#else - if(DISABLE_E) Extruder::disableCurrentExtruderMotor(); -#endif - } - else waitRelax--; - stepperWait = 0; // Importent becaus of optimization in asm at begin - OCR1A = 65500; // Wait for next move - } - DEBUG_MEMORY; - insideTimer1 = 0; -} - -#if !defined(HEATER_PWM_SPEED) -#define HEATER_PWM_SPEED 0 -#endif -#if HEATER_PWM_SPEED < 0 -#define HEATER_PWM_SPEED 0 -#endif -#if HEATER_PWM_SPEED > 2 -#define HEATER_PWM_SPEED 2 -#endif - -#if HEATER_PWM_SPEED == 0 -#define HEATER_PWM_STEP 1 -#define HEATER_PWM_MASK 255 -#elif HEATER_PWM_SPEED == 1 -#define HEATER_PWM_STEP 2 -#define HEATER_PWM_MASK 254 -#else -#define HEATER_PWM_STEP 4 -#define HEATER_PWM_MASK 252 -#endif - -#if !defined(COOLER_PWM_SPEED) -#define COOLER_PWM_SPEED 0 -#endif -#if COOLER_PWM_SPEED < 0 -#define COOLER_PWM_SPEED 0 -#endif -#if COOLER_PWM_SPEED > 2 -#define COOLER_PWM_SPEED 2 -#endif - -#if COOLER_PWM_SPEED == 0 -#define COOLER_PWM_STEP 1 -#define COOLER_PWM_MASK 255 -#elif COOLER_PWM_SPEED == 1 -#define COOLER_PWM_STEP 2 -#define COOLER_PWM_MASK 254 -#else -#define COOLER_PWM_STEP 4 -#define COOLER_PWM_MASK 252 -#endif - -#define pulseDensityModulate( pin, density,error,invert) {uint8_t carry;carry = error + (invert ? 255 - density : density); WRITE(pin, (carry < error)); error = carry;} -/** -This timer is called 3906 timer per second. It is used to update pwm values for heater and some other frequent jobs. -*/ -ISR(PWM_TIMER_VECTOR) -{ - static uint8_t pwm_count_cooler = 0; - static uint8_t pwm_count_heater = 0; - static uint8_t pwm_pos_set[NUM_EXTRUDER + 3]; -#if NUM_EXTRUDER > 0 - static uint8_t pwm_cooler_pos_set[NUM_EXTRUDER]; -#endif - PWM_OCR += 64; - if(pwm_count_heater == 0 && !PDM_FOR_EXTRUDER) - { -#if defined(EXT0_HEATER_PIN) && EXT0_HEATER_PIN > -1 - if((pwm_pos_set[0] = (pwm_pos[0] & HEATER_PWM_MASK)) > 0) WRITE(EXT0_HEATER_PIN,!HEATER_PINS_INVERTED); -#endif -#if defined(EXT1_HEATER_PIN) && EXT1_HEATER_PIN > -1 && NUM_EXTRUDER > 1 - if((pwm_pos_set[1] = (pwm_pos[1] & HEATER_PWM_MASK)) > 0) WRITE(EXT1_HEATER_PIN,!HEATER_PINS_INVERTED); -#endif -#if defined(EXT2_HEATER_PIN) && EXT2_HEATER_PIN > -1 && NUM_EXTRUDER > 2 - if((pwm_pos_set[2] = (pwm_pos[2] & HEATER_PWM_MASK)) > 0) WRITE(EXT2_HEATER_PIN,!HEATER_PINS_INVERTED); -#endif -#if defined(EXT3_HEATER_PIN) && EXT3_HEATER_PIN > -1 && NUM_EXTRUDER > 3 - if((pwm_pos_set[3] = (pwm_pos[3] & HEATER_PWM_MASK)) > 0) WRITE(EXT3_HEATER_PIN,!HEATER_PINS_INVERTED); -#endif -#if defined(EXT4_HEATER_PIN) && EXT4_HEATER_PIN > -1 && NUM_EXTRUDER > 4 - if((pwm_pos_set[4] = (pwm_pos[4] & HEATER_PWM_MASK)) > 0) WRITE(EXT4_HEATER_PIN,!HEATER_PINS_INVERTED); -#endif -#if defined(EXT5_HEATER_PIN) && EXT5_HEATER_PIN > -1 && NUM_EXTRUDER > 5 - if((pwm_pos_set[5] = (pwm_pos[5] & HEATER_PWM_MASK)) > 0) WRITE(EXT5_HEATER_PIN, !HEATER_PINS_INVERTED); -#endif -#if HEATED_BED_HEATER_PIN > -1 && HAVE_HEATED_BED - if((pwm_pos_set[NUM_EXTRUDER] = (pwm_pos[NUM_EXTRUDER] & HEATER_PWM_MASK)) > 0) WRITE(HEATED_BED_HEATER_PIN, !HEATER_PINS_INVERTED); -#endif - } - if(pwm_count_cooler == 0 && !PDM_FOR_COOLER) - { -#if defined(EXT0_HEATER_PIN) && EXT0_HEATER_PIN > -1 && EXT0_EXTRUDER_COOLER_PIN > -1 - if((pwm_cooler_pos_set[0] = (extruder[0].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT0_EXTRUDER_COOLER_PIN, 1); -#endif -#if !SHARED_COOLER && defined(EXT1_HEATER_PIN) && EXT1_HEATER_PIN > -1 && NUM_EXTRUDER > 1 -#if EXT1_EXTRUDER_COOLER_PIN > -1 && EXT1_EXTRUDER_COOLER_PIN != EXT0_EXTRUDER_COOLER_PIN - if((pwm_cooler_pos_set[1] = (extruder[1].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT1_EXTRUDER_COOLER_PIN, 1); -#endif -#endif -#if !SHARED_COOLER && defined(EXT2_HEATER_PIN) && EXT2_HEATER_PIN > -1 && NUM_EXTRUDER > 2 -#if EXT2_EXTRUDER_COOLER_PIN > -1 - if((pwm_cooler_pos_set[2] = (extruder[2].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT2_EXTRUDER_COOLER_PIN, 1); -#endif -#endif -#if !SHARED_COOLER && defined(EXT3_HEATER_PIN) && EXT3_HEATER_PIN > -1 && NUM_EXTRUDER > 3 -#if EXT3_EXTRUDER_COOLER_PIN > -1 - if((pwm_cooler_pos_set[3] = (extruder[3].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT3_EXTRUDER_COOLER_PIN, 1); -#endif -#endif -#if !SHARED_COOLER && defined(EXT4_HEATER_PIN) && EXT4_HEATER_PIN > -1 && NUM_EXTRUDER > 4 -#if EXT4_EXTRUDER_COOLER_PIN > -1 - if((pwm_cooler_pos_set[4] = (extruder[4].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT4_EXTRUDER_COOLER_PIN, 1); -#endif -#endif -#if !SHARED_COOLER && defined(EXT5_HEATER_PIN) && EXT5_HEATER_PIN > -1 && NUM_EXTRUDER > 5 -#if EXT5_EXTRUDER_COOLER_PIN > -1 - if((pwm_cooler_pos_set[5] = (extruder[5].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT5_EXTRUDER_COOLER_PIN, 1); -#endif -#endif -#if FAN_BOARD_PIN > -1 && SHARED_COOLER_BOARD_EXT == 0 - if((pwm_pos_set[NUM_EXTRUDER + 1] = (pwm_pos[NUM_EXTRUDER + 1] & COOLER_PWM_MASK)) > 0) WRITE(FAN_BOARD_PIN,1); -#endif -#if FAN_PIN > -1 && FEATURE_FAN_CONTROL - if((pwm_pos_set[NUM_EXTRUDER + 2] = (pwm_pos[NUM_EXTRUDER + 2] & COOLER_PWM_MASK)) > 0) WRITE(FAN_PIN,1); -#endif - } -#if defined(EXT0_HEATER_PIN) && EXT0_HEATER_PIN > -1 -#if PDM_FOR_EXTRUDER - pulseDensityModulate(EXT0_HEATER_PIN, pwm_pos[0], pwm_pos_set[0], HEATER_PINS_INVERTED); -#else - if(pwm_pos_set[0] == pwm_count_heater && pwm_pos_set[0] != HEATER_PWM_MASK) WRITE(EXT0_HEATER_PIN,HEATER_PINS_INVERTED); -#endif -#if EXT0_EXTRUDER_COOLER_PIN > -1 -#if PDM_FOR_COOLER - pulseDensityModulate(EXT0_EXTRUDER_COOLER_PIN, extruder[0].coolerPWM, pwm_cooler_pos_set[0], false); -#else - if(pwm_cooler_pos_set[0] == pwm_count_cooler && pwm_cooler_pos_set[0] != COOLER_PWM_MASK) WRITE(EXT0_EXTRUDER_COOLER_PIN,0); -#endif -#endif -#endif -#if defined(EXT1_HEATER_PIN) && EXT1_HEATER_PIN > -1 && NUM_EXTRUDER > 1 -#if PDM_FOR_EXTRUDER - pulseDensityModulate(EXT1_HEATER_PIN, pwm_pos[1], pwm_pos_set[1], HEATER_PINS_INVERTED); -#else - if(pwm_pos_set[1] == pwm_count_heater && pwm_pos_set[1] != HEATER_PWM_MASK) WRITE(EXT1_HEATER_PIN,HEATER_PINS_INVERTED); -#endif -#if !SHARED_COOLER && defined(EXT1_EXTRUDER_COOLER_PIN) && EXT1_EXTRUDER_COOLER_PIN > -1 && EXT1_EXTRUDER_COOLER_PIN != EXT0_EXTRUDER_COOLER_PIN -#if PDM_FOR_COOLER - pulseDensityModulate(EXT1_EXTRUDER_COOLER_PIN, extruder[1].coolerPWM, pwm_cooler_pos_set[1], false); -#else - if(pwm_cooler_pos_set[1] == pwm_count_cooler && pwm_cooler_pos_set[1] != COOLER_PWM_MASK) WRITE(EXT1_EXTRUDER_COOLER_PIN,0); -#endif -#endif -#endif -#if defined(EXT2_HEATER_PIN) && EXT2_HEATER_PIN > -1 && NUM_EXTRUDER > 2 -#if PDM_FOR_EXTRUDER - pulseDensityModulate(EXT2_HEATER_PIN, pwm_pos[2], pwm_pos_set[2], HEATER_PINS_INVERTED); -#else - if(pwm_pos_set[2] == pwm_count_heater && pwm_pos_set[2] != HEATER_PWM_MASK) WRITE(EXT2_HEATER_PIN,HEATER_PINS_INVERTED); -#endif -#if !SHARED_COOLER && EXT2_EXTRUDER_COOLER_PIN > -1 -#if PDM_FOR_COOLER - pulseDensityModulate(EXT2_EXTRUDER_COOLER_PIN, extruder[2].coolerPWM, pwm_cooler_pos_set[2], false); -#else - if(pwm_cooler_pos_set[2] == pwm_count_cooler && pwm_cooler_pos_set[2] != COOLER_PWM_MASK) WRITE(EXT2_EXTRUDER_COOLER_PIN,0); -#endif -#endif -#endif -#if defined(EXT3_HEATER_PIN) && EXT3_HEATER_PIN>-1 && NUM_EXTRUDER > 3 -#if PDM_FOR_EXTRUDER - pulseDensityModulate(EXT3_HEATER_PIN, pwm_pos[3], pwm_pos_set[3], HEATER_PINS_INVERTED); -#else - if(pwm_pos_set[3] == pwm_count_heater && pwm_pos_set[3] != HEATER_PWM_MASK) WRITE(EXT3_HEATER_PIN,HEATER_PINS_INVERTED); -#endif -#if !SHARED_COOLER && EXT3_EXTRUDER_COOLER_PIN > -1 -#if PDM_FOR_COOLER - pulseDensityModulate(EXT3_EXTRUDER_COOLER_PIN, extruder[3].coolerPWM, pwm_cooler_pos_set[3], false); -#else - if(pwm_cooler_pos_set[3] == pwm_count_cooler && pwm_cooler_pos_set[3] != COOLER_PWM_MASK) WRITE(EXT3_EXTRUDER_COOLER_PIN,0); -#endif -#endif -#endif -#if defined(EXT4_HEATER_PIN) && EXT4_HEATER_PIN > -1 && NUM_EXTRUDER > 4 -#if PDM_FOR_EXTRUDER - pulseDensityModulate(EXT4_HEATER_PIN, pwm_pos[4], pwm_pos_set[4], HEATER_PINS_INVERTED); -#else - if(pwm_pos_set[4] == pwm_count_heater && pwm_pos_set[4] != HEATER_PWM_MASK) WRITE(EXT4_HEATER_PIN,HEATER_PINS_INVERTED); -#endif -#if !SHARED_COOLER && EXT4_EXTRUDER_COOLER_PIN > -1 -#if PDM_FOR_COOLER - pulseDensityModulate(EXT4_EXTRUDER_COOLER_PIN, extruder[4].coolerPWM, pwm_cooler_pos_set[4], false); -#else - if(pwm_cooler_pos_set[4] == pwm_count_cooler && pwm_cooler_pos_set[4] != COOLER_PWM_MASK) WRITE(EXT4_EXTRUDER_COOLER_PIN,0); -#endif -#endif -#endif -#if defined(EXT5_HEATER_PIN) && EXT5_HEATER_PIN>-1 && NUM_EXTRUDER > 5 -#if PDM_FOR_EXTRUDER - pulseDensityModulate(EXT5_HEATER_PIN, pwm_pos[5], pwm_pos_set[5], HEATER_PINS_INVERTED); -#else - if(pwm_pos_set[5] == pwm_count_heater && pwm_pos_set[5] != HEATER_PWM_MASK) WRITE(EXT5_HEATER_PIN,HEATER_PINS_INVERTED); -#endif -#if !SHARED_COOLER && EXT5_EXTRUDER_COOLER_PIN > -1 -#if PDM_FOR_COOLER - pulseDensityModulate(EXT5_EXTRUDER_COOLER_PIN, extruder[5].coolerPWM, pwm_cooler_pos_set[5], false); -#else - if(pwm_cooler_pos_set[5] == pwm_count_cooler && pwm_cooler_pos_set[5] != COOLER_PWM_MASK) WRITE(EXT5_EXTRUDER_COOLER_PIN,0); -#endif -#endif -#endif -#if FAN_BOARD_PIN > -1 && SHARED_COOLER_BOARD_EXT == 0 -#if PDM_FOR_COOLER - pulseDensityModulate(FAN_BOARD_PIN, pwm_pos[NUM_EXTRUDER + 1], pwm_pos_set[NUM_EXTRUDER + 1], false); -#else - if(pwm_pos_set[NUM_EXTRUDER + 1] == pwm_count_cooler && pwm_pos_set[NUM_EXTRUDER + 1] != COOLER_PWM_MASK) WRITE(FAN_BOARD_PIN,0); -#endif -#endif -#if FAN_PIN > -1 && FEATURE_FAN_CONTROL - if(fanKickstart == 0) - { -#if PDM_FOR_COOLER - pulseDensityModulate(FAN_PIN, pwm_pos[NUM_EXTRUDER + 2], pwm_pos_set[NUM_EXTRUDER + 2], false); -#else - if(pwm_pos_set[NUM_EXTRUDER + 2] == pwm_count_cooler && pwm_pos_set[NUM_EXTRUDER + 2] != COOLER_PWM_MASK) WRITE(FAN_PIN,0); -#endif - } -#endif -#if HEATED_BED_HEATER_PIN > -1 && HAVE_HEATED_BED -#if PDM_FOR_EXTRUDER - pulseDensityModulate(HEATED_BED_HEATER_PIN, pwm_pos[NUM_EXTRUDER], pwm_pos_set[NUM_EXTRUDER], HEATER_PINS_INVERTED); -#else - if(pwm_pos_set[NUM_EXTRUDER] == pwm_count_heater && pwm_pos_set[NUM_EXTRUDER] != HEATER_PWM_MASK) WRITE(HEATED_BED_HEATER_PIN,HEATER_PINS_INVERTED); -#endif -#endif - HAL::allowInterrupts(); - counterPeriodical++; // Appxoimate a 100ms timer - if(counterPeriodical >= (int)(F_CPU/40960)) - { - counterPeriodical = 0; - executePeriodical = 1; - if(fanKickstart) fanKickstart--; - } -// read analog values -#if ANALOG_INPUTS > 0 - if((ADCSRA & _BV(ADSC)) == 0) // Conversion finished? - { - osAnalogInputBuildup[osAnalogInputPos] += ADCW; - if(++osAnalogInputCounter[osAnalogInputPos] >= _BV(ANALOG_INPUT_SAMPLE)) - { -#if ANALOG_INPUT_BITS + ANALOG_INPUT_SAMPLE < 12 - osAnalogInputValues[osAnalogInputPos] = - osAnalogInputBuildup[osAnalogInputPos] << (12 - ANALOG_INPUT_BITS - ANALOG_INPUT_SAMPLE); -#endif -#if ANALOG_INPUT_BITS + ANALOG_INPUT_SAMPLE > 12 - osAnalogInputValues[osAnalogInputPos] = - osAnalogInputBuildup[osAnalogInputPos] >> (ANALOG_INPUT_BITS + ANALOG_INPUT_SAMPLE - 12); -#endif -#if ANALOG_INPUT_BITS + ANALOG_INPUT_SAMPLE == 12 - osAnalogInputValues[osAnalogInputPos] = osAnalogInputBuildup[osAnalogInputPos]; -#endif - osAnalogInputBuildup[osAnalogInputPos] = 0; - osAnalogInputCounter[osAnalogInputPos] = 0; - // Start next conversion - if(++osAnalogInputPos >= ANALOG_INPUTS) osAnalogInputPos = 0; - uint8_t channel = pgm_read_byte(&osAnalogInputChannels[osAnalogInputPos]); -#if defined(ADCSRB) && defined(MUX5) - if(channel & 8) // Reading channel 0-7 or 8-15? - ADCSRB |= _BV(MUX5); - else - ADCSRB &= ~_BV(MUX5); -#endif - ADMUX = (ADMUX & ~(0x1F)) | (channel & 7); - } - ADCSRA |= _BV(ADSC); // start next conversion - } -#endif - - UI_FAST; // Short timed user interface action - pwm_count_cooler += COOLER_PWM_STEP; - pwm_count_heater += HEATER_PWM_STEP; -} -#if USE_ADVANCE - -static int8_t extruderLastDirection = 0; -#ifndef ADVANCE_DIR_FILTER_STEPS -#define ADVANCE_DIR_FILTER_STEPS 2 -#endif - -void HAL::resetExtruderDirection() -{ - extruderLastDirection = 0; -} -/** \brief Timer routine for extruder stepper. - -Several methods need to move the extruder. To get a optima result, -all methods update the printer_state.extruderStepsNeeded with the -number of additional steps needed. During this interrupt, one step -is executed. This will keep the extruder moving, until the total -wanted movement is achieved. This will be done with the maximum -allowable speed for the extruder. -*/ -ISR(EXTRUDER_TIMER_VECTOR) -{ - uint8_t timer = EXTRUDER_OCR; - if(!Printer::isAdvanceActivated()) return; // currently no need - if(Printer::extruderStepsNeeded > 0 && extruderLastDirection != 1) - { - if(Printer::extruderStepsNeeded >= ADVANCE_DIR_FILTER_STEPS) - { - Extruder::setDirection(true); - extruderLastDirection = 1; - timer += 40; // Add some more wait time to prevent blocking - } - } - else if(Printer::extruderStepsNeeded < 0 && extruderLastDirection != -1) - { - if(-Printer::extruderStepsNeeded >= ADVANCE_DIR_FILTER_STEPS) - { - Extruder::setDirection(false); - extruderLastDirection = -1; - timer += 40; // Add some more wait time to prevent blocking - } - } - else if(Printer::extruderStepsNeeded != 0) - { - Extruder::step(); - Printer::extruderStepsNeeded -= extruderLastDirection; - Printer::insertStepperHighDelay(); - Extruder::unstep(); - } - EXTRUDER_OCR = timer + Printer::maxExtruderSpeed; -} -#endif - -#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 -*/ - -ring_buffer rx_buffer = { { 0 }, 0, 0}; -ring_buffer_tx tx_buffer = { { 0 }, 0, 0}; - -inline void rf_store_char(unsigned char c, ring_buffer *buffer) -{ - uint8_t i = (buffer->head + 1) & SERIAL_BUFFER_MASK; - - // if we should be storing the received character into the location - // just before the tail (meaning that the head would advance to the - // current location of the tail), we're about to overflow the buffer - // and so we don't write the character or advance the head. - if (i != buffer->tail) - { - buffer->buffer[buffer->head] = c; - buffer->head = i; - } -} -#if !defined(USART0_RX_vect) && defined(USART1_RX_vect) -// do nothing - on the 32u4 the first USART is USART1 -#else -void rfSerialEvent() __attribute__((weak)); -void rfSerialEvent() {} -#define serialEvent_implemented -#if defined(USART_RX_vect) -SIGNAL(USART_RX_vect) -#elif defined(USART0_RX_vect) -SIGNAL(USART0_RX_vect) -#else -#if defined(SIG_USART0_RECV) -SIGNAL(SIG_USART0_RECV) -#elif defined(SIG_UART0_RECV) -SIGNAL(SIG_UART0_RECV) -#elif defined(SIG_UART_RECV) -SIGNAL(SIG_UART_RECV) -#else -#error "Don't know what the Data Received vector is called for the first UART" -#endif -#endif -{ -#if defined(UDR0) - uint8_t c = UDR0; -#elif defined(UDR) - uint8_t c = UDR; -#else -#error UDR not defined -#endif - rf_store_char(c, &rx_buffer); -} -#endif - -#if !defined(USART0_UDRE_vect) && defined(USART1_UDRE_vect) -// do nothing - on the 32u4 the first USART is USART1 -#else -#if !defined(UART0_UDRE_vect) && !defined(UART_UDRE_vect) && !defined(USART0_UDRE_vect) && !defined(USART_UDRE_vect) -#error "Don't know what the Data Register Empty vector is called for the first UART" -#else -#if defined(UART0_UDRE_vect) -ISR(UART0_UDRE_vect) -#elif defined(UART_UDRE_vect) -ISR(UART_UDRE_vect) -#elif defined(USART0_UDRE_vect) -ISR(USART0_UDRE_vect) -#elif defined(USART_UDRE_vect) -ISR(USART_UDRE_vect) -#endif -{ - if (tx_buffer.head == tx_buffer.tail) - { - // Buffer empty, so disable interrupts -#if defined(UCSR0B) - bit_clear(UCSR0B, UDRIE0); -#else - bit_clear(UCSRB, UDRIE); -#endif - } - else - { - // There is more data in the output buffer. Send the next byte - uint8_t c = tx_buffer.buffer[tx_buffer.tail]; - tx_buffer.tail = (tx_buffer.tail + 1) & SERIAL_TX_BUFFER_MASK; - -#if defined(UDR0) - UDR0 = c; -#elif defined(UDR) - UDR = c; -#else -#error UDR not defined -#endif - } -} -#endif -#endif - -#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 -#if !(defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega1284__) || defined(__AVR_ATmega2561__) || defined(__AVR_ATmega1281__) || defined (__AVR_ATmega644__) || defined (__AVR_ATmega644P__)) -#error BlueTooth option cannot be used with your mainboard -#endif -#if BLUETOOTH_SERIAL > 1 && !(defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)) -#error BlueTooth serial 2 or 3 can be used only with boards based on ATMega2560 or ATMega1280 -#endif -#if (BLUETOOTH_SERIAL == 1) -#if defined(USART1_RX_vect) -#define SIG_USARTx_RECV USART1_RX_vect -#define USARTx_UDRE_vect USART1_UDRE_vect -#else -#define SIG_USARTx_RECV SIG_USART1_RECV -#define USARTx_UDRE_vect SIG_USART1_DATA -#endif -#define UDRx UDR1 -#define UCSRxA UCSR1A -#define UCSRxB UCSR1B -#define UBRRxH UBRR1H -#define UBRRxL UBRR1L -#define U2Xx U2X1 -#define UARTxENABLE ((1< 4095) && use_u2x) - { - use_u2x = false; - goto try_again; - } - - // assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register) - *_ubrrh = baud_setting >> 8; - *_ubrrl = baud_setting; - - bit_set(*_ucsrb, _rxen); - bit_set(*_ucsrb, _txen); - bit_set(*_ucsrb, _rxcie); - bit_clear(*_ucsrb, _udrie); -#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 - WRITE(RXxPIN,1); // Pullup on RXDx - UCSRxA = (1<> 8); - UBRRxL = (uint8_t)(((F_CPU / 4 / BLUETOOTH_BAUD -1) / 2) & 0xFF); - UCSRxB |= UARTxENABLE; -#endif -} - -void RFHardwareSerial::end() -{ - // wait for transmission of outgoing data - while (_tx_buffer->head != _tx_buffer->tail) - ; - - bit_clear(*_ucsrb, _rxen); - bit_clear(*_ucsrb, _txen); - bit_clear(*_ucsrb, _rxcie); - bit_clear(*_ucsrb, _udrie); - -#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 - UCSRxB = 0; -#endif - // clear a ny received data - _rx_buffer->head = _rx_buffer->tail; -} - -int RFHardwareSerial::available(void) -{ - return (unsigned int)(SERIAL_BUFFER_SIZE + _rx_buffer->head - _rx_buffer->tail) & SERIAL_BUFFER_MASK; -} -int RFHardwareSerial::outputUnused(void) -{ - return SERIAL_TX_BUFFER_SIZE-(unsigned int)((SERIAL_TX_BUFFER_SIZE + _tx_buffer->head - _tx_buffer->tail) & SERIAL_TX_BUFFER_MASK); -} - -int RFHardwareSerial::peek(void) -{ - if (_rx_buffer->head == _rx_buffer->tail) - { - return -1; - } - return _rx_buffer->buffer[_rx_buffer->tail]; -} - -int RFHardwareSerial::read(void) -{ - // if the head isn't ahead of the tail, we don't have any characters - if (_rx_buffer->head == _rx_buffer->tail) - { - return -1; - } - unsigned char c = _rx_buffer->buffer[_rx_buffer->tail]; - _rx_buffer->tail = (_rx_buffer->tail + 1) & SERIAL_BUFFER_MASK; - return c; -} - -void RFHardwareSerial::flush() -{ - while (_tx_buffer->head != _tx_buffer->tail) - ; -#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 - while (_tx_buffer->head != txx_buffer_tail) ; -#endif -} -#ifdef COMPAT_PRE1 -void -#else -size_t -#endif -RFHardwareSerial::write(uint8_t c) -{ - uint8_t i = (_tx_buffer->head + 1) & SERIAL_TX_BUFFER_MASK; - - // If the output buffer is full, there's nothing for it other than to - // wait for the interrupt handler to empty it a bit - while (i == _tx_buffer->tail) ; -#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 - while (i == txx_buffer_tail) ; -#endif - _tx_buffer->buffer[_tx_buffer->head] = c; - _tx_buffer->head = i; - - bit_set(*_ucsrb, _udrie); -#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 - bit_set(UCSRxB, UDRIEx); -#endif -#ifndef COMPAT_PRE1 - return 1; -#endif -} - -// Preinstantiate Objects ////////////////////////////////////////////////////// - -#if defined(UBRRH) && defined(UBRRL) -RFHardwareSerial RFSerial(&rx_buffer, &tx_buffer, &UBRRH, &UBRRL, &UCSRA, &UCSRB, &UDR, RXEN, TXEN, RXCIE, UDRIE, U2X); -#elif defined(UBRR0H) && defined(UBRR0L) -RFHardwareSerial RFSerial(&rx_buffer, &tx_buffer, &UBRR0H, &UBRR0L, &UCSR0A, &UCSR0B, &UDR0, RXEN0, TXEN0, RXCIE0, UDRIE0, U2X0); -#elif defined(USBCON) -// do nothing - Serial object and buffers are initialized in CDC code -#else -#error no serial port defined (port 0) -#endif - -#endif - - - +#include "Repetier.h" +#include + +#if ANALOG_INPUTS > 0 +uint8 osAnalogInputCounter[ANALOG_INPUTS]; +uint osAnalogInputBuildup[ANALOG_INPUTS]; +uint8 osAnalogInputPos = 0; // Current sampling position +#endif +#if FEATURE_WATCHDOG + bool HAL::wdPinged = false; +#endif +//extern "C" void __cxa_pure_virtual() { } + +HAL::HAL() +{ + //ctor +} + +HAL::~HAL() +{ + //dtor +} + +uint16_t HAL::integerSqrt(uint32_t a) +{ +// http://www.mikrocontroller.net/articles/AVR_Arithmetik#32_Bit_.2F_32_Bit +//----------------------------------------------------------- +// Fast and short 32 bits AVR sqrt routine, avr-gcc ABI compliant +// R25:R24 = SQRT (R25:R24:R23:R22) rounded to the +// nearest integer (0.5 rounds up) +// Destroys R18-R19,R22-R23,R26-R27 +// Cycles incl call & ret = 265-310 +// Stack incl call = 2-3 +//----------------------------------------------------------- + + uint16_t b; + + __asm__ __volatile__ ( + "ldi R19, 0xc0 \n\t" + "clr R18 \n\t" // rotation mask in R19:R18 + "ldi R27, 0x40 \n\t" + "sub R26, R26 \n\t" // developing sqrt in R27:R26, C=0 + "1: brcs 2f \n\t" // C --> Bit is always 1 + "cp %C1, R26 \n\t" + "cpc %D1, R27 \n\t" // Does test value fit? + "brcs 3f \n\t" // C --> nope, bit is 0 + "2: sub %C1, R26 \n\t" + "sbc %D1, R27 \n\t" // Adjust argument for next bit + "or R26, R18 \n\t" + "or R27, R19 \n\t" // Set bit to 1 + "3: lsr R19 \n\t" + "ror R18 \n\t" // Shift right mask, C --> end loop + "eor R27, R19 \n\t" + "eor R26, R18 \n\t" // Shift right only test bit in result + "rol %A1 \n\t" // Bit 0 only set if end of loop + "rol %B1 \n\t" + "rol %C1 \n\t" + "rol %D1 \n\t" // Shift left remaining argument (C used at 1:) + "sbrs %A1, 0 \n\t" // Skip if 15 bits developed + "rjmp 1b \n\t" // Develop 15 bits of the sqrt + "brcs 4f \n\t" // C--> Last bits always 1 + "cp R26, %C1 \n\t" + "cpc R27, %D1 \n\t" // Test for last bit 1 + "brcc 5f \n\t" // NC --> bit is 0 + "4: sbc %B1, R19 \n\t" // Subtract C (any value from 1 to 0x7f will do) + "sbc %C1, R26 \n\t" + "sbc %D1, R27 \n\t" // Update argument for test + "inc R26 \n\t" // Last bit is 1 + "5: lsl %B1 \n\t" // Only bit 7 matters + "rol %C1 \n\t" + "rol %D1 \n\t" // Remainder * 2 + C + "brcs 6f \n\t" // C --> Always round up + "cp R26, %C1 \n\t" + "cpc R27, %D1 \n\t" // C decides rounding + "6: adc R26, R19 \n\t" + "adc R27, R19 \n\t" // Round up if C (R19=0) + "mov %B0, R27 \n\t" // return in R25:R24 for avr-gcc ABI compliance + "mov %A0, R26 \n\t" + :"=r"(b) + :"r"(a) + :"r18","r19","r27","r26" ); + return b; +} + + + +const uint16_t fast_div_lut[17] PROGMEM = {0,F_CPU/4096,F_CPU/8192,F_CPU/12288,F_CPU/16384,F_CPU/20480,F_CPU/24576,F_CPU/28672,F_CPU/32768,F_CPU/36864 + ,F_CPU/40960,F_CPU/45056,F_CPU/49152,F_CPU/53248,F_CPU/57344,F_CPU/61440,F_CPU/65536 + }; + +const uint16_t slow_div_lut[257] PROGMEM = {0,0,0,0,0,0,0,0,F_CPU/256,F_CPU/288,F_CPU/320,F_CPU/352 + ,F_CPU/384,F_CPU/416,F_CPU/448,F_CPU/480,F_CPU/512,F_CPU/544,F_CPU/576,F_CPU/608,F_CPU/640,F_CPU/672,F_CPU/704,F_CPU/736,F_CPU/768,F_CPU/800,F_CPU/832 + ,F_CPU/864,F_CPU/896,F_CPU/928,F_CPU/960,F_CPU/992,F_CPU/1024,F_CPU/1056,F_CPU/1088,F_CPU/1120,F_CPU/1152,F_CPU/1184,F_CPU/1216,F_CPU/1248,F_CPU/1280,F_CPU/1312 + ,F_CPU/1344,F_CPU/1376,F_CPU/1408,F_CPU/1440,F_CPU/1472,F_CPU/1504,F_CPU/1536,F_CPU/1568,F_CPU/1600,F_CPU/1632,F_CPU/1664,F_CPU/1696,F_CPU/1728,F_CPU/1760,F_CPU/1792 + ,F_CPU/1824,F_CPU/1856,F_CPU/1888,F_CPU/1920,F_CPU/1952,F_CPU/1984,F_CPU/2016 + ,F_CPU/2048,F_CPU/2080,F_CPU/2112,F_CPU/2144,F_CPU/2176,F_CPU/2208,F_CPU/2240,F_CPU/2272,F_CPU/2304,F_CPU/2336,F_CPU/2368,F_CPU/2400 + ,F_CPU/2432,F_CPU/2464,F_CPU/2496,F_CPU/2528,F_CPU/2560,F_CPU/2592,F_CPU/2624,F_CPU/2656,F_CPU/2688,F_CPU/2720,F_CPU/2752,F_CPU/2784,F_CPU/2816,F_CPU/2848,F_CPU/2880 + ,F_CPU/2912,F_CPU/2944,F_CPU/2976,F_CPU/3008,F_CPU/3040,F_CPU/3072,F_CPU/3104,F_CPU/3136,F_CPU/3168,F_CPU/3200,F_CPU/3232,F_CPU/3264,F_CPU/3296,F_CPU/3328,F_CPU/3360 + ,F_CPU/3392,F_CPU/3424,F_CPU/3456,F_CPU/3488,F_CPU/3520,F_CPU/3552,F_CPU/3584,F_CPU/3616,F_CPU/3648,F_CPU/3680,F_CPU/3712,F_CPU/3744,F_CPU/3776,F_CPU/3808,F_CPU/3840 + ,F_CPU/3872,F_CPU/3904,F_CPU/3936,F_CPU/3968,F_CPU/4000,F_CPU/4032,F_CPU/4064 + ,F_CPU/4096,F_CPU/4128,F_CPU/4160,F_CPU/4192,F_CPU/4224,F_CPU/4256,F_CPU/4288,F_CPU/4320,F_CPU/4352,F_CPU/4384,F_CPU/4416,F_CPU/4448,F_CPU/4480,F_CPU/4512,F_CPU/4544 + ,F_CPU/4576,F_CPU/4608,F_CPU/4640,F_CPU/4672,F_CPU/4704,F_CPU/4736,F_CPU/4768,F_CPU/4800,F_CPU/4832,F_CPU/4864,F_CPU/4896,F_CPU/4928,F_CPU/4960,F_CPU/4992,F_CPU/5024 + ,F_CPU/5056,F_CPU/5088,F_CPU/5120,F_CPU/5152,F_CPU/5184,F_CPU/5216,F_CPU/5248,F_CPU/5280,F_CPU/5312,F_CPU/5344,F_CPU/5376,F_CPU/5408,F_CPU/5440,F_CPU/5472,F_CPU/5504 + ,F_CPU/5536,F_CPU/5568,F_CPU/5600,F_CPU/5632,F_CPU/5664,F_CPU/5696,F_CPU/5728,F_CPU/5760,F_CPU/5792,F_CPU/5824,F_CPU/5856,F_CPU/5888,F_CPU/5920,F_CPU/5952,F_CPU/5984 + ,F_CPU/6016,F_CPU/6048,F_CPU/6080,F_CPU/6112,F_CPU/6144,F_CPU/6176,F_CPU/6208,F_CPU/6240,F_CPU/6272,F_CPU/6304,F_CPU/6336,F_CPU/6368,F_CPU/6400,F_CPU/6432,F_CPU/6464 + ,F_CPU/6496,F_CPU/6528,F_CPU/6560,F_CPU/6592,F_CPU/6624,F_CPU/6656,F_CPU/6688,F_CPU/6720,F_CPU/6752,F_CPU/6784,F_CPU/6816,F_CPU/6848,F_CPU/6880,F_CPU/6912,F_CPU/6944 + ,F_CPU/6976,F_CPU/7008,F_CPU/7040,F_CPU/7072,F_CPU/7104,F_CPU/7136,F_CPU/7168,F_CPU/7200,F_CPU/7232,F_CPU/7264,F_CPU/7296,F_CPU/7328,F_CPU/7360,F_CPU/7392,F_CPU/7424 + ,F_CPU/7456,F_CPU/7488,F_CPU/7520,F_CPU/7552,F_CPU/7584,F_CPU/7616,F_CPU/7648,F_CPU/7680,F_CPU/7712,F_CPU/7744,F_CPU/7776,F_CPU/7808,F_CPU/7840,F_CPU/7872,F_CPU/7904 + ,F_CPU/7936,F_CPU/7968,F_CPU/8000,F_CPU/8032,F_CPU/8064,F_CPU/8096,F_CPU/8128,F_CPU/8160,F_CPU/8192 + }; +/** \brief approximates division of F_CPU/divisor + +In the stepper interrupt a division is needed, which is a slow operation. +The result is used for timer calculation where small errors are ok. This +function uses lookup tables to find a fast approximation of the result. + +*/ +int32_t HAL::CPUDivU2(unsigned int divisor) +{ +#if CPU_ARCH==ARCH_AVR + int32_t res; + unsigned short table; + if(divisor<8192) + { + if(divisor<512) + { + if(divisor<10) divisor = 10; + return Div4U2U(F_CPU,divisor); // These entries have overflows in lookuptable! + } + table = (unsigned short)&slow_div_lut[0]; + __asm__ __volatile__( // needs 64 ticks neu 49 Ticks + "mov r18,%A1 \n\t" + "andi r18,31 \n\t" // divisor & 31 in r18 + "lsr %B1 \n\t" // divisor >> 4 + "ror %A1 \n\t" + "lsr %B1 \n\t" + "ror %A1 \n\t" + "lsr %B1 \n\t" + "ror %A1 \n\t" + "lsr %B1 \n\t" + "ror %A1 \n\t" + "andi %A1,254 \n\t" + "add %A2,%A1 \n\t" // table+divisor>>3 + "adc %B2,%B1 \n\t" + "lpm %A0,Z+ \n\t" // y0 in res + "lpm %B0,Z+ \n\t" // %C0,%D0 are 0 + "movw r4,%A0 \n\t" // y0 nach gain (r4-r5) + "lpm r0,Z+ \n\t" // gain = gain-y1 + "sub r4,r0 \n\t" + "lpm r0,Z+ \n\t" + "sbc r5,r0 \n\t" + "mul r18,r4 \n\t" // gain*(divisor & 31) + "movw %A1,r0 \n\t" // divisor not needed any more, use for byte 0,1 of result + "mul r18,r5 \n\t" + "add %B1,r0 \n\t" + "mov %A2,r1 \n\t" + "lsl %A1 \n\t" + "rol %B1 \n\t" + "rol %A2 \n\t" + "lsl %A1 \n\t" + "rol %B1 \n\t" + "rol %A2 \n\t" + "lsl %A1 \n\t" + "rol %B1 \n\t" + "rol %A2 \n\t" + "sub %A0,%B1 \n\t" + "sbc %B0,%A2 \n\t" + "clr %C0 \n\t" + "clr %D0 \n\t" + "clr r1 \n\t" + : "=&r" (res),"=&d"(divisor),"=&z"(table) : "1"(divisor),"2"(table) : "r18","r4","r5"); + return res; + /*unsigned short adr0 = (unsigned short)&slow_div_lut+(divisor>>4)&1022; + long y0= pgm_read_dword_near(adr0); + long gain = y0-pgm_read_dword_near(adr0+2); + return y0-((gain*(divisor & 31))>>5);*/ + } + else + { + table = (unsigned short)&fast_div_lut[0]; + __asm__ __volatile__( // needs 49 ticks + "movw r18,%A1 \n\t" + "andi r19,15 \n\t" // divisor & 4095 in r18,r19 + "lsr %B1 \n\t" // divisor >> 3, then %B1 is 2*(divisor >> 12) + "lsr %B1 \n\t" + "lsr %B1 \n\t" + "andi %B1,254 \n\t" + "add %A2,%B1 \n\t" // table+divisor>>11 + "adc %B2,r1 \n\t" // + "lpm %A0,Z+ \n\t" // y0 in res + "lpm %B0,Z+ \n\t" + "movw r4,%A0 \n\t" // y0 to gain (r4-r5) + "lpm r0,Z+ \n\t" // gain = gain-y1 + "sub r4,r0 \n\t" + "lpm r0,Z+ \n\t" + "sbc r5,r0 \n\t" // finished - result has max. 16 bit + "mul r18,r4 \n\t" // gain*(divisor & 4095) + "movw %A1,r0 \n\t" // divisor not needed any more, use for byte 0,1 of result + "mul r19,r5 \n\t" + "mov %A2,r0 \n\t" // %A2 = byte 3 of result + "mul r18,r5 \n\t" + "add %B1,r0 \n\t" + "adc %A2,r1 \n\t" + "mul r19,r4 \n\t" + "add %B1,r0 \n\t" + "adc %A2,r1 \n\t" + "andi %B1,240 \n\t" // >> 12 + "swap %B1 \n\t" + "swap %A2 \r\n" + "mov %A1,%A2 \r\n" + "andi %A1,240 \r\n" + "or %B1,%A1 \r\n" + "andi %A2,15 \r\n" + "sub %A0,%B1 \n\t" + "sbc %B0,%A2 \n\t" + "clr %C0 \n\t" + "clr %D0 \n\t" + "clr r1 \n\t" + : "=&r" (res),"=&d"(divisor),"=&z"(table) : "1"(divisor),"2"(table) : "r18","r19","r4","r5"); + return res; + /* + // The asm mimics the following code + unsigned short adr0 = (unsigned short)&fast_div_lut+(divisor>>11)&254; + unsigned short y0= pgm_read_word_near(adr0); + unsigned short gain = y0-pgm_read_word_near(adr0+2); + return y0-(((long)gain*(divisor & 4095))>>12);*/ + } +#else + return F_CPU/divisor; +#endif +} + +void HAL::setupTimer() +{ +#if USE_ADVANCE + EXTRUDER_TCCR = 0; // need Normal not fastPWM set by arduino init + EXTRUDER_TIMSK |= (1<-1 + SET_OUTPUT(SERVO0_PIN); + WRITE(SERVO0_PIN,LOW); +#endif +#if SERVO1_PIN>-1 + SET_OUTPUT(SERVO1_PIN); + WRITE(SERVO1_PIN,LOW); +#endif +#if SERVO2_PIN>-1 + SET_OUTPUT(SERVO2_PIN); + WRITE(SERVO2_PIN,LOW); +#endif +#if SERVO3_PIN>-1 + SET_OUTPUT(SERVO3_PIN); + WRITE(SERVO3_PIN,LOW); +#endif + TCCR3A = 0; // normal counting mode + TCCR3B = _BV(CS31); // set prescaler of 8 + TCNT3 = 0; // clear the timer count +#if defined(__AVR_ATmega128__) + TIFR |= _BV(OCF3A); // clear any pending interrupts; + ETIMSK |= _BV(OCIE3A); // enable the output compare interrupt +#else + TIFR3 = _BV(OCF3A); // clear any pending interrupts; + TIMSK3 = _BV(OCIE3A) ; // enable the output compare interrupt +#endif +#endif +} + +void HAL::showStartReason() +{ + // Check startup - does nothing if bootloader sets MCUSR to 0 + uint8_t mcu = MCUSR; + if(mcu & 1) Com::printInfoFLN(Com::tPowerUp); + if(mcu & 2) Com::printInfoFLN(Com::tExternalReset); + if(mcu & 4) Com::printInfoFLN(Com::tBrownOut); + if(mcu & 8) Com::printInfoFLN(Com::tWatchdog); + if(mcu & 32) Com::printInfoFLN(Com::tSoftwareReset); + MCUSR=0; +} +int HAL::getFreeRam() +{ + int freeram = 0; + InterruptProtectedBlock noInts; + uint8_t * heapptr, * stackptr; + heapptr = (uint8_t *)malloc(4); // get heap pointer + free(heapptr); // free up the memory again (sets heapptr to 0) + stackptr = (uint8_t *)(SP); // save value of stack pointer + freeram = (int)stackptr-(int)heapptr; + return freeram; +} + +void(* resetFunc) (void) = 0; //declare reset function @ address 0 + +void HAL::resetHardware() +{ + resetFunc(); +} + +void HAL::analogStart() +{ +#if ANALOG_INPUTS > 0 + ADMUX = ANALOG_REF; // refernce voltage + for(uint8_t i = 0; i < ANALOG_INPUTS; i++) + { + osAnalogInputCounter[i] = 0; + osAnalogInputBuildup[i] = 0; + osAnalogInputValues[i] = 0; + } + ADCSRA = _BV(ADEN)|_BV(ADSC)|ANALOG_PRESCALER; + //ADCSRA |= _BV(ADSC); // start ADC-conversion + while (ADCSRA & _BV(ADSC) ) {} // wait for conversion + /* ADCW must be read once, otherwise the next result is wrong. */ + //uint dummyADCResult; + //dummyADCResult = ADCW; + // Enable interrupt driven conversion loop + uint8_t channel = pgm_read_byte(&osAnalogInputChannels[osAnalogInputPos]); +#if defined(ADCSRB) && defined(MUX5) + if(channel & 8) // Reading channel 0-7 or 8-15? + ADCSRB |= _BV(MUX5); + else + ADCSRB &= ~_BV(MUX5); +#endif + ADMUX = (ADMUX & ~(0x1F)) | (channel & 7); + ADCSRA |= _BV(ADSC); // start conversion without interrupt! +#endif +} + +/************************************************************************* +* Title: I2C master library using hardware TWI interface +* Author: Peter Fleury http://jump.to/fleury +* File: $Id: twimaster.c,v 1.3 2005/07/02 11:14:21 Peter Exp $ +* Software: AVR-GCC 3.4.3 / avr-libc 1.2.3 +* Target: any AVR device with hardware TWI +* Usage: API compatible with I2C Software Library i2cmaster.h +**************************************************************************/ +#if (__GNUC__ * 100 + __GNUC_MINOR__) < 304 +#error "This library requires AVR-GCC 3.4 or later, update to newer AVR-GCC compiler !" +#endif + +#include + +/************************************************************************* + Initialization of the I2C bus interface. Need to be called only once +*************************************************************************/ +void HAL::i2cInit(unsigned long clockSpeedHz) +{ + /* initialize TWI clock: 100 kHz clock, TWPS = 0 => prescaler = 1 */ + TWSR = 0; /* no prescaler */ + TWBR = ((F_CPU/clockSpeedHz)-16)/2; /* must be > 10 for stable operation */ +} + + +/************************************************************************* + Issues a start condition and sends address and transfer direction. + return 0 = device accessible, 1= failed to access device +*************************************************************************/ +unsigned char HAL::i2cStart(unsigned char address) +{ + uint8_t twst; + + // send START condition + TWCR = (1<2500) ms = 2500; + servoTimings[servo] = (unsigned int)(((F_CPU/1000000)*(long)ms)>>3); + servoAutoOff[servo] = (ms) ? (autoOff / 20) : 0; +} +SIGNAL (TIMER3_COMPA_vect) +{ + switch(servoIndex) + { + case 0: + TCNT3 = 0; + if(HAL::servoTimings[0]) + { +#if SERVO0_PIN>-1 + WRITE(SERVO0_PIN,HIGH); +#endif + OCR3A = HAL::servoTimings[0]; + } + else OCR3A = SERVO2500US; + break; + case 1: +#if SERVO0_PIN>-1 + WRITE(SERVO0_PIN,LOW); +#endif + OCR3A = SERVO5000US; + break; + case 2: + TCNT3 = 0; + if(HAL::servoTimings[1]) + { +#if SERVO1_PIN>-1 + WRITE(SERVO1_PIN,HIGH); +#endif + OCR3A = HAL::servoTimings[1]; + } + else OCR3A = SERVO2500US; + break; + case 3: +#if SERVO1_PIN>-1 + WRITE(SERVO1_PIN,LOW); +#endif + OCR3A = SERVO5000US; + break; + case 4: + TCNT3 = 0; + if(HAL::servoTimings[2]) + { +#if SERVO2_PIN>-1 + WRITE(SERVO2_PIN,HIGH); +#endif + OCR3A = HAL::servoTimings[2]; + } + else OCR3A = SERVO2500US; + break; + case 5: +#if SERVO2_PIN>-1 + WRITE(SERVO2_PIN,LOW); +#endif + OCR3A = SERVO5000US; + break; + case 6: + TCNT3 = 0; + if(HAL::servoTimings[3]) + { +#if SERVO3_PIN>-1 + WRITE(SERVO3_PIN,HIGH); +#endif + OCR3A = HAL::servoTimings[3]; + } + else OCR3A = SERVO2500US; + break; + case 7: +#if SERVO3_PIN>-1 + WRITE(SERVO3_PIN,LOW); +#endif + OCR3A = SERVO5000US; + break; + } + if(servoIndex & 1) + { + uint8_t nr = servoIndex >> 1; + if(servoAutoOff[nr]) + { + servoAutoOff[nr]--; + if(servoAutoOff[nr] == 0) HAL::servoTimings[nr] = 0; + } + } + servoIndex++; + if(servoIndex>7) + servoIndex = 0; +} +#else +#error No servo support for your board, please diable FEATURE_SERVO +#endif +#endif + +// ================== Interrupt handling ====================== + +/** \brief Sets the timer 1 compare value to delay ticks. + +This function sets the OCR1A compare counter to get the next interrupt +at delay ticks measured from the last interrupt. delay must be << 2^24 +*/ +inline void setTimer(uint32_t delay) +{ + __asm__ __volatile__ ( + "cli \n\t" + "tst %C[delay] \n\t" //if(delay<65536) { + "brne else%= \n\t" + "cpi %B[delay],255 \n\t" + "breq else%= \n\t" // delay <65280 + "sts stepperWait,r1 \n\t" // stepperWait = 0; + "sts stepperWait+1,r1 \n\t" + "sts stepperWait+2,r1 \n\t" + "lds %C[delay],%[time] \n\t" // Read TCNT1 + "lds %D[delay],%[time]+1 \n\t" + "ldi r18,100 \n\t" // Add 100 to TCNT1 + "add %C[delay],r18 \n\t" + "adc %D[delay],r1 \n\t" + "cp %A[delay],%C[delay] \n\t" // delay 65535 + "lds r23,stepperWait+1 \n\t" + "tst r23 \n\t" + "brne last%= \n\t" // Still not 0, go ahead + "lds r22,stepperWait \n\t" + "breq end%= \n\t" // stepperWait is 0, do your work + "last%=: \n\t" + "sts %[ocr]+1,r23 \n\t" // OCR1A = stepper wait; + "sts %[ocr],r22 \n\t" + "sts stepperWait,r1 \n\t" + "sts stepperWait+1,r1 \n\t" + "rjmp end1%= \n\t" + "else%=: lds r22,stepperWait+1 \n\t" //} else { stepperWait = stepperWait-32768; + "subi r22, 0x80 \n\t" + "sbci r23, 0x00 \n\t" + "sts stepperWait+1,r22 \n\t" // ocr1a stays 32768 + "sts stepperWait+2,r23 \n\t" + "end1%=: ldi %[ex],1 \n\t" + "end%=: \n\t" + :[ex]"=&d"(doExit):[ocr]"i" (_SFR_MEM_ADDR(OCR1A)):"r22","r23" ); + if(doExit) return; + insideTimer1 = 1; + OCR1A = 61000; + if(PrintLine::hasLines()) + { + setTimer(PrintLine::bresenhamStep()); + } + else if(FEATURE_BABYSTEPPING && Printer::zBabystepsMissing) + { + Printer::zBabystep(); + setTimer(Printer::interval); + } + else + { + if(waitRelax == 0) + { +#if USE_ADVANCE + if(Printer::advanceStepsSet) + { + Printer::extruderStepsNeeded -= Printer::advanceStepsSet; +#if ENABLE_QUADRATIC_ADVANCE + Printer::advanceExecuted = 0; +#endif + Printer::advanceStepsSet = 0; + } +#endif +#if USE_ADVANCE + if(!Printer::extruderStepsNeeded) if(DISABLE_E) Extruder::disableCurrentExtruderMotor(); +#else + if(DISABLE_E) Extruder::disableCurrentExtruderMotor(); +#endif + } + else waitRelax--; + stepperWait = 0; // Importent becaus of optimization in asm at begin + OCR1A = 65500; // Wait for next move + } + DEBUG_MEMORY; + insideTimer1 = 0; +} + +#if !defined(HEATER_PWM_SPEED) +#define HEATER_PWM_SPEED 0 +#endif +#if HEATER_PWM_SPEED < 0 +#define HEATER_PWM_SPEED 0 +#endif +#if HEATER_PWM_SPEED > 2 +#define HEATER_PWM_SPEED 2 +#endif + +#if HEATER_PWM_SPEED == 0 +#define HEATER_PWM_STEP 1 +#define HEATER_PWM_MASK 255 +#elif HEATER_PWM_SPEED == 1 +#define HEATER_PWM_STEP 2 +#define HEATER_PWM_MASK 254 +#else +#define HEATER_PWM_STEP 4 +#define HEATER_PWM_MASK 252 +#endif + +#if !defined(COOLER_PWM_SPEED) +#define COOLER_PWM_SPEED 0 +#endif +#if COOLER_PWM_SPEED < 0 +#define COOLER_PWM_SPEED 0 +#endif +#if COOLER_PWM_SPEED > 2 +#define COOLER_PWM_SPEED 2 +#endif + +#if COOLER_PWM_SPEED == 0 +#define COOLER_PWM_STEP 1 +#define COOLER_PWM_MASK 255 +#elif COOLER_PWM_SPEED == 1 +#define COOLER_PWM_STEP 2 +#define COOLER_PWM_MASK 254 +#else +#define COOLER_PWM_STEP 4 +#define COOLER_PWM_MASK 252 +#endif + +#define pulseDensityModulate( pin, density,error,invert) {uint8_t carry;carry = error + (invert ? 255 - density : density); WRITE(pin, (carry < error)); error = carry;} +/** +This timer is called 3906 timer per second. It is used to update pwm values for heater and some other frequent jobs. +*/ +ISR(PWM_TIMER_VECTOR) +{ + static uint8_t pwm_count_cooler = 0; + static uint8_t pwm_count_heater = 0; + static uint8_t pwm_pos_set[NUM_PWM]; +#if NUM_EXTRUDER > 0 && ((defined(EXT0_HEATER_PIN) && EXT0_HEATER_PIN > -1 && EXT0_EXTRUDER_COOLER_PIN > -1) || (NUM_EXTRUDER > 1 && EXT1_EXTRUDER_COOLER_PIN > -1 && EXT1_EXTRUDER_COOLER_PIN != EXT0_EXTRUDER_COOLER_PIN) || (NUM_EXTRUDER > 2 && EXT2_EXTRUDER_COOLER_PIN > -1 && EXT2_EXTRUDER_COOLER_PIN != EXT2_EXTRUDER_COOLER_PIN) || (NUM_EXTRUDER > 3 && EXT3_EXTRUDER_COOLER_PIN > -1 && EXT3_EXTRUDER_COOLER_PIN != EXT3_EXTRUDER_COOLER_PIN) || (NUM_EXTRUDER > 4 && EXT4_EXTRUDER_COOLER_PIN > -1 && EXT4_EXTRUDER_COOLER_PIN != EXT4_EXTRUDER_COOLER_PIN) || (NUM_EXTRUDER > 5 && EXT5_EXTRUDER_COOLER_PIN > -1 && EXT5_EXTRUDER_COOLER_PIN != EXT5_EXTRUDER_COOLER_PIN)) + static uint8_t pwm_cooler_pos_set[NUM_EXTRUDER]; +#endif + PWM_OCR += 64; + if(pwm_count_heater == 0 && !PDM_FOR_EXTRUDER) + { +#if defined(EXT0_HEATER_PIN) && EXT0_HEATER_PIN > -1 + if((pwm_pos_set[0] = (pwm_pos[0] & HEATER_PWM_MASK)) > 0) WRITE(EXT0_HEATER_PIN,!HEATER_PINS_INVERTED); +#endif +#if defined(EXT1_HEATER_PIN) && EXT1_HEATER_PIN > -1 && NUM_EXTRUDER > 1 + if((pwm_pos_set[1] = (pwm_pos[1] & HEATER_PWM_MASK)) > 0) WRITE(EXT1_HEATER_PIN,!HEATER_PINS_INVERTED); +#endif +#if defined(EXT2_HEATER_PIN) && EXT2_HEATER_PIN > -1 && NUM_EXTRUDER > 2 + if((pwm_pos_set[2] = (pwm_pos[2] & HEATER_PWM_MASK)) > 0) WRITE(EXT2_HEATER_PIN,!HEATER_PINS_INVERTED); +#endif +#if defined(EXT3_HEATER_PIN) && EXT3_HEATER_PIN > -1 && NUM_EXTRUDER > 3 + if((pwm_pos_set[3] = (pwm_pos[3] & HEATER_PWM_MASK)) > 0) WRITE(EXT3_HEATER_PIN,!HEATER_PINS_INVERTED); +#endif +#if defined(EXT4_HEATER_PIN) && EXT4_HEATER_PIN > -1 && NUM_EXTRUDER > 4 + if((pwm_pos_set[4] = (pwm_pos[4] & HEATER_PWM_MASK)) > 0) WRITE(EXT4_HEATER_PIN,!HEATER_PINS_INVERTED); +#endif +#if defined(EXT5_HEATER_PIN) && EXT5_HEATER_PIN > -1 && NUM_EXTRUDER > 5 + if((pwm_pos_set[5] = (pwm_pos[5] & HEATER_PWM_MASK)) > 0) WRITE(EXT5_HEATER_PIN, !HEATER_PINS_INVERTED); +#endif +#if HEATED_BED_HEATER_PIN > -1 && HAVE_HEATED_BED + if((pwm_pos_set[NUM_EXTRUDER] = (pwm_pos[NUM_EXTRUDER] & HEATER_PWM_MASK)) > 0) WRITE(HEATED_BED_HEATER_PIN, !HEATER_PINS_INVERTED); +#endif + } + if(pwm_count_cooler == 0 && !PDM_FOR_COOLER) + { +#if defined(EXT0_HEATER_PIN) && EXT0_HEATER_PIN > -1 && EXT0_EXTRUDER_COOLER_PIN > -1 + if((pwm_cooler_pos_set[0] = (extruder[0].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT0_EXTRUDER_COOLER_PIN, 1); +#endif +#if !SHARED_COOLER && defined(EXT1_HEATER_PIN) && EXT1_HEATER_PIN > -1 && NUM_EXTRUDER > 1 +#if EXT1_EXTRUDER_COOLER_PIN > -1 && EXT1_EXTRUDER_COOLER_PIN != EXT0_EXTRUDER_COOLER_PIN + if((pwm_cooler_pos_set[1] = (extruder[1].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT1_EXTRUDER_COOLER_PIN, 1); +#endif +#endif +#if !SHARED_COOLER && defined(EXT2_HEATER_PIN) && EXT2_HEATER_PIN > -1 && NUM_EXTRUDER > 2 +#if EXT2_EXTRUDER_COOLER_PIN > -1 + if((pwm_cooler_pos_set[2] = (extruder[2].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT2_EXTRUDER_COOLER_PIN, 1); +#endif +#endif +#if !SHARED_COOLER && defined(EXT3_HEATER_PIN) && EXT3_HEATER_PIN > -1 && NUM_EXTRUDER > 3 +#if EXT3_EXTRUDER_COOLER_PIN > -1 + if((pwm_cooler_pos_set[3] = (extruder[3].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT3_EXTRUDER_COOLER_PIN, 1); +#endif +#endif +#if !SHARED_COOLER && defined(EXT4_HEATER_PIN) && EXT4_HEATER_PIN > -1 && NUM_EXTRUDER > 4 +#if EXT4_EXTRUDER_COOLER_PIN > -1 + if((pwm_cooler_pos_set[4] = (extruder[4].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT4_EXTRUDER_COOLER_PIN, 1); +#endif +#endif +#if !SHARED_COOLER && defined(EXT5_HEATER_PIN) && EXT5_HEATER_PIN > -1 && NUM_EXTRUDER > 5 +#if EXT5_EXTRUDER_COOLER_PIN > -1 + if((pwm_cooler_pos_set[5] = (extruder[5].coolerPWM & COOLER_PWM_MASK)) > 0) WRITE(EXT5_EXTRUDER_COOLER_PIN, 1); +#endif +#endif +#if FAN_BOARD_PIN > -1 && SHARED_COOLER_BOARD_EXT == 0 + if((pwm_pos_set[PWM_BOARD_FAN] = (pwm_pos[PWM_BOARD_FAN] & COOLER_PWM_MASK)) > 0) WRITE(FAN_BOARD_PIN,1); +#endif +#if FAN_PIN > -1 && FEATURE_FAN_CONTROL + if((pwm_pos_set[PWM_FAN1] = (pwm_pos[PWM_FAN1] & COOLER_PWM_MASK)) > 0) WRITE(FAN_PIN,1); +#endif +#if FAN2_PIN > -1 && FEATURE_FAN2_CONTROL + if((pwm_pos_set[PWM_FAN2] = (pwm_pos[PWM_FAN2] & COOLER_PWM_MASK)) > 0) WRITE(FAN2_PIN,1); +#endif +#if defined(FAN_THERMO_PIN) && FAN_THERMO_PIN > -1 + if((pwm_pos_set[PWM_FAN_THERMO] = (pwm_pos[PWM_FAN_THERMO] & COOLER_PWM_MASK)) > 0) WRITE(FAN_THERMO_PIN,1); +#endif + } +#if defined(EXT0_HEATER_PIN) && EXT0_HEATER_PIN > -1 +#if PDM_FOR_EXTRUDER + pulseDensityModulate(EXT0_HEATER_PIN, pwm_pos[0], pwm_pos_set[0], HEATER_PINS_INVERTED); +#else + if(pwm_pos_set[0] == pwm_count_heater && pwm_pos_set[0] != HEATER_PWM_MASK) WRITE(EXT0_HEATER_PIN,HEATER_PINS_INVERTED); +#endif +#if EXT0_EXTRUDER_COOLER_PIN > -1 +#if PDM_FOR_COOLER + pulseDensityModulate(EXT0_EXTRUDER_COOLER_PIN, extruder[0].coolerPWM, pwm_cooler_pos_set[0], false); +#else + if(pwm_cooler_pos_set[0] == pwm_count_cooler && pwm_cooler_pos_set[0] != COOLER_PWM_MASK) WRITE(EXT0_EXTRUDER_COOLER_PIN,0); +#endif +#endif +#endif +#if defined(EXT1_HEATER_PIN) && EXT1_HEATER_PIN > -1 && NUM_EXTRUDER > 1 +#if PDM_FOR_EXTRUDER + pulseDensityModulate(EXT1_HEATER_PIN, pwm_pos[1], pwm_pos_set[1], HEATER_PINS_INVERTED); +#else + if(pwm_pos_set[1] == pwm_count_heater && pwm_pos_set[1] != HEATER_PWM_MASK) WRITE(EXT1_HEATER_PIN,HEATER_PINS_INVERTED); +#endif +#if !SHARED_COOLER && defined(EXT1_EXTRUDER_COOLER_PIN) && EXT1_EXTRUDER_COOLER_PIN > -1 && EXT1_EXTRUDER_COOLER_PIN != EXT0_EXTRUDER_COOLER_PIN +#if PDM_FOR_COOLER + pulseDensityModulate(EXT1_EXTRUDER_COOLER_PIN, extruder[1].coolerPWM, pwm_cooler_pos_set[1], false); +#else + if(pwm_cooler_pos_set[1] == pwm_count_cooler && pwm_cooler_pos_set[1] != COOLER_PWM_MASK) WRITE(EXT1_EXTRUDER_COOLER_PIN,0); +#endif +#endif +#endif +#if defined(EXT2_HEATER_PIN) && EXT2_HEATER_PIN > -1 && NUM_EXTRUDER > 2 +#if PDM_FOR_EXTRUDER + pulseDensityModulate(EXT2_HEATER_PIN, pwm_pos[2], pwm_pos_set[2], HEATER_PINS_INVERTED); +#else + if(pwm_pos_set[2] == pwm_count_heater && pwm_pos_set[2] != HEATER_PWM_MASK) WRITE(EXT2_HEATER_PIN,HEATER_PINS_INVERTED); +#endif +#if !SHARED_COOLER && EXT2_EXTRUDER_COOLER_PIN > -1 +#if PDM_FOR_COOLER + pulseDensityModulate(EXT2_EXTRUDER_COOLER_PIN, extruder[2].coolerPWM, pwm_cooler_pos_set[2], false); +#else + if(pwm_cooler_pos_set[2] == pwm_count_cooler && pwm_cooler_pos_set[2] != COOLER_PWM_MASK) WRITE(EXT2_EXTRUDER_COOLER_PIN,0); +#endif +#endif +#endif +#if defined(EXT3_HEATER_PIN) && EXT3_HEATER_PIN>-1 && NUM_EXTRUDER > 3 +#if PDM_FOR_EXTRUDER + pulseDensityModulate(EXT3_HEATER_PIN, pwm_pos[3], pwm_pos_set[3], HEATER_PINS_INVERTED); +#else + if(pwm_pos_set[3] == pwm_count_heater && pwm_pos_set[3] != HEATER_PWM_MASK) WRITE(EXT3_HEATER_PIN,HEATER_PINS_INVERTED); +#endif +#if !SHARED_COOLER && EXT3_EXTRUDER_COOLER_PIN > -1 +#if PDM_FOR_COOLER + pulseDensityModulate(EXT3_EXTRUDER_COOLER_PIN, extruder[3].coolerPWM, pwm_cooler_pos_set[3], false); +#else + if(pwm_cooler_pos_set[3] == pwm_count_cooler && pwm_cooler_pos_set[3] != COOLER_PWM_MASK) WRITE(EXT3_EXTRUDER_COOLER_PIN,0); +#endif +#endif +#endif +#if defined(EXT4_HEATER_PIN) && EXT4_HEATER_PIN > -1 && NUM_EXTRUDER > 4 +#if PDM_FOR_EXTRUDER + pulseDensityModulate(EXT4_HEATER_PIN, pwm_pos[4], pwm_pos_set[4], HEATER_PINS_INVERTED); +#else + if(pwm_pos_set[4] == pwm_count_heater && pwm_pos_set[4] != HEATER_PWM_MASK) WRITE(EXT4_HEATER_PIN,HEATER_PINS_INVERTED); +#endif +#if !SHARED_COOLER && EXT4_EXTRUDER_COOLER_PIN > -1 +#if PDM_FOR_COOLER + pulseDensityModulate(EXT4_EXTRUDER_COOLER_PIN, extruder[4].coolerPWM, pwm_cooler_pos_set[4], false); +#else + if(pwm_cooler_pos_set[4] == pwm_count_cooler && pwm_cooler_pos_set[4] != COOLER_PWM_MASK) WRITE(EXT4_EXTRUDER_COOLER_PIN,0); +#endif +#endif +#endif +#if defined(EXT5_HEATER_PIN) && EXT5_HEATER_PIN>-1 && NUM_EXTRUDER > 5 +#if PDM_FOR_EXTRUDER + pulseDensityModulate(EXT5_HEATER_PIN, pwm_pos[5], pwm_pos_set[5], HEATER_PINS_INVERTED); +#else + if(pwm_pos_set[5] == pwm_count_heater && pwm_pos_set[5] != HEATER_PWM_MASK) WRITE(EXT5_HEATER_PIN,HEATER_PINS_INVERTED); +#endif +#if !SHARED_COOLER && EXT5_EXTRUDER_COOLER_PIN > -1 +#if PDM_FOR_COOLER + pulseDensityModulate(EXT5_EXTRUDER_COOLER_PIN, extruder[5].coolerPWM, pwm_cooler_pos_set[5], false); +#else + if(pwm_cooler_pos_set[5] == pwm_count_cooler && pwm_cooler_pos_set[5] != COOLER_PWM_MASK) WRITE(EXT5_EXTRUDER_COOLER_PIN,0); +#endif +#endif +#endif +#if FAN_BOARD_PIN > -1 && SHARED_COOLER_BOARD_EXT == 0 +#if PDM_FOR_COOLER + pulseDensityModulate(FAN_BOARD_PIN, pwm_pos[PWM_BOARD_FAN], pwm_pos_set[PWM_BOARD_FAN], false); +#else + if(pwm_pos_set[PWM_BOARD_FAN] == pwm_count_cooler && pwm_pos_set[NUM_EXTRUDER + 1] != COOLER_PWM_MASK) WRITE(FAN_BOARD_PIN,0); +#endif +#endif +#if FAN_PIN > -1 && FEATURE_FAN_CONTROL + if(fanKickstart == 0) + { +#if PDM_FOR_COOLER + pulseDensityModulate(FAN_PIN, pwm_pos[PWM_FAN1], pwm_pos_set[PWM_FAN1], false); +#else + if(pwm_pos_set[PWM_FAN1] == pwm_count_cooler && pwm_pos_set[PWM_FAN1] != COOLER_PWM_MASK) WRITE(FAN_PIN,0); +#endif + } +#endif +#if FAN2_PIN > -1 && FEATURE_FAN2_CONTROL +if(fan2Kickstart == 0) +{ + #if PDM_FOR_COOLER + pulseDensityModulate(FAN2_PIN, pwm_pos[PWM_FAN2], pwm_pos_set[PWM_FAN2], false); + #else + if(pwm_pos_set[PWM_FAN2] == pwm_count_cooler && pwm_pos_set[PWM_FAN2] != COOLER_PWM_MASK) WRITE(FAN2_PIN,0); + #endif +} +#endif +#if defined(FAN_THERMO_PIN) && FAN_THERMO_PIN > -1 + #if PDM_FOR_COOLER + pulseDensityModulate(FAN_THERMO_PIN, pwm_pos[PWM_FAN_THERMO], pwm_pos_set[PWM_FAN_THERMO], false); + #else + if(pwm_pos_set[PWM_FAN_THERMO] == pwm_count_cooler && pwm_pos_set[PWM_FAN_THERMO] != COOLER_PWM_MASK) WRITE(FAN_THERMO_PIN,0); + #endif +#endif +#if HEATED_BED_HEATER_PIN > -1 && HAVE_HEATED_BED +#if PDM_FOR_EXTRUDER + pulseDensityModulate(HEATED_BED_HEATER_PIN, pwm_pos[NUM_EXTRUDER], pwm_pos_set[NUM_EXTRUDER], HEATER_PINS_INVERTED); +#else + if(pwm_pos_set[NUM_EXTRUDER] == pwm_count_heater && pwm_pos_set[NUM_EXTRUDER] != HEATER_PWM_MASK) WRITE(HEATED_BED_HEATER_PIN,HEATER_PINS_INVERTED); +#endif +#endif + HAL::allowInterrupts(); + counterPeriodical++; // Approximate a 100ms timer + if(counterPeriodical >= (int)(F_CPU/40960)) + { + counterPeriodical = 0; + executePeriodical = 1; +#if FEATURE_FAN_CONTROL + if (fanKickstart) fanKickstart--; +#endif +#if FEATURE_FAN2_CONTROL + if (fan2Kickstart) fan2Kickstart--; +#endif + } +// read analog values +#if ANALOG_INPUTS > 0 + if((ADCSRA & _BV(ADSC)) == 0) // Conversion finished? + { + osAnalogInputBuildup[osAnalogInputPos] += ADCW; + if(++osAnalogInputCounter[osAnalogInputPos] >= _BV(ANALOG_INPUT_SAMPLE)) + { +#if ANALOG_INPUT_BITS + ANALOG_INPUT_SAMPLE < 12 + osAnalogInputValues[osAnalogInputPos] = + osAnalogInputBuildup[osAnalogInputPos] << (12 - ANALOG_INPUT_BITS - ANALOG_INPUT_SAMPLE); +#endif +#if ANALOG_INPUT_BITS + ANALOG_INPUT_SAMPLE > 12 + osAnalogInputValues[osAnalogInputPos] = + osAnalogInputBuildup[osAnalogInputPos] >> (ANALOG_INPUT_BITS + ANALOG_INPUT_SAMPLE - 12); +#endif +#if ANALOG_INPUT_BITS + ANALOG_INPUT_SAMPLE == 12 + osAnalogInputValues[osAnalogInputPos] = osAnalogInputBuildup[osAnalogInputPos]; +#endif + osAnalogInputBuildup[osAnalogInputPos] = 0; + osAnalogInputCounter[osAnalogInputPos] = 0; + // Start next conversion + if(++osAnalogInputPos >= ANALOG_INPUTS) osAnalogInputPos = 0; + uint8_t channel = pgm_read_byte(&osAnalogInputChannels[osAnalogInputPos]); +#if defined(ADCSRB) && defined(MUX5) + if(channel & 8) // Reading channel 0-7 or 8-15? + ADCSRB |= _BV(MUX5); + else + ADCSRB &= ~_BV(MUX5); +#endif + ADMUX = (ADMUX & ~(0x1F)) | (channel & 7); + } + ADCSRA |= _BV(ADSC); // start next conversion + } +#endif + + UI_FAST; // Short timed user interface action + pwm_count_cooler += COOLER_PWM_STEP; + pwm_count_heater += HEATER_PWM_STEP; +#if FEATURE_WATCHDOG + if(HAL::wdPinged) { + wdt_reset(); + HAL::wdPinged = false; + } +#endif +} +#if USE_ADVANCE + +static int8_t extruderLastDirection = 0; +#ifndef ADVANCE_DIR_FILTER_STEPS +#define ADVANCE_DIR_FILTER_STEPS 2 +#endif + +void HAL::resetExtruderDirection() +{ + extruderLastDirection = 0; +} +/** \brief Timer routine for extruder stepper. + +Several methods need to move the extruder. To get a optima result, +all methods update the printer_state.extruderStepsNeeded with the +number of additional steps needed. During this interrupt, one step +is executed. This will keep the extruder moving, until the total +wanted movement is achieved. This will be done with the maximum +allowable speed for the extruder. +*/ +ISR(EXTRUDER_TIMER_VECTOR) +{ + uint8_t timer = EXTRUDER_OCR; + if(!Printer::isAdvanceActivated()) return; // currently no need + if(Printer::extruderStepsNeeded > 0 && extruderLastDirection != 1) + { + if(Printer::extruderStepsNeeded >= ADVANCE_DIR_FILTER_STEPS) + { + Extruder::setDirection(true); + extruderLastDirection = 1; + timer += 40; // Add some more wait time to prevent blocking + } + } + else if(Printer::extruderStepsNeeded < 0 && extruderLastDirection != -1) + { + if(-Printer::extruderStepsNeeded >= ADVANCE_DIR_FILTER_STEPS) + { + Extruder::setDirection(false); + extruderLastDirection = -1; + timer += 40; // Add some more wait time to prevent blocking + } + } + else if(Printer::extruderStepsNeeded != 0) + { + Extruder::step(); + Printer::extruderStepsNeeded -= extruderLastDirection; + Printer::insertStepperHighDelay(); + Extruder::unstep(); + } + EXTRUDER_OCR = timer + Printer::maxExtruderSpeed; +} +#endif + +#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 +*/ + +ring_buffer rx_buffer = { { 0 }, 0, 0}; +ring_buffer_tx tx_buffer = { { 0 }, 0, 0}; + +inline void rf_store_char(unsigned char c, ring_buffer *buffer) +{ + uint8_t i = (buffer->head + 1) & SERIAL_BUFFER_MASK; + + // if we should be storing the received character into the location + // just before the tail (meaning that the head would advance to the + // current location of the tail), we're about to overflow the buffer + // and so we don't write the character or advance the head. + if (i != buffer->tail) + { + buffer->buffer[buffer->head] = c; + buffer->head = i; + } +} +#if !defined(USART0_RX_vect) && defined(USART1_RX_vect) +// do nothing - on the 32u4 the first USART is USART1 +#else +void rfSerialEvent() __attribute__((weak)); +void rfSerialEvent() {} +#define serialEvent_implemented +#if defined(USART_RX_vect) +SIGNAL(USART_RX_vect) +#elif defined(USART0_RX_vect) +SIGNAL(USART0_RX_vect) +#else +#if defined(SIG_USART0_RECV) +SIGNAL(SIG_USART0_RECV) +#elif defined(SIG_UART0_RECV) +SIGNAL(SIG_UART0_RECV) +#elif defined(SIG_UART_RECV) +SIGNAL(SIG_UART_RECV) +#else +#error "Don't know what the Data Received vector is called for the first UART" +#endif +#endif +{ +#if defined(UDR0) + uint8_t c = UDR0; +#elif defined(UDR) + uint8_t c = UDR; +#else +#error UDR not defined +#endif + rf_store_char(c, &rx_buffer); +} +#endif + +#if !defined(USART0_UDRE_vect) && defined(USART1_UDRE_vect) +// do nothing - on the 32u4 the first USART is USART1 +#else +#if !defined(UART0_UDRE_vect) && !defined(UART_UDRE_vect) && !defined(USART0_UDRE_vect) && !defined(USART_UDRE_vect) +#error "Don't know what the Data Register Empty vector is called for the first UART" +#else +#if defined(UART0_UDRE_vect) +ISR(UART0_UDRE_vect) +#elif defined(UART_UDRE_vect) +ISR(UART_UDRE_vect) +#elif defined(USART0_UDRE_vect) +ISR(USART0_UDRE_vect) +#elif defined(USART_UDRE_vect) +ISR(USART_UDRE_vect) +#endif +{ + if (tx_buffer.head == tx_buffer.tail) + { + // Buffer empty, so disable interrupts +#if defined(UCSR0B) + bit_clear(UCSR0B, UDRIE0); +#else + bit_clear(UCSRB, UDRIE); +#endif + } + else + { + // There is more data in the output buffer. Send the next byte + uint8_t c = tx_buffer.buffer[tx_buffer.tail]; +#if defined(UDR0) + UDR0 = c; +#elif defined(UDR) + UDR = c; +#else +#error UDR not defined +#endif + tx_buffer.tail = (tx_buffer.tail + 1) & SERIAL_TX_BUFFER_MASK; + } +} +#endif +#endif + +#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 +#if !(defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega1284__) || defined(__AVR_ATmega2561__) || defined(__AVR_ATmega1281__) || defined (__AVR_ATmega644__) || defined (__AVR_ATmega644P__)) +#error BlueTooth option cannot be used with your mainboard +#endif +#if BLUETOOTH_SERIAL > 1 && !(defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)) +#error BlueTooth serial 2 or 3 can be used only with boards based on ATMega2560 or ATMega1280 +#endif +#if (BLUETOOTH_SERIAL == 1) +#if defined(USART1_RX_vect) +#define SIG_USARTx_RECV USART1_RX_vect +#define USARTx_UDRE_vect USART1_UDRE_vect +#else +#define SIG_USARTx_RECV SIG_USART1_RECV +#define USARTx_UDRE_vect SIG_USART1_DATA +#endif +#define UDRx UDR1 +#define UCSRxA UCSR1A +#define UCSRxB UCSR1B +#define UBRRxH UBRR1H +#define UBRRxL UBRR1L +#define U2Xx U2X1 +#define UARTxENABLE ((1< 4095) && use_u2x) + { + use_u2x = false; + goto try_again; + } + + // assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register) + *_ubrrh = baud_setting >> 8; + *_ubrrl = baud_setting; + + bit_set(*_ucsrb, _rxen); + bit_set(*_ucsrb, _txen); + bit_set(*_ucsrb, _rxcie); + bit_clear(*_ucsrb, _udrie); +#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 + WRITE(RXxPIN,1); // Pullup on RXDx + UCSRxA = (1<> 8); + UBRRxL = (uint8_t)(((F_CPU / 4 / BLUETOOTH_BAUD -1) / 2) & 0xFF); + UCSRxB |= UARTxENABLE; +#endif +} + +void RFHardwareSerial::end() +{ + // wait for transmission of outgoing data + while (_tx_buffer->head != _tx_buffer->tail) + ; + + bit_clear(*_ucsrb, _rxen); + bit_clear(*_ucsrb, _txen); + bit_clear(*_ucsrb, _rxcie); + bit_clear(*_ucsrb, _udrie); + +#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 + UCSRxB = 0; +#endif + // clear a ny received data + _rx_buffer->head = _rx_buffer->tail; +} + +int RFHardwareSerial::available(void) +{ + return (unsigned int)(SERIAL_BUFFER_SIZE + _rx_buffer->head - _rx_buffer->tail) & SERIAL_BUFFER_MASK; +} +int RFHardwareSerial::outputUnused(void) +{ + return SERIAL_TX_BUFFER_SIZE - (unsigned int)((SERIAL_TX_BUFFER_SIZE + _tx_buffer->head - _tx_buffer->tail) & SERIAL_TX_BUFFER_MASK); +} + +int RFHardwareSerial::peek(void) +{ + if (_rx_buffer->head == _rx_buffer->tail) + { + return -1; + } + return _rx_buffer->buffer[_rx_buffer->tail]; +} + +int RFHardwareSerial::read(void) +{ + // if the head isn't ahead of the tail, we don't have any characters + if (_rx_buffer->head == _rx_buffer->tail) + { + return -1; + } + unsigned char c = _rx_buffer->buffer[_rx_buffer->tail]; + _rx_buffer->tail = (_rx_buffer->tail + 1) & SERIAL_BUFFER_MASK; + return c; +} + +void RFHardwareSerial::flush() +{ + while (_tx_buffer->head != _tx_buffer->tail) + ; +#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 + while (_tx_buffer->head != txx_buffer_tail) ; +#endif +} +#ifdef COMPAT_PRE1 +void +#else +size_t +#endif +RFHardwareSerial::write(uint8_t c) +{ + uint8_t i = (_tx_buffer->head + 1) & SERIAL_TX_BUFFER_MASK; + + // If the output buffer is full, there's nothing for it other than to + // wait for the interrupt handler to empty it a bit + while (i == _tx_buffer->tail) {} +#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 + while (i == txx_buffer_tail) {} +#endif + _tx_buffer->buffer[_tx_buffer->head] = c; + _tx_buffer->head = i; + + bit_set(*_ucsrb, _udrie); +#if defined(BLUETOOTH_SERIAL) && BLUETOOTH_SERIAL > 0 + bit_set(UCSRxB, UDRIEx); +#endif +#ifndef COMPAT_PRE1 + return 1; +#endif +} + +// Preinstantiate Objects ////////////////////////////////////////////////////// + +#if defined(UBRRH) && defined(UBRRL) +RFHardwareSerial RFSerial(&rx_buffer, &tx_buffer, &UBRRH, &UBRRL, &UCSRA, &UCSRB, &UDR, RXEN, TXEN, RXCIE, UDRIE, U2X); +#elif defined(UBRR0H) && defined(UBRR0L) +RFHardwareSerial RFSerial(&rx_buffer, &tx_buffer, &UBRR0H, &UBRR0L, &UCSR0A, &UCSR0B, &UDR0, RXEN0, TXEN0, RXCIE0, UDRIE0, U2X0); +#elif defined(USBCON) +// do nothing - Serial object and buffers are initialized in CDC code +#else +#error no serial port defined (port 0) +#endif + +#endif + diff --git a/Repetier/HAL.h b/Repetier/HAL.h index 685678c..4c49418 100644 --- a/Repetier/HAL.h +++ b/Repetier/HAL.h @@ -70,7 +70,9 @@ All known arduino boards use 64. This value is needed for the extruder timing. * #endif #include #include "Print.h" - +#ifdef EXTERNALSERIAL +#define SERIAL_RX_BUFFER_SIZE 128 +#endif #if defined(ARDUINO) && ARDUINO >= 100 #include "Arduino.h" #else @@ -132,7 +134,7 @@ public: #define I2C_WRITE 0 #if NONLINEAR_SYSTEM -// Maximum speed with 100% inerrupt utilization is 27000 hz at 16MHz cpu +// Maximum speed with 100% interrupt utilization is 27000 hz at 16MHz cpu // leave some margin for all the extra transformations. So we keep inside clean timings. #define LIMIT_INTERVAL ((F_CPU/30000)+1) #else @@ -174,9 +176,16 @@ typedef uint8_t ufast8_t; */ #define SERIAL_BUFFER_SIZE 128 -#define SERIAL_BUFFER_MASK 127 +#define SERIAL_BUFFER_MASK 127 +#undef SERIAL_TX_BUFFER_SIZE +#undef SERIAL_TX_BUFFER_MASK +#ifdef BIG_OUTPUT_BUFFER +#define SERIAL_TX_BUFFER_SIZE 128 +#define SERIAL_TX_BUFFER_MASK 127 +#else #define SERIAL_TX_BUFFER_SIZE 64 #define SERIAL_TX_BUFFER_MASK 63 +#endif struct ring_buffer { @@ -251,8 +260,11 @@ extern RFHardwareSerial RFSerial; #define OUT_LN Com::println() class HAL -{ -public: +{ +public: +#if FEATURE_WATCHDOG + static bool wdPinged; +#endif HAL(); virtual ~HAL(); static inline void hwSetup(void) @@ -601,7 +613,7 @@ public: SET_OUTPUT(SDSSORIG); #endif // set SS high - may be chip select for another SPI device -#if SET_SPI_SS_HIGH +#if defined(SET_SPI_SS_HIGH) && SET_SPI_SS_HIGH WRITE(SDSS, HIGH); #endif // SET_SPI_SS_HIGH #endif @@ -710,8 +722,8 @@ public: } inline static void pingWatchdog() { -#if FEATURE_WATCHDOG - wdt_reset(); +#if FEATURE_WATCHDOG + wdPinged = true; #endif }; inline static float maxExtruderTimerFrequency() @@ -756,5 +768,3 @@ private: #define PWM_OCIE OCIE0B //#endif #endif // HAL_H - - diff --git a/Repetier/Printer.cpp b/Repetier/Printer.cpp index 024d3cb..0d02a2d 100644 --- a/Repetier/Printer.cpp +++ b/Repetier/Printer.cpp @@ -19,7 +19,7 @@ #include "Repetier.h" #if USE_ADVANCE -uint8_t Printer::maxExtruderSpeed; ///< Timer delay for end extruder speed +ufast8_t Printer::maxExtruderSpeed; ///< Timer delay for end extruder speed volatile int Printer::extruderStepsNeeded; ///< This many extruder steps are still needed, <0 = reverse steps needed. //uint8_t Printer::extruderAccelerateDelay; ///< delay between 2 speec increases #endif @@ -41,8 +41,10 @@ unsigned long Printer::maxTravelAccelerationStepsPerSquareSecond[E_AXIS_ARRAY]; #if NONLINEAR_SYSTEM long Printer::currentDeltaPositionSteps[E_TOWER_ARRAY]; uint8_t lastMoveID = 0; // Last move ID +#else +int32_t Printer::zCorrectionStepsIncluded = 0; #endif -int8_t Printer::zBabystepsMissing = 0; +int16_t Printer::zBabystepsMissing = 0; uint8_t Printer::relativeCoordinateMode = false; ///< Determines absolute (false) or relative Coordinates (true). uint8_t Printer::relativeExtruderCoordinateMode = false; ///< Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode. @@ -55,15 +57,22 @@ uint8_t Printer::flag0 = 0; uint8_t Printer::flag1 = 0; uint8_t Printer::flag2 = 0; uint8_t Printer::debugLevel = 6; ///< Bitfield defining debug output. 1 = echo, 2 = info, 4 = error, 8 = dry run., 16 = Only communication, 32 = No moves -uint8_t Printer::stepsPerTimerCall = 1; +fast8_t Printer::stepsPerTimerCall = 1; uint8_t Printer::menuMode = 0; +uint8_t Printer::mode = DEFAULT_PRINTER_MODE; +uint8_t Printer::fanSpeed = 0; // Last fan speed set with M106/M107 float Printer::extrudeMultiplyError = 0; float Printer::extrusionFactor = 1.0; uint8_t Printer::interruptEvent = 0; +#if EEPROM_MODE != 0 +float Printer::zBedOffset = HAL::eprGetFloat(EPR_Z_PROBE_Z_OFFSET); +#else +float Printer::zBedOffset = Z_PROBE_Z_OFFSET; +#endif #if FEATURE_AUTOLEVEL float Printer::autolevelTransformation[9]; ///< Transformation matrix #endif -uint32_t Printer::interval; ///< Last step duration in ticks. +uint32_t Printer::interval = 30000; ///< Last step duration in ticks. uint32_t Printer::timer; ///< used for acceleration/deceleration timing uint32_t Printer::stepNumber; ///< Step number in current move. #if USE_ADVANCE @@ -135,9 +144,6 @@ float Printer::backlashY; float Printer::backlashZ; uint8_t Printer::backlashDir; #endif -#ifdef DEBUG_STEPCOUNT -int32_t Printer::totalStepsRemaining; -#endif float Printer::memoryX; float Printer::memoryY; float Printer::memoryZ; @@ -147,6 +153,10 @@ float Printer::memoryF = -1; int8_t Printer::motorX; int8_t Printer::motorYorZ; #endif +#if FAN_THERMO_PIN > -1 +float Printer::thermoMinTemp = FAN_THERMO_MIN_TEMP; +float Printer::thermoMaxTemp = FAN_THERMO_MAX_TEMP; +#endif #ifdef DEBUG_SEGMENT_LENGTH float Printer::maxRealSegmentLength = 0; #endif @@ -161,10 +171,13 @@ wizardVar Printer::wizardStack[WIZARD_STACK_SIZE]; flag8_t Endstops::lastState = 0; flag8_t Endstops::lastRead = 0; +flag8_t Endstops::accumulator = 0; #ifdef EXTENDED_ENDSTOPS flag8_t Endstops::lastState2 = 0; flag8_t Endstops::lastRead2 = 0; +flag8_t Endstops::accumulator2 = 0; #endif + void Endstops::update() { flag8_t newRead = 0; #ifdef EXTENDED_ENDSTOPS @@ -212,8 +225,10 @@ void Endstops::update() { #endif ) { // Report endstop hit changes lastState = lastRead; + accumulator |= lastState; #ifdef EXTENDED_ENDSTOPS lastState2 = lastRead2; + accumulator2 |= lastState2; #endif #ifdef DEBUG_ENDSTOPS report(); @@ -278,7 +293,7 @@ void Printer::constrainDestinationCoords() if (destinationSteps[Y_AXIS] < yMinSteps) Printer::destinationSteps[Y_AXIS] = Printer::yMinSteps; #endif #if min_software_endstop_z - if (destinationSteps[Z_AXIS] < zMinSteps && !isZProbingActive()) Printer::destinationSteps[Z_AXIS] = Printer::zMinSteps; + if (isAutolevelActive() == false && destinationSteps[Z_AXIS] < zMinSteps && !isZProbingActive()) Printer::destinationSteps[Z_AXIS] = Printer::zMinSteps; #endif #if max_software_endstop_x @@ -288,11 +303,33 @@ void Printer::constrainDestinationCoords() if (destinationSteps[Y_AXIS] > Printer::yMaxSteps) Printer::destinationSteps[Y_AXIS] = Printer::yMaxSteps; #endif #if max_software_endstop_z - if (destinationSteps[Z_AXIS] > Printer::zMaxSteps && !isZProbingActive()) Printer::destinationSteps[Z_AXIS] = Printer::zMaxSteps; + if (isAutolevelActive() == false && destinationSteps[Z_AXIS] > Printer::zMaxSteps && !isZProbingActive()) Printer::destinationSteps[Z_AXIS] = Printer::zMaxSteps; #endif } #endif - +void Printer::setDebugLevel(uint8_t newLevel) { + debugLevel = newLevel; + Com::printFLN(PSTR("DebugLevel:"),(int)newLevel); +} +void Printer::toggleEcho() { + setDebugLevel(debugLevel ^ 32); +} +void Printer::toggleInfo() { + setDebugLevel(debugLevel ^ 2); +} +void Printer::toggleErrors() { + setDebugLevel(debugLevel ^ 4); +} +void Printer::toggleDryRun() { + setDebugLevel(debugLevel ^ 8); +} +void Printer::toggleCommunication() { + setDebugLevel(debugLevel ^ 16); +} +void Printer::toggleNoMoves() { + setDebugLevel(debugLevel ^ 32); +} + bool Printer::isPositionAllowed(float x,float y,float z) { if(isNoDestinationCheck()) return true; @@ -308,6 +345,49 @@ bool Printer::isPositionAllowed(float x,float y,float z) } return allowed; } + +void Printer::setFanSpeedDirectly(uint8_t speed) { +#if FAN_PIN > -1 && FEATURE_FAN_CONTROL + if(pwm_pos[PWM_FAN1] == speed) + return; +#if FAN_KICKSTART_TIME + if(fanKickstart == 0 && speed > pwm_pos[PWM_FAN1] && speed < 85) + { + if(pwm_pos[PWM_FAN1]) fanKickstart = FAN_KICKSTART_TIME / 100; + else fanKickstart = FAN_KICKSTART_TIME / 25; + } +#endif + pwm_pos[PWM_FAN1] = speed; +#endif +} +void Printer::setFan2SpeedDirectly(uint8_t speed) { + #if FAN2_PIN > -1 && FEATURE_FAN2_CONTROL + if(pwm_pos[PWM_FAN2] == speed) + return; + #if FAN_KICKSTART_TIME + if(fan2Kickstart == 0 && speed > pwm_pos[PWM_FAN2] && speed < 85) + { + if(pwm_pos[PWM_FAN2]) fan2Kickstart = FAN_KICKSTART_TIME / 100; + else fan2Kickstart = FAN_KICKSTART_TIME / 25; + } + #endif + pwm_pos[PWM_FAN2] = speed; + #endif +} + +void Printer::reportPrinterMode() { + switch(Printer::mode) { + case PRINTER_MODE_FFF: + Com::printFLN(Com::tPrinterModeFFF); + break; + case PRINTER_MODE_LASER: + Com::printFLN(Com::tPrinterModeLaser); + break; + case PRINTER_MODE_CNC: + Com::printFLN(Com::tPrinterModeCNC); + break; + } +} void Printer::updateDerivedParameter() { #if DRIVE_SYSTEM == DELTA @@ -429,14 +509,19 @@ void Printer::kill(uint8_t only_steppers) #endif // defined disableXStepper(); disableYStepper(); +#if !defined(PREVENT_Z_DISABLE_ON_STEPPER_TIMEOUT) disableZStepper(); +#else + if(!only_steppers) + disableZStepper(); +#endif Extruder::disableAllExtruderMotors(); if(!only_steppers) { for(uint8_t i = 0; i < NUM_TEMPERATURE_LOOPS; i++) Extruder::setTemperatureForExtruder(0, i); Extruder::setHeatedBedTemperature(0); - UI_STATUS_UPD(UI_TEXT_STANDBY); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_STANDBY_ID)); #if defined(PS_ON_PIN) && PS_ON_PIN>-1 //pinMode(PS_ON_PIN,INPUT); SET_OUTPUT(PS_ON_PIN); //GND @@ -445,12 +530,12 @@ void Printer::kill(uint8_t only_steppers) #endif Printer::setAllKilled(true); } - else UI_STATUS_UPD(UI_TEXT_STEPPER_DISABLED); -#if FAN_BOARD_PIN>-1 + else UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_STEPPER_DISABLED_ID)); +#if FAN_BOARD_PIN > -1 #if HAVE_HEATED_BED if(heatedBedController.targetTemperatureC < 15) // turn off FAN_BOARD only if bed heater is off #endif - pwm_pos[NUM_EXTRUDER + 1] = 0; + pwm_pos[PWM_BOARD_FAN] = 0; #endif // FAN_BOARD_PIN } @@ -499,7 +584,7 @@ uint8_t Printer::moveTo(float x,float y,float z,float e,float f) } // Move to transformed cartesian coordinates, mapping real (model) space to printer space -uint8_t Printer::moveToReal(float x, float y, float z, float e, float f) +uint8_t Printer::moveToReal(float x, float y, float z, float e, float f,bool pathOptimize) { if(x == IGNORE_COORDINATE) x = currentPosition[X_AXIS]; @@ -537,7 +622,7 @@ uint8_t Printer::moveToReal(float x, float y, float z, float e, float f) feedrate = f; #if NONLINEAR_SYSTEM - if (!PrintLine::queueDeltaMove(ALWAYS_CHECK_ENDSTOPS, true, true)) + if (!PrintLine::queueDeltaMove(ALWAYS_CHECK_ENDSTOPS, pathOptimize, true)) { Com::printWarningFLN(PSTR("moveToReal / queueDeltaMove returns error")); SHOWM(x); @@ -546,7 +631,7 @@ uint8_t Printer::moveToReal(float x, float y, float z, float e, float f) return 0; } #else - PrintLine::queueCartesianMove(ALWAYS_CHECK_ENDSTOPS, true); + PrintLine::queueCartesianMove(ALWAYS_CHECK_ENDSTOPS, pathOptimize); #endif return 1; } @@ -563,7 +648,11 @@ void Printer::updateCurrentPosition(bool copyLastCmd) { currentPosition[X_AXIS] = static_cast(currentPositionSteps[X_AXIS]) * invAxisStepsPerMM[X_AXIS]; currentPosition[Y_AXIS] = static_cast(currentPositionSteps[Y_AXIS]) * invAxisStepsPerMM[Y_AXIS]; +#if NONLINEAR_SYSTEM currentPosition[Z_AXIS] = static_cast(currentPositionSteps[Z_AXIS]) * invAxisStepsPerMM[Z_AXIS]; +#else + currentPosition[Z_AXIS] = static_cast(currentPositionSteps[Z_AXIS] - zCorrectionStepsIncluded) * invAxisStepsPerMM[Z_AXIS]; +#endif #if FEATURE_AUTOLEVEL if(isAutolevelActive()) transformFromPrinter(currentPosition[X_AXIS], currentPosition[Y_AXIS], currentPosition[Z_AXIS], @@ -678,6 +767,9 @@ void Printer::setup() #if FEATURE_CONTROLLER == CONTROLLER_VIKI HAL::delayMilliseconds(100); #endif // FEATURE_CONTROLLER +#if UI_DISPLAY_TYPE != NO_DISPLAY + Com::selectLanguage(0); // just make sure we have a language in case someone uses it early +#endif //HAL::delayMilliseconds(500); // add a delay at startup to give hardware time for initalization #if defined(EEPROM_AVAILABLE) && defined(EEPROM_SPI_ALLIGATOR) && EEPROM_AVAILABLE == EEPROM_SPI_ALLIGATOR HAL::spiBegin(); @@ -791,7 +883,16 @@ void Printer::setup() #endif #endif - //endstop pullups +#if FEATURE_THREE_ZSTEPPER + SET_OUTPUT(Z3_STEP_PIN); + SET_OUTPUT(Z3_DIR_PIN); +#if Z3_ENABLE_PIN > -1 + SET_OUTPUT(Z3_ENABLE_PIN); + WRITE(Z3_ENABLE_PIN, !Z_ENABLE_ON); +#endif +#endif + + //end stop pull ups #if MIN_HARDWARE_ENDSTOP_X #if X_MIN_PIN > -1 SET_INPUT(X_MIN_PIN); @@ -858,10 +959,18 @@ void Printer::setup() PULLUP(Z_PROBE_PIN, HIGH); #endif #endif // FEATURE_FEATURE_Z_PROBE -#if FAN_PIN>-1 && FEATURE_FAN_CONTROL +#if FAN_PIN > -1 && FEATURE_FAN_CONTROL SET_OUTPUT(FAN_PIN); WRITE(FAN_PIN, LOW); #endif +#if FAN2_PIN > -1 && FEATURE_FAN2_CONTROL + SET_OUTPUT(FAN2_PIN); + WRITE(FAN2_PIN, LOW); +#endif +#if FAN_THERMO_PIN > -1 + SET_OUTPUT(FAN_THERMO_PIN); + WRITE(FAN_THERMO_PIN, LOW); +#endif #if FAN_BOARD_PIN>-1 SET_OUTPUT(FAN_BOARD_PIN); WRITE(FAN_BOARD_PIN, LOW); @@ -914,7 +1023,7 @@ void Printer::setup() SET_OUTPUT(EXT5_EXTRUDER_COOLER_PIN); WRITE(EXT5_EXTRUDER_COOLER_PIN, LOW); #endif -// Initalize jam sensors +// Initialize jam sensors #if defined(EXT0_JAM_PIN) && EXT0_JAM_PIN > -1 SET_INPUT(EXT0_JAM_PIN); PULLUP(EXT0_JAM_PIN, EXT0_JAM_PULLUP); @@ -947,6 +1056,13 @@ void Printer::setup() SET_OUTPUT(EXP_VOLTAGE_LEVEL_PIN); WRITE(EXP_VOLTAGE_LEVEL_PIN,UI_VOLTAGE_LEVEL); #endif // UI_VOLTAGE_LEVEL +#if defined(SUPPORT_LASER) && SUPPORT_LASER + LaserDriver::initialize(); +#endif // defined +#if defined(SUPPORT_CNC) && SUPPORT_CNC + CNCDriver::initialize(); +#endif // defined + #if GANTRY Printer::motorX = 0; Printer::motorYorZ = 0; @@ -1009,16 +1125,16 @@ void Printer::setup() EEPROM::initBaudrate(); HAL::serialSetBaudrate(baudrate); Com::printFLN(Com::tStart); - UI_INITIALIZE; HAL::showStartReason(); Extruder::initExtruder(); - // sets autoleveling in eeprom init + // sets auto leveling in eeprom init EEPROM::init(); // Read settings from eeprom if wanted + UI_INITIALIZE; for(uint8_t i = 0; i < E_AXIS_ARRAY; i++) { currentPositionSteps[i] = 0; - currentPosition[i] = 0.0; } + currentPosition[X_AXIS] = currentPosition[Y_AXIS]= currentPosition[Z_AXIS] = 0.0; //setAutolevelActive(false); // fixme delete me //Commands::printCurrentPosition(PSTR("Printer::setup 0 ")); #if DISTORTION_CORRECTION @@ -1040,12 +1156,12 @@ void Printer::setup() Commands::printCurrentPosition(PSTR("Printer::setup ")); #endif // DRIVE_SYSTEM Extruder::selectExtruderById(0); -#if SDSUPPORT - sd.initsd(); -#endif #if FEATURE_WATCHDOG HAL::startWatchdog(); #endif // FEATURE_WATCHDOG +#if SDSUPPORT + sd.mount(); +#endif #if FEATURE_SERVO // set servos to neutral positions at power_up #if defined(SERVO0_NEUTRAL_POS) && SERVO0_NEUTRAL_POS >= 500 HAL::servoMicroseconds(0,SERVO0_NEUTRAL_POS, 1000); @@ -1061,6 +1177,15 @@ void Printer::setup() #endif #endif EVENT_INITIALIZE; +#ifdef STARTUP_GCODE +GCode::executeFString(Com::tStartupGCode); +#endif +#if EEPROM_MODE != 0 && UI_DISPLAY_TYPE != NO_DISPLAY + if(EEPROM::getStoredLanguage() == 254) { + Com::printFLN(PSTR("Needs language selection")); + uid.showLanguageSelectionWizard(); + } +#endif // EEPROM_MODE } void Printer::defaultLoopActions() @@ -1080,7 +1205,7 @@ void Printer::defaultLoopActions() if(stepperInactiveTime != 0 && curtime > stepperInactiveTime ) Printer::kill(true); } -#if SDCARDDETECT>-1 && SDSUPPORT +#if SDCARDDETECT > -1 && SDSUPPORT sd.automount(); #endif DEBUG_MEMORY; @@ -1097,7 +1222,7 @@ void Printer::MemoryPosition() void Printer::GoToMemoryPosition(bool x, bool y, bool z, bool e, float feed) { - if(memoryF < 0) return; // Not stored before call, so we ignor eit + if(memoryF < 0) return; // Not stored before call, so we ignore it bool all = !(x || y || z); moveToReal((all || x ? (lastCmdPos[X_AXIS] = memoryX) : IGNORE_COORDINATE) ,(all || y ?(lastCmdPos[Y_AXIS] = memoryY) : IGNORE_COORDINATE) @@ -1118,7 +1243,7 @@ void Printer::deltaMoveToTopEndstops(float feedrate) Printer::stepsRemainingAtZHit = -1; setHoming(true); transformCartesianStepsToDeltaSteps(currentPositionSteps, currentDeltaPositionSteps); - PrintLine::moveRelativeDistanceInSteps(0, 0, zMaxSteps * 1.5, 0, feedrate, true, true); + PrintLine::moveRelativeDistanceInSteps(0, 0, (zMaxSteps + EEPROM::deltaDiagonalRodLength()*axisStepsPerMM[Z_AXIS]) * 1.5, 0, feedrate, true, true); offsetX = offsetY = offsetZ = 0; setHoming(false); } @@ -1141,27 +1266,31 @@ void Printer::homeYAxis() void Printer::homeZAxis() // Delta z homing { bool homingSuccess = false; + Endstops::resetAccumulator(); deltaMoveToTopEndstops(Printer::homingFeedrate[Z_AXIS]); // New safe homing routine by Kyrre Aalerud // This method will safeguard against sticky endstops such as may be gotten cheaply from china. // This can lead to headcrashes and even fire, thus a safer algorithm to ensure the endstops actually respond as expected. //Endstops::report(); - // Check that all endstoips (XYZ) were hit + // Check that all endstops (XYZ) were hit + Endstops::fillFromAccumulator(); if (Endstops::xMax() && Endstops::yMax() && Endstops::zMax()) { // Back off for retest - PrintLine::moveRelativeDistanceInSteps(0, 0, 2 * axisStepsPerMM[Z_AXIS] * -ENDSTOP_Z_BACK_MOVE, 0, Printer::homingFeedrate[Z_AXIS]/ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, false); + PrintLine::moveRelativeDistanceInSteps(0, 0, axisStepsPerMM[Z_AXIS] * -ENDSTOP_Z_BACK_MOVE, 0, Printer::homingFeedrate[Z_AXIS]/ENDSTOP_X_RETEST_REDUCTION_FACTOR, true, true); //Endstops::report(); // Check for proper release of all (XYZ) endstops if (!(Endstops::xMax() || Endstops::yMax() || Endstops::zMax())) { // Rehome with reduced speed + Endstops::resetAccumulator(); deltaMoveToTopEndstops(Printer::homingFeedrate[Z_AXIS] / ENDSTOP_Z_RETEST_REDUCTION_FACTOR); + Endstops::fillFromAccumulator(); //Endstops::report(); - // Check that all endstoips (XYZ) were hit again + // Check that all endstops (XYZ) were hit again if (Endstops::xMax() && Endstops::yMax() && Endstops::zMax()) { homingSuccess = true; // Assume success in case there is no back move #if defined(ENDSTOP_Z_BACK_ON_HOME) if(ENDSTOP_Z_BACK_ON_HOME > 0) { - PrintLine::moveRelativeDistanceInSteps(0, 0, axisStepsPerMM[Z_AXIS] * -ENDSTOP_Z_BACK_ON_HOME * Z_HOME_DIR,0,homingFeedrate[Z_AXIS], true, false); + PrintLine::moveRelativeDistanceInSteps(0, 0, axisStepsPerMM[Z_AXIS] * -ENDSTOP_Z_BACK_ON_HOME * Z_HOME_DIR,0,homingFeedrate[Z_AXIS], true, true); //Endstops::report(); // Check for missing release of any (XYZ) endstop if (Endstops::xMax() || Endstops::yMax() || Endstops::zMax()) { @@ -1201,7 +1330,7 @@ void Printer::homeZAxis() // Delta z homing PrintLine::moveRelativeDistanceInSteps(0, 0, dm, 0, homingFeedrate[Z_AXIS], true, false); currentPositionSteps[X_AXIS] = 0; // now we are really here currentPositionSteps[Y_AXIS] = 0; - currentPositionSteps[Z_AXIS] = zMaxSteps; // Extruder is now exactly in the delta center + currentPositionSteps[Z_AXIS] = zMaxSteps - zBedOffset * axisStepsPerMM[Z_AXIS]; // Extruder is now exactly in the delta center coordinateOffset[X_AXIS] = 0; coordinateOffset[Y_AXIS] = 0; coordinateOffset[Z_AXIS] = 0; @@ -1212,7 +1341,7 @@ void Printer::homeZAxis() // Delta z homing //maxDeltaPositionSteps = currentDeltaPositionSteps[X_AXIS]; #if defined(ENDSTOP_Z_BACK_ON_HOME) if(ENDSTOP_Z_BACK_ON_HOME > 0) - maxDeltaPositionSteps += axisStepsPerMM[Z_AXIS]*ENDSTOP_Z_BACK_ON_HOME; + maxDeltaPositionSteps += axisStepsPerMM[Z_AXIS] * ENDSTOP_Z_BACK_ON_HOME; #endif Extruder::selectExtruderById(Extruder::current->id); } @@ -1231,10 +1360,10 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // Delta homing code // so the redundant check is only an opportunity to // gratuitously fail due to incorrect settings. // The following movements would be meaningless unless it was zeroed for example. - UI_STATUS_UPD(UI_TEXT_HOME_DELTA); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_HOME_DELTA_ID)); // Homing Z axis means that you must home X and Y homeZAxis(); - moveToReal(0,0,Printer::zLength,IGNORE_COORDINATE,homingFeedrate[Z_AXIS]); // Move to designed coordinates including translation + moveToReal(0,0,Printer::zLength - zBedOffset,IGNORE_COORDINATE,homingFeedrate[Z_AXIS]); // Move to designed coordinates including translation updateCurrentPosition(true); UI_CLEAR_STATUS Commands::printCurrentPosition(PSTR("homeAxis ")); @@ -1245,12 +1374,12 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // Delta homing code void Printer::homeXAxis() { long steps; - if ((MIN_HARDWARE_ENDSTOP_X && X_MIN_PIN > -1 && X_HOME_DIR==-1 && MIN_HARDWARE_ENDSTOP_Y && Y_MIN_PIN > -1 && Y_HOME_DIR==-1) || - (MAX_HARDWARE_ENDSTOP_X && X_MAX_PIN > -1 && X_HOME_DIR==1 && MAX_HARDWARE_ENDSTOP_Y && Y_MAX_PIN > -1 && Y_HOME_DIR==1)) + if ((MIN_HARDWARE_ENDSTOP_X && X_MIN_PIN > -1 && X_HOME_DIR == -1 && MIN_HARDWARE_ENDSTOP_Y && Y_MIN_PIN > -1 && Y_HOME_DIR == -1) || + (MAX_HARDWARE_ENDSTOP_X && X_MAX_PIN > -1 && X_HOME_DIR == 1 && MAX_HARDWARE_ENDSTOP_Y && Y_MAX_PIN > -1 && Y_HOME_DIR == 1)) { long offX = 0,offY = 0; #if NUM_EXTRUDER>1 - for(uint8_t i=0; i 1 - UI_STATUS_UPD(UI_TEXT_HOME_X); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_HOME_X_ID)); steps = (Printer::xMaxSteps - Printer::xMinSteps) * X_HOME_DIR; currentPositionSteps[X_AXIS] = -steps; setHoming(true); @@ -1326,7 +1455,11 @@ void Printer::homeXAxis() #endif currentPositionSteps[X_AXIS] = (X_HOME_DIR == -1) ? xMinSteps - offX : xMaxSteps + offX; #if NUM_EXTRUDER > 1 +#if X_HOME_DIR < 0 PrintLine::moveRelativeDistanceInSteps((Extruder::current->xOffset - offX) * X_HOME_DIR,0,0,0,homingFeedrate[X_AXIS], true, true); +#else + PrintLine::moveRelativeDistanceInSteps(-(Extruder::current->xOffset - offX) * X_HOME_DIR,0,0,0,homingFeedrate[X_AXIS], true, true); +#endif #endif } } @@ -1334,34 +1467,38 @@ void Printer::homeXAxis() void Printer::homeYAxis() { long steps; - if ((MIN_HARDWARE_ENDSTOP_Y && Y_MIN_PIN > -1 && Y_HOME_DIR==-1) || (MAX_HARDWARE_ENDSTOP_Y && Y_MAX_PIN > -1 && Y_HOME_DIR==1)) + if ((MIN_HARDWARE_ENDSTOP_Y && Y_MIN_PIN > -1 && Y_HOME_DIR == -1) || (MAX_HARDWARE_ENDSTOP_Y && Y_MAX_PIN > -1 && Y_HOME_DIR == 1)) { long offY = 0; -#if NUM_EXTRUDER>1 - for(uint8_t i=0; i 1 + for(uint8_t i = 0; i < NUM_EXTRUDER; i++) +#if Y_HOME_DIR < 0 offY = RMath::max(offY,extruder[i].yOffset); #else offY = RMath::min(offY,extruder[i].yOffset); #endif // Reposition extruder that way, that all extruders can be selected at home pos. #endif - UI_STATUS_UPD(UI_TEXT_HOME_Y); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_HOME_Y_ID)); steps = (yMaxSteps-Printer::yMinSteps) * Y_HOME_DIR; currentPositionSteps[Y_AXIS] = -steps; setHoming(true); - PrintLine::moveRelativeDistanceInSteps(0,2*steps,0,0,homingFeedrate[Y_AXIS],true,true); + PrintLine::moveRelativeDistanceInSteps(0,2 * steps,0,0,homingFeedrate[Y_AXIS],true,true); currentPositionSteps[Y_AXIS] = (Y_HOME_DIR == -1) ? yMinSteps-offY : yMaxSteps+offY; - PrintLine::moveRelativeDistanceInSteps(0,axisStepsPerMM[Y_AXIS]*-ENDSTOP_Y_BACK_MOVE * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS]/ENDSTOP_X_RETEST_REDUCTION_FACTOR,true,false); - PrintLine::moveRelativeDistanceInSteps(0,axisStepsPerMM[Y_AXIS]*2*ENDSTOP_Y_BACK_MOVE * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS]/ENDSTOP_X_RETEST_REDUCTION_FACTOR,true,true); + PrintLine::moveRelativeDistanceInSteps(0,axisStepsPerMM[Y_AXIS] * -ENDSTOP_Y_BACK_MOVE * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR,true,false); + PrintLine::moveRelativeDistanceInSteps(0,axisStepsPerMM[Y_AXIS] * 2 * ENDSTOP_Y_BACK_MOVE * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS] / ENDSTOP_X_RETEST_REDUCTION_FACTOR,true,true); setHoming(false); #if defined(ENDSTOP_Y_BACK_ON_HOME) if(ENDSTOP_Y_BACK_ON_HOME > 0) - PrintLine::moveRelativeDistanceInSteps(0,axisStepsPerMM[Y_AXIS]*-ENDSTOP_Y_BACK_ON_HOME * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS],true,false); + PrintLine::moveRelativeDistanceInSteps(0,axisStepsPerMM[Y_AXIS] * -ENDSTOP_Y_BACK_ON_HOME * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS],true,false); +#endif + currentPositionSteps[Y_AXIS] = (Y_HOME_DIR == -1) ? yMinSteps - offY : yMaxSteps + offY; +#if NUM_EXTRUDER > 1 +#if Y_HOME_DIR < 0 + PrintLine::moveRelativeDistanceInSteps(0,(Extruder::current->yOffset - offY) * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS],true,false); +#else + PrintLine::moveRelativeDistanceInSteps(0,-(Extruder::current->yOffset - offY) * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS],true,false); #endif - currentPositionSteps[Y_AXIS] = (Y_HOME_DIR == -1) ? yMinSteps-offY : yMaxSteps+offY; -#if NUM_EXTRUDER>1 - PrintLine::moveRelativeDistanceInSteps(0,(Extruder::current->yOffset-offY) * Y_HOME_DIR,0,0,homingFeedrate[Y_AXIS],true,false); #endif } } @@ -1370,23 +1507,40 @@ void Printer::homeYAxis() void Printer::homeZAxis() // cartesian homing { long steps; - if ((MIN_HARDWARE_ENDSTOP_Z && Z_MIN_PIN > -1 && Z_HOME_DIR==-1) || (MAX_HARDWARE_ENDSTOP_Z && Z_MAX_PIN > -1 && Z_HOME_DIR==1)) + if ((MIN_HARDWARE_ENDSTOP_Z && Z_MIN_PIN > -1 && Z_HOME_DIR == -1) || (MAX_HARDWARE_ENDSTOP_Z && Z_MAX_PIN > -1 && Z_HOME_DIR == 1)) { - UI_STATUS_UPD(UI_TEXT_HOME_Z); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_HOME_Z_ID)); steps = (zMaxSteps - zMinSteps) * Z_HOME_DIR; currentPositionSteps[Z_AXIS] = -steps; setHoming(true); - PrintLine::moveRelativeDistanceInSteps(0,0,2*steps,0,homingFeedrate[Z_AXIS],true,true); + PrintLine::moveRelativeDistanceInSteps(0,0,2 * steps,0,homingFeedrate[Z_AXIS],true,true); currentPositionSteps[Z_AXIS] = (Z_HOME_DIR == -1) ? zMinSteps : zMaxSteps; - PrintLine::moveRelativeDistanceInSteps(0,0,axisStepsPerMM[Z_AXIS]*-ENDSTOP_Z_BACK_MOVE * Z_HOME_DIR,0,homingFeedrate[Z_AXIS]/ENDSTOP_Z_RETEST_REDUCTION_FACTOR,true,false); - PrintLine::moveRelativeDistanceInSteps(0,0,axisStepsPerMM[Z_AXIS]*2*ENDSTOP_Z_BACK_MOVE * Z_HOME_DIR,0,homingFeedrate[Z_AXIS]/ENDSTOP_Z_RETEST_REDUCTION_FACTOR,true,true); - setHoming(false); -#if defined(ENDSTOP_Z_BACK_ON_HOME) - if(ENDSTOP_Z_BACK_ON_HOME > 0) - PrintLine::moveRelativeDistanceInSteps(0,0,axisStepsPerMM[Z_AXIS]*-ENDSTOP_Z_BACK_ON_HOME * Z_HOME_DIR,0,homingFeedrate[Z_AXIS],true,false); + PrintLine::moveRelativeDistanceInSteps(0,0,axisStepsPerMM[Z_AXIS] * -ENDSTOP_Z_BACK_MOVE * Z_HOME_DIR,0,homingFeedrate[Z_AXIS] / ENDSTOP_Z_RETEST_REDUCTION_FACTOR,true,false); +#if defined(ZHOME_WAIT_UNSWING) && ZHOME_WAIT_UNSWING > 0 + HAL::delayMilliseconds(ZHOME_WAIT_UNSWING); #endif - currentPositionSteps[Z_AXIS] = (Z_HOME_DIR == -1) ? zMinSteps : zMaxSteps; -#if DRIVE_SYSTEM==TUGA + PrintLine::moveRelativeDistanceInSteps(0,0,axisStepsPerMM[Z_AXIS] * 2 * ENDSTOP_Z_BACK_MOVE * Z_HOME_DIR,0,homingFeedrate[Z_AXIS] / ENDSTOP_Z_RETEST_REDUCTION_FACTOR,true,true); + setHoming(false); + int32_t zCorrection = 0; +#if MIN_HARDWARE_ENDSTOP_Z && FEATURE_Z_PROBE && Z_PROBE_PIN==Z_MIN_PIN + // Fix error from z probe testing + zCorrection -= axisStepsPerMM[Z_AXIS]*EEPROM::zProbeHeight(); +#endif +#if defined(ENDSTOP_Z_BACK_ON_HOME) + // If we want to go up a bit more for some reason + if(ENDSTOP_Z_BACK_ON_HOME > 0) + zCorrection -= axisStepsPerMM[Z_AXIS]*ENDSTOP_Z_BACK_ON_HOME * Z_HOME_DIR; +#endif +#if Z_HOME_DIR < 0 + // Fix bed coating + zCorrection += axisStepsPerMM[Z_AXIS] * Printer::zBedOffset; +#endif + PrintLine::moveRelativeDistanceInSteps(0,0,zCorrection,0,homingFeedrate[Z_AXIS],true,false); + currentPositionSteps[Z_AXIS] = ((Z_HOME_DIR == -1) ? zMinSteps : zMaxSteps - Printer::zBedOffset * axisStepsPerMM[Z_AXIS]); +#if NUM_EXTRUDER > 0 + currentPositionSteps[Z_AXIS] -= Extruder::current->zOffset; +#endif +#if DRIVE_SYSTEM == TUGA currentDeltaPositionSteps[C_TOWER] = currentPositionSteps[Z_AXIS]; #endif } @@ -1395,7 +1549,7 @@ void Printer::homeZAxis() // cartesian homing void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // home non-delta printer { float startX,startY,startZ; - realPosition(startX,startY,startZ); + realPosition(startX, startY, startZ); setHomed(true); #if !defined(HOMING_ORDER) #define HOMING_ORDER HOME_ORDER_XYZ @@ -1428,18 +1582,22 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // home non-delta print { float actTemp[NUM_EXTRUDER]; for(int i = 0;i < NUM_EXTRUDER; i++) - actTemp[i] = Extruder::current->tempControl.targetTemperatureC; + actTemp[i] = extruder[i].tempControl.targetTemperatureC; if(zaxis) { homeZAxis(); Printer::moveToReal(IGNORE_COORDINATE,IGNORE_COORDINATE,ZHOME_HEAT_HEIGHT,IGNORE_COORDINATE,homingFeedrate[Z_AXIS]); Commands::waitUntilEndOfAllMoves(); #if ZHOME_HEAT_ALL - for(int i = 0; i < NUM_EXTRUDER; i++) + for(int i = 0; i < NUM_EXTRUDER; i++) { Extruder::setTemperatureForExtruder(RMath::max(actTemp[i],static_cast(ZHOME_MIN_TEMPERATURE)),i,false,false); - for(int i = 0; i < NUM_EXTRUDER; i++) - Extruder::setTemperatureForExtruder(RMath::max(actTemp[i],static_cast(ZHOME_MIN_TEMPERATURE)),i,false,true); + } + for(int i = 0; i < NUM_EXTRUDER; i++) { + if(actTemp[i] < ZHOME_MIN_TEMPERATURE) + Extruder::setTemperatureForExtruder(RMath::max(actTemp[i],static_cast(ZHOME_MIN_TEMPERATURE)),i,false,true); + } #else - Extruder::setTemperatureForExtruder(RMath::max(actTemp[Extruder::current->id],static_cast(ZHOME_MIN_TEMPERATURE)),Extruder::current->id,false,true); + if(actTemp[Extruder::current->id] < ZHOME_MIN_TEMPERATURE) + Extruder::setTemperatureForExtruder(RMath::max(actTemp[Extruder::current->id],static_cast(ZHOME_MIN_TEMPERATURE)),Extruder::current->id,false,true); #endif } #if ZHOME_X_POS == IGNORE_COORDINATE @@ -1449,12 +1607,12 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // home non-delta print #endif { homeXAxis(); -#if ZHOME_X_POS == IGNORE_COORDINATE +//#if ZHOME_X_POS == IGNORE_COORDINATE if(X_HOME_DIR < 0) startX = Printer::xMin; else startX = Printer::xMin + Printer::xLength; -#else - startX = ZHOME_X_POS; -#endif +//#else +// startX = ZHOME_X_POS; +//#endif } #if ZHOME_Y_POS == IGNORE_COORDINATE if(yaxis) @@ -1463,21 +1621,26 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // home non-delta print #endif { homeYAxis(); -#if ZHOME_Y_POS == IGNORE_COORDINATE +//#if ZHOME_Y_POS == IGNORE_COORDINATE if(Y_HOME_DIR < 0) startY = Printer::yMin; else startY = Printer::yMin + Printer::yLength; -#else - startY = ZHOME_Y_POS; -#endif +//#else +// startY = ZHOME_Y_POS; +//#endif } + if(zaxis) { #if ZHOME_X_POS != IGNORE_COORDINATE || ZHOME_Y_POS != IGNORE_COORDINATE - if(zaxis) { // only required for z axis moveToReal(ZHOME_X_POS,ZHOME_Y_POS,IGNORE_COORDINATE,IGNORE_COORDINATE,homingFeedrate[Y_AXIS]); Commands::waitUntilEndOfAllMoves(); - } #endif - if(zaxis) { homeZAxis(); +#if DISTORTION_CORRECTION && Z_HOME_DIR < 0 && Z_PROBE_PIN == Z_MIN_PIN + // Special case where z probe is z min endstop and distortion correction is enabled + if(Printer::distortion.isEnabled()) { + Printer::zCorrectionStepsIncluded = Printer::distortion.correct(Printer::currentPositionSteps[X_AXIS],currentPositionSteps[Y_AXIS],currentPositionSteps[Z_AXIS]); + currentPositionSteps[Z_AXIS] += Printer::zCorrectionStepsIncluded; + } +#endif #if ZHOME_HEAT_ALL for(int i = 0;i < NUM_EXTRUDER; i++) Extruder::setTemperatureForExtruder(actTemp[i],i,false,false); @@ -1487,7 +1650,7 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // home non-delta print Extruder::setTemperatureForExtruder(actTemp[Extruder::current->id], Extruder::current->id, false, actTemp[Extruder::current->id] > MAX_ROOM_TEMPERATURE); #endif if(Z_HOME_DIR < 0) startZ = Printer::zMin; - else startZ = Printer::zMin + Printer::zLength; + else startZ = Printer::zMin + Printer::zLength - zBedOffset; } } #endif @@ -1505,11 +1668,17 @@ void Printer::homeAxis(bool xaxis,bool yaxis,bool zaxis) // home non-delta print if(zaxis) { if(Z_HOME_DIR < 0) startZ = Printer::zMin; - else startZ = Printer::zMin + Printer::zLength; + else startZ = Printer::zMin + Printer::zLength - Printer::zBedOffset; } #endif updateCurrentPosition(true); +#if defined(Z_UP_AFTER_HOME) && Z_HOME_DIR < 0 + //PrintLine::moveRelativeDistanceInSteps(0,0,axisStepsPerMM[Z_AXIS]*Z_UP_AFTER_HOME * Z_HOME_DIR,0,homingFeedrate[Z_AXIS],true,false); + if(zaxis) + startZ = Z_UP_AFTER_HOME; +#endif moveToReal(startX, startY, startZ, IGNORE_COORDINATE, homingFeedrate[X_AXIS]); + updateCurrentPosition(true); UI_CLEAR_STATUS Commands::printCurrentPosition(PSTR("homeAxis ")); } @@ -1520,18 +1689,18 @@ void Printer::zBabystep() bool dir = zBabystepsMissing > 0; if(dir) zBabystepsMissing--; else zBabystepsMissing++; -#if DRIVE_SYSTEM == 3 +#if DRIVE_SYSTEM == DELTA Printer::enableXStepper(); Printer::enableYStepper(); #endif Printer::enableZStepper(); Printer::unsetAllSteppersDisabled(); -#if DRIVE_SYSTEM == 3 +#if DRIVE_SYSTEM == DELTA bool xDir = Printer::getXDirection(); bool yDir = Printer::getYDirection(); #endif bool zDir = Printer::getZDirection(); -#if DRIVE_SYSTEM == 3 +#if DRIVE_SYSTEM == DELTA Printer::setXDirection(dir); Printer::setYDirection(dir); #endif @@ -1539,24 +1708,16 @@ void Printer::zBabystep() #if defined(DIRECTION_DELAY) && DIRECTION_DELAY > 0 HAL::delayMicroseconds(DIRECTION_DELAY); #else - HAL::delayMicroseconds(1); -#endif -#if DRIVE_SYSTEM == 3 - WRITE(X_STEP_PIN,HIGH); -#if FEATURE_TWO_XSTEPPER - WRITE(X2_STEP_PIN,HIGH); -#endif - WRITE(Y_STEP_PIN,HIGH); -#if FEATURE_TWO_YSTEPPER - WRITE(Y2_STEP_PIN,HIGH); -#endif -#endif - WRITE(Z_STEP_PIN,HIGH); -#if FEATURE_TWO_ZSTEPPER - WRITE(Z2_STEP_PIN,HIGH); + HAL::delayMicroseconds(10); #endif +#if DRIVE_SYSTEM == DELTA + startXStep(); + startYStep(); +#endif // Drive system 3 + startZStep(); HAL::delayMicroseconds(STEPPER_HIGH_DELAY + 2); Printer::endXYZSteps(); + HAL::delayMicroseconds(10); #if DRIVE_SYSTEM == 3 Printer::setXDirection(xDir); Printer::setYDirection(yDir); @@ -1568,257 +1729,6 @@ void Printer::zBabystep() //HAL::delayMicroseconds(STEPPER_HIGH_DELAY + 1); } - -void Printer::setAutolevelActive(bool on) -{ -#if FEATURE_AUTOLEVEL - if(on == isAutolevelActive()) return; - flag0 = (on ? flag0 | PRINTER_FLAG0_AUTOLEVEL_ACTIVE : flag0 & ~PRINTER_FLAG0_AUTOLEVEL_ACTIVE); - if(on) - Com::printInfoFLN(Com::tAutolevelEnabled); - else - Com::printInfoFLN(Com::tAutolevelDisabled); - updateCurrentPosition(false); -#endif // FEATURE_AUTOLEVEL if(isAutolevelActive()==on) return; -} -#if MAX_HARDWARE_ENDSTOP_Z -float Printer::runZMaxProbe() -{ -#if NONLINEAR_SYSTEM - long startZ = realDeltaPositionSteps[Z_AXIS] = currentDeltaPositionSteps[Z_AXIS]; // update real -#endif - Commands::waitUntilEndOfAllMoves(); - long probeDepth = 2*(Printer::zMaxSteps-Printer::zMinSteps); - stepsRemainingAtZHit = -1; - setZProbingActive(true); - PrintLine::moveRelativeDistanceInSteps(0,0,probeDepth,0,EEPROM::zProbeSpeed(),true,true); - if(stepsRemainingAtZHit < 0) - { - Com::printErrorFLN(Com::tZProbeFailed); - return -1; - } - setZProbingActive(false); - currentPositionSteps[Z_AXIS] -= stepsRemainingAtZHit; -#if NONLINEAR_SYSTEM - probeDepth -= (realDeltaPositionSteps[Z_AXIS] - startZ); -#else - probeDepth -= stepsRemainingAtZHit; -#endif - float distance = (float)probeDepth * invAxisStepsPerMM[Z_AXIS]; - Com::printF(Com::tZProbeMax,distance); - Com::printF(Com::tSpaceXColon,realXPosition()); - Com::printFLN(Com::tSpaceYColon,realYPosition()); - PrintLine::moveRelativeDistanceInSteps(0,0,-probeDepth,0,EEPROM::zProbeSpeed(),true,true); - return distance; -} -#endif - -#if FEATURE_Z_PROBE -float Printer::runZProbe(bool first,bool last,uint8_t repeat,bool runStartScript) -{ - float oldOffX = Printer::offsetX; - float oldOffY = Printer::offsetY; - float oldOffZ = Printer::offsetZ; - if(first) - { - if(runStartScript) - GCode::executeFString(Com::tZProbeStartScript); - float maxStartHeight = EEPROM::zProbeBedDistance() + EEPROM::zProbeHeight() + 0.1; - if(currentPosition[Z_AXIS] > maxStartHeight) { - moveTo(IGNORE_COORDINATE, IGNORE_COORDINATE, maxStartHeight, IGNORE_COORDINATE, homingFeedrate[Z_AXIS]); - } - Printer::offsetX = -EEPROM::zProbeXOffset(); - Printer::offsetY = -EEPROM::zProbeYOffset(); - Printer::offsetZ = 0; // we correct this with probe height - PrintLine::moveRelativeDistanceInSteps((Printer::offsetX - oldOffX) * Printer::axisStepsPerMM[X_AXIS], - (Printer::offsetY - oldOffY) * Printer::axisStepsPerMM[Y_AXIS], - 0, 0, EEPROM::zProbeXYSpeed(), true, ALWAYS_CHECK_ENDSTOPS); - } - Commands::waitUntilEndOfAllMoves(); - int32_t sum = 0, probeDepth; - int32_t shortMove = static_cast((float)Z_PROBE_SWITCHING_DISTANCE * axisStepsPerMM[Z_AXIS]); // distance to go up for repeated moves - int32_t lastCorrection = currentPositionSteps[Z_AXIS]; // starting position -#if NONLINEAR_SYSTEM - realDeltaPositionSteps[Z_AXIS] = currentDeltaPositionSteps[Z_AXIS]; // update real -#endif - int32_t updateZ = 0; - for(int8_t r = 0; r < repeat; r++) - { - probeDepth = 2 * (Printer::zMaxSteps - Printer::zMinSteps); // probe should always hit within this distance - stepsRemainingAtZHit = -1; // Marker that we did not hit z probe - int32_t offx = axisStepsPerMM[X_AXIS] * EEPROM::zProbeXOffset(); - int32_t offy = axisStepsPerMM[Y_AXIS] * EEPROM::zProbeYOffset(); - //PrintLine::moveRelativeDistanceInSteps(-offx,-offy,0,0,EEPROM::zProbeXYSpeed(),true,true); - waitForZProbeStart(); - setZProbingActive(true); - PrintLine::moveRelativeDistanceInSteps(0, 0, -probeDepth, 0, EEPROM::zProbeSpeed(), true, true); - if(stepsRemainingAtZHit < 0) - { - Com::printErrorFLN(Com::tZProbeFailed); - return -1; - } - setZProbingActive(false); -#if NONLINEAR_SYSTEM - stepsRemainingAtZHit = realDeltaPositionSteps[C_TOWER] - currentDeltaPositionSteps[C_TOWER]; // nonlinear moves may split z so stepsRemainingAtZHit is only what is left from last segment not total move. This corrects the problem. -#endif -#if DRIVE_SYSTEM == DELTA - currentDeltaPositionSteps[A_TOWER] += stepsRemainingAtZHit; // Update difference - currentDeltaPositionSteps[B_TOWER] += stepsRemainingAtZHit; - currentDeltaPositionSteps[C_TOWER] += stepsRemainingAtZHit; -#endif - currentPositionSteps[Z_AXIS] += stepsRemainingAtZHit; // now current position is correct - /* if(r == 0 && first) // Modify start z position on first probe hit to speed the ZProbe process - { - int32_t newLastCorrection = currentPositionSteps[Z_AXIS] + (int32_t)((float)EEPROM::zProbeBedDistance() * axisStepsPerMM[Z_AXIS]); - if(newLastCorrection < lastCorrection) // don't want to go all the way up again, fix discrepancy and retest - { - updateZ = lastCorrection - newLastCorrection; - lastCorrection = newLastCorrection; - first = false; - PrintLine::moveRelativeDistanceInSteps(0, 0, lastCorrection - currentPositionSteps[Z_AXIS], 0, EEPROM::zProbeSpeed(), true, false); - r--; - } - }*/ - sum += lastCorrection - currentPositionSteps[Z_AXIS]; - if(r + 1 < repeat) // go only shortes possible move up for repetitions - PrintLine::moveRelativeDistanceInSteps(0, 0, shortMove, 0, EEPROM::zProbeSpeed(), true, false); - } - float distance = static_cast(sum) * invAxisStepsPerMM[Z_AXIS] / static_cast(repeat) + EEPROM::zProbeHeight(); -#if DISTORTION_CORRECTION - float zCorr = distortion.correct(currentPositionSteps[X_AXIS] + EEPROM::zProbeXOffset() * axisStepsPerMM[X_AXIS],currentPositionSteps[Y_AXIS] - + EEPROM::zProbeYOffset() * axisStepsPerMM[Y_AXIS],0) * invAxisStepsPerMM[Z_AXIS]; - distance += zCorr; -#endif - Com::printF(Com::tZProbe, distance); - Com::printF(Com::tSpaceXColon, realXPosition()); -#if DISTORTION_CORRECTION - Com::printF(Com::tSpaceYColon, realYPosition()); - Com::printFLN(PSTR(" zCorr:"), zCorr); -#else - Com::printFLN(Com::tSpaceYColon, realYPosition()); -#endif - // Go back to start position - PrintLine::moveRelativeDistanceInSteps(0, 0, lastCorrection - currentPositionSteps[Z_AXIS], 0, EEPROM::zProbeSpeed(), true, false); - //PrintLine::moveRelativeDistanceInSteps(offx,offy,0,0,EEPROM::zProbeXYSpeed(),true,true); - if(last) - { - oldOffX = Printer::offsetX; - oldOffY = Printer::offsetY; - oldOffZ = Printer::offsetZ; - GCode::executeFString(Com::tZProbeEndScript); - if(Extruder::current) - { - Printer::offsetX = -Extruder::current->xOffset * Printer::invAxisStepsPerMM[X_AXIS]; - Printer::offsetY = -Extruder::current->yOffset * Printer::invAxisStepsPerMM[Y_AXIS]; - Printer::offsetZ = -Extruder::current->zOffset * Printer::invAxisStepsPerMM[Z_AXIS]; - } - PrintLine::moveRelativeDistanceInSteps((Printer::offsetX - oldOffX) * Printer::axisStepsPerMM[X_AXIS], - (Printer::offsetY - oldOffY) * Printer::axisStepsPerMM[Y_AXIS], - (Printer::offsetZ - oldOffZ) * Printer::axisStepsPerMM[Z_AXIS], 0, EEPROM::zProbeXYSpeed(), true, ALWAYS_CHECK_ENDSTOPS); - } - return distance; -} - -void Printer::waitForZProbeStart() -{ -#if Z_PROBE_WAIT_BEFORE_TEST - if(Endstops::zProbe()) return; -#if UI_DISPLAY_TYPE != NO_DISPLAY - uid.setStatusP(Com::tHitZProbe); - uid.refreshPage(); -#endif -#ifdef DEBUG_PRINT - debugWaitLoop = 3; -#endif - while(!Endstops::zProbe()) - { - defaultLoopActions(); - Endstops::update(); - } -#ifdef DEBUG_PRINT - debugWaitLoop = 4; -#endif - HAL::delayMilliseconds(30); - while(Endstops::zProbe()) - { - defaultLoopActions(); - Endstops::update(); - } - HAL::delayMilliseconds(30); - UI_CLEAR_STATUS; -#endif -} -#endif - -#if FEATURE_AUTOLEVEL -void Printer::transformToPrinter(float x,float y,float z,float &transX,float &transY,float &transZ) -{ -#if FEATURE_AXISCOMP - // Axis compensation: - x = x + y * EEPROM::axisCompTanXY() + z * EEPROM::axisCompTanXZ(); - y = y + z * EEPROM::axisCompTanYZ(); -#endif - transX = x * autolevelTransformation[0] + y * autolevelTransformation[3] + z * autolevelTransformation[6]; - transY = x * autolevelTransformation[1] + y * autolevelTransformation[4] + z * autolevelTransformation[7]; - transZ = x * autolevelTransformation[2] + y * autolevelTransformation[5] + z * autolevelTransformation[8]; -} - -void Printer::transformFromPrinter(float x,float y,float z,float &transX,float &transY,float &transZ) -{ - transX = x * autolevelTransformation[0] + y * autolevelTransformation[1] + z * autolevelTransformation[2]; - transY = x * autolevelTransformation[3] + y * autolevelTransformation[4] + z * autolevelTransformation[5]; - transZ = x * autolevelTransformation[6] + y * autolevelTransformation[7] + z * autolevelTransformation[8]; -#if FEATURE_AXISCOMP - // Axis compensation: - transY = transY - transZ * EEPROM::axisCompTanYZ(); - transX = transX - transY * EEPROM::axisCompTanXY() - transZ * EEPROM::axisCompTanXZ(); -#endif -} - -void Printer::resetTransformationMatrix(bool silent) -{ - autolevelTransformation[0] = autolevelTransformation[4] = autolevelTransformation[8] = 1; - autolevelTransformation[1] = autolevelTransformation[2] = autolevelTransformation[3] = - autolevelTransformation[5] = autolevelTransformation[6] = autolevelTransformation[7] = 0; - if(!silent) - Com::printInfoFLN(Com::tAutolevelReset); -} - -void Printer::buildTransformationMatrix(float h1,float h2,float h3) -{ - float ax = EEPROM::zProbeX2()-EEPROM::zProbeX1(); - float ay = EEPROM::zProbeY2()-EEPROM::zProbeY1(); - float az = h1-h2; - float bx = EEPROM::zProbeX3()-EEPROM::zProbeX1(); - float by = EEPROM::zProbeY3()-EEPROM::zProbeY1(); - float bz = h1-h3; - // First z direction - autolevelTransformation[6] = ay * bz - az * by; - autolevelTransformation[7] = az * bx - ax * bz; - autolevelTransformation[8] = ax * by - ay * bx; - float len = sqrt(autolevelTransformation[6] * autolevelTransformation[6] + autolevelTransformation[7] * autolevelTransformation[7] + autolevelTransformation[8] * autolevelTransformation[8]); - if(autolevelTransformation[8] < 0) len = -len; - autolevelTransformation[6] /= len; - autolevelTransformation[7] /= len; - autolevelTransformation[8] /= len; - autolevelTransformation[3] = 0; - autolevelTransformation[4] = autolevelTransformation[8]; - autolevelTransformation[5] = -autolevelTransformation[7]; - // cross(y,z) - autolevelTransformation[0] = autolevelTransformation[4] * autolevelTransformation[8] - autolevelTransformation[5] * autolevelTransformation[7]; - autolevelTransformation[1] = autolevelTransformation[5] * autolevelTransformation[6];// - autolevelTransformation[3] * autolevelTransformation[8]; - autolevelTransformation[2] = /*autolevelTransformation[3] * autolevelTransformation[7]*/ - autolevelTransformation[4] * autolevelTransformation[6]; - len = sqrt(autolevelTransformation[0] * autolevelTransformation[0] + autolevelTransformation[1] * autolevelTransformation[1] + autolevelTransformation[2] * autolevelTransformation[2]); - autolevelTransformation[0] /= len; - autolevelTransformation[1] /= len; - autolevelTransformation[2] /= len; - len = sqrt(autolevelTransformation[4] * autolevelTransformation[4] + autolevelTransformation[5] * autolevelTransformation[5]); - autolevelTransformation[4] /= len; - autolevelTransformation[5] /= len; - Com::printArrayFLN(Com::tTransformationMatrix,autolevelTransformation, 9, 6); -} -#endif - void Printer::setCaseLight(bool on) { #if CASE_LIGHTS_PIN > -1 WRITE(CASE_LIGHTS_PIN,on); @@ -1846,10 +1756,12 @@ void Printer::handleInterruptEvent() { case PRINTER_INTERRUPT_EVENT_JAM_DETECTED: EVENT_JAM_DETECTED; Com::printFLN(PSTR("important:Extruder jam detected")); - UI_ERROR_P(Com::tExtruderJam); + UI_ERROR_P(Com::translatedF(UI_TEXT_EXTRUDER_JAM_ID)); #if JAM_ACTION == 1 // start dialog Printer::setUIErrorMessage(false); +#if UI_DISPLAY_TYPE != NO_DISPLAY uid.executeAction(UI_ACTION_WIZARD_JAM_EOF, true); +#endif #elif JAM_ACTION == 2 // pause host/print #if SDSUPPORT if(sd.sdmode == 2) { @@ -1899,6 +1811,11 @@ void Printer::showConfiguration() { Com::config(PSTR("HeatedBed:"),HAVE_HEATED_BED); Com::config(PSTR("SDCard:"),SDSUPPORT); Com::config(PSTR("Fan:"),FAN_PIN > -1 && FEATURE_FAN_CONTROL); +#if FEATURE_FAN2_CONTROL && defined(FAN2_PIN) && FAN2_PIN > -1 + Com::config(PSTR("Fan2:1")); +#else + Com::config(PSTR("Fan2:0")); +#endif Com::config(PSTR("LCD:"),FEATURE_CONTROLLER != NO_CONTROLLER); Com::config(PSTR("SoftwarePowerSwitch:"),PS_ON_PIN > -1); Com::config(PSTR("XHomeDir:"),X_HOME_DIR); @@ -1987,8 +1904,16 @@ void Distortion::init() { void Distortion::updateDerived() { +#if DRIVE_SYSTEM == DELTA step = (2 * Printer::axisStepsPerMM[Z_AXIS] * DISTORTION_CORRECTION_R) / (DISTORTION_CORRECTION_POINTS - 1.0f); radiusCorrectionSteps = DISTORTION_CORRECTION_R * Printer::axisStepsPerMM[Z_AXIS]; +#else + xCorrectionSteps = (DISTORTION_XMAX - DISTORTION_XMIN) * Printer::axisStepsPerMM[X_AXIS] / DISTORTION_CORRECTION_POINTS; + xOffsetSteps = DISTORTION_XMIN * Printer::axisStepsPerMM[X_AXIS]; + yCorrectionSteps = (DISTORTION_YMAX - DISTORTION_YMIN) * Printer::axisStepsPerMM[Y_AXIS] / DISTORTION_CORRECTION_POINTS; + yOffsetSteps = DISTORTION_YMIN * Printer::axisStepsPerMM[Y_AXIS]; + +#endif zStart = DISTORTION_START_DEGRADE * Printer::axisStepsPerMM[Z_AXIS]; zEnd = DISTORTION_END_HEIGHT * Printer::axisStepsPerMM[Z_AXIS]; } @@ -1996,7 +1921,7 @@ void Distortion::updateDerived() void Distortion::enable(bool permanent) { enabled = true; -#if DISTORTION_PERMANENT +#if DISTORTION_PERMANENT && EEPROM_MODE != 0 if(permanent) EEPROM::setZCorrectionEnabled(enabled); #endif @@ -2006,10 +1931,14 @@ void Distortion::enable(bool permanent) void Distortion::disable(bool permanent) { enabled = false; -#if DISTORTION_PERMANENT +#if DISTORTION_PERMANENT && EEPROM_MODE != 0 if(permanent) EEPROM::setZCorrectionEnabled(enabled); #endif +#if DRIVE_SYSTEM != DELTA + Printer::zCorrectionStepsIncluded = 0; +#endif + Printer::updateCurrentPosition(false); Com::printFLN(Com::tZCorrectionDisabled); } @@ -2040,7 +1969,9 @@ int32_t Distortion::getMatrix(int index) const void Distortion::setMatrix(int32_t val, int index) { #if DISTORTION_PERMANENT +#if EEPROM_MODE != 0 EEPROM::setZCorrection(val, index); +#endif #else matrix[index] = val; #endif @@ -2053,7 +1984,7 @@ bool Distortion::isCorner(fast8_t i, fast8_t j) const } /** - Extrapolates the changes from p1 to p2 to p3 whcih has the same distance as p1-p2. + Extrapolates the changes from p1 to p2 to p3 which has the same distance as p1-p2. */ inline int32_t Distortion::extrapolatePoint(fast8_t x1, fast8_t y1, fast8_t x2, fast8_t y2) const { @@ -2078,30 +2009,42 @@ void Distortion::extrapolateCorners() void Distortion::measure(void) { fast8_t ix, iy; - float z = EEPROM::zProbeBedDistance() + EEPROM::zProbeHeight(); + float z = EEPROM::zProbeBedDistance() + (EEPROM::zProbeHeight() > 0 ? EEPROM::zProbeHeight() : 0); disable(false); //Com::printFLN(PSTR("radiusCorr:"), radiusCorrectionSteps); //Com::printFLN(PSTR("steps:"), step); + int32_t zCorrection = 0; +#if Z_HOME_DIR < 0 + zCorrection += Printer::zBedOffset * Printer::axisStepsPerMM[Z_AXIS]; +#endif +#if Z_HOME_DIR < 0 && Z_PROBE_Z_OFFSET_MODE == 1 + zCorrection += Printer::zBedOffset * Printer::axisStepsPerMM[Z_AXIS]; +#endif for (iy = DISTORTION_CORRECTION_POINTS - 1; iy >= 0; iy--) for (ix = 0; ix < DISTORTION_CORRECTION_POINTS; ix++) { #if (DRIVE_SYSTEM == DELTA) && DISTORTION_EXTRAPOLATE_CORNERS if (isCorner(ix, iy)) continue; #endif +#if DRIVE_SYSTEM == DELTA float mtx = Printer::invAxisStepsPerMM[X_AXIS] * (ix * step - radiusCorrectionSteps); float mty = Printer::invAxisStepsPerMM[Y_AXIS] * (iy * step - radiusCorrectionSteps); +#else + float mtx = Printer::invAxisStepsPerMM[X_AXIS] * (ix * xCorrectionSteps + xOffsetSteps); + float mty = Printer::invAxisStepsPerMM[Y_AXIS] * (iy * xCorrectionSteps + yOffsetSteps); +#endif //Com::printF(PSTR("mx "),mtx); //Com::printF(PSTR("my "),mty); //Com::printF(PSTR("ix "),(int)ix); //Com::printFLN(PSTR("iy "),(int)iy); Printer::moveToReal(mtx, mty, z, IGNORE_COORDINATE, EEPROM::zProbeXYSpeed()); -#if DISTORTION_EXTRAPOLATE_CORNERS +#if DISTORTION_EXTRAPOLATE_CORNERS && DRIVE_SYSTEM == DELTA setMatrix(floor(0.5f + Printer::axisStepsPerMM[Z_AXIS] * (z - - Printer::runZProbe(ix == 1 && iy == DISTORTION_CORRECTION_POINTS - 1, ix == DISTORTION_CORRECTION_POINTS - 2 && iy == 0, Z_PROBE_REPETITIONS))), + Printer::runZProbe(ix == 1 && iy == DISTORTION_CORRECTION_POINTS - 1, ix == DISTORTION_CORRECTION_POINTS - 2 && iy == 0, Z_PROBE_REPETITIONS))) + zCorrection, matrixIndex(ix,iy)); #else setMatrix(floor(0.5f + Printer::axisStepsPerMM[Z_AXIS] * (z - - Printer::runZProbe(ix == 0 && iy == DISTORTION_CORRECTION_POINTS - 1, ix == DISTORTION_CORRECTION_POINTS - 1 && iy == 0, Z_PROBE_REPETITIONS))), + Printer::runZProbe(ix == 0 && iy == DISTORTION_CORRECTION_POINTS - 1, ix == DISTORTION_CORRECTION_POINTS - 1 && iy == 0, Z_PROBE_REPETITIONS))) + zCorrection, matrixIndex(ix,iy)); #endif } @@ -2109,6 +2052,9 @@ void Distortion::measure(void) extrapolateCorners(); #endif // make average center + // Disabled since we can use grid measurement to get average plane if that is what we want. + // Shifting z with each measuring is a pain and can result in unexpected behavior. + /* float sum = 0; for(int k = 0;k < DISTORTION_CORRECTION_POINTS * DISTORTION_CORRECTION_POINTS; k++) sum += getMatrix(k); @@ -2116,6 +2062,7 @@ void Distortion::measure(void) for(int k = 0;k < DISTORTION_CORRECTION_POINTS * DISTORTION_CORRECTION_POINTS; k++) setMatrix(getMatrix(k) - sum, k); Printer::zLength -= sum * Printer::invAxisStepsPerMM[Z_AXIS]; + */ #if EEPROM_MODE EEPROM::storeDataIntoEEPROM(); #endif @@ -2127,8 +2074,9 @@ void Distortion::measure(void) Com::printF(ix ? PSTR(", ") : PSTR(""), getMatrix(matrixIndex(ix,iy))); Com::println(); } + showMatrix(); enable(true); - Printer::homeAxis(false, false, true); + //Printer::homeAxis(false, false, true); } int32_t Distortion::correct(int32_t x, int32_t y, int32_t z) const @@ -2137,10 +2085,17 @@ int32_t Distortion::correct(int32_t x, int32_t y, int32_t z) const if(false && z == 0) { Com::printF(PSTR("correcting ("), x); Com::printF(PSTR(","), y); } +#if DRIVE_SYSTEM == DELTA x += radiusCorrectionSteps; y += radiusCorrectionSteps; int32_t fxFloor = (x - (x < 0 ? step - 1 : 0)) / step; // special case floor for negative integers! int32_t fyFloor = (y - (y < 0 ? step -1 : 0)) / step; +#else + x -= xOffsetSteps; + y -= yOffsetSteps; + int32_t fxFloor = (x - (x < 0 ? xCorrectionSteps - 1 : 0)) / xCorrectionSteps; // special case floor for negative integers! + int32_t fyFloor = (y - (y < 0 ? yCorrectionSteps -1 : 0)) / yCorrectionSteps; +#endif // indexes to the matrix if (fxFloor < 0) fxFloor = 0; @@ -2152,6 +2107,7 @@ int32_t Distortion::correct(int32_t x, int32_t y, int32_t z) const fyFloor = DISTORTION_CORRECTION_POINTS - 2; // position between cells of matrix, range=0 to 1 - outside of the matrix the value will be outside this range and the value will be extrapolated +#if DRIVE_SYSTEM == DELTA int32_t fx = x - fxFloor * step; // Grid normalized coordinates int32_t fy = y - fyFloor * step; @@ -2159,10 +2115,21 @@ int32_t Distortion::correct(int32_t x, int32_t y, int32_t z) const int32_t m11 = getMatrix(idx11), m12 = getMatrix(idx11 + 1); int32_t m21 = getMatrix(idx11 + DISTORTION_CORRECTION_POINTS); int32_t m22 = getMatrix(idx11 + DISTORTION_CORRECTION_POINTS + 1); - int32_t zx1 = m11 + ((m21 - m11) * fx) / step; + int32_t zx1 = m11 + ((m12 - m11) * fx) / step; int32_t zx2 = m21 + ((m22 - m21) * fx) / step; int32_t correction_z = zx1 + ((zx2 - zx1) * fy) / step; +#else + int32_t fx = x - fxFloor * xCorrectionSteps; // Grid normalized coordinates + int32_t fy = y - fyFloor * yCorrectionSteps; + int32_t idx11 = matrixIndex(fxFloor, fyFloor); + int32_t m11 = getMatrix(idx11), m12 = getMatrix(idx11 + 1); + int32_t m21 = getMatrix(idx11 + DISTORTION_CORRECTION_POINTS); + int32_t m22 = getMatrix(idx11 + DISTORTION_CORRECTION_POINTS + 1); + int32_t zx1 = m11 + ((m12 - m11) * fx) / xCorrectionSteps; + int32_t zx2 = m21 + ((m22 - m21) * fx) / xCorrectionSteps; + int32_t correction_z = zx1 + ((zx2 - zx1) * fy) / yCorrectionSteps; +#endif if(false && z == 0) { Com::printF(PSTR(") by "), correction_z); Com::printF(PSTR(" ix= "), fxFloor); Com::printF(PSTR(" fx= "), fx); @@ -2188,11 +2155,256 @@ int32_t Distortion::correct(int32_t x, int32_t y, int32_t z) const return correction_z; } +void Distortion::set(float x,float y,float z) { +#if DRIVE_SYSTEM == DELTA + int ix = (x * Printer::axisStepsPerMM[Z_AXIS] + radiusCorrectionSteps + step / 2) / step; + int iy = (y * Printer::axisStepsPerMM[Z_AXIS] + radiusCorrectionSteps + step / 2) / step; +#else + int ix = (x * Printer::axisStepsPerMM[X_AXIS] - xOffsetSteps + xCorrectionSteps / 2) / xCorrectionSteps; + int iy = (y * Printer::axisStepsPerMM[Y_AXIS] - yOffsetSteps + yCorrectionSteps / 2) / yCorrectionSteps; +#endif + if(ix < 0) ix = 0; + if(iy < 0) iy = 0; + if(ix >= DISTORTION_CORRECTION_POINTS-1) ix = DISTORTION_CORRECTION_POINTS-1; + if(iy >= DISTORTION_CORRECTION_POINTS-1) iy = DISTORTION_CORRECTION_POINTS-1; + int32_t idx = matrixIndex(ix, iy); + setMatrix(z * Printer::axisStepsPerMM[Z_AXIS],idx); +} + +void Distortion::showMatrix() { + for(int ix = 0;ix < DISTORTION_CORRECTION_POINTS; ix++) { + for(int iy = 0;iy < DISTORTION_CORRECTION_POINTS; iy++) { +#if DRIVE_SYSTEM == DELTA + float x = (-radiusCorrectionSteps + ix * step) * Printer::invAxisStepsPerMM[Z_AXIS]; + float y = (-radiusCorrectionSteps + iy * step) * Printer::invAxisStepsPerMM[Z_AXIS]; +#else + float x = (xOffsetSteps + ix * xCorrectionSteps) * Printer::invAxisStepsPerMM[X_AXIS]; + float y = (yOffsetSteps + iy * yCorrectionSteps) * Printer::invAxisStepsPerMM[Y_AXIS]; +#endif + int32_t idx = matrixIndex(ix, iy); + float z = getMatrix(idx) * Printer::invAxisStepsPerMM[Z_AXIS]; + Com::printF(PSTR("Distortion correction at px:"),x,2); + Com::printF(PSTR(" py:"),y,2); + Com::printFLN(PSTR(" zCoorection:"),z,3); + } + } +} + #endif // DISTORTION_CORRECTION +#if JSON_OUTPUT +void Printer::showJSONStatus(int type) { + bool firstOccurrence; + + Com::printF(PSTR("{\"status\": \"")); + if (PrintLine::linesCount == 0) { + Com::print('I'); // IDLING +#if SDSUPPORT + } else if (sd.sdactive) { + Com::print('P'); // SD PRINTING +#endif + } else { + Com::print('B'); // SOMETHING ELSE, BUT SOMETHIG + } + Com::printF(PSTR("\",\"coords\": {")); + Com::printF(PSTR("\"axesHomed\":[")); + Com::printF(isHomed() ? PSTR("1, 1, 1") : PSTR("0, 0, 0")); + Com::printF(PSTR("],\"extr\":[")); + firstOccurrence = true; + for (int i = 0; i < NUM_EXTRUDER; i++) { + if (!firstOccurrence) Com::print(','); + Com::print(extruder[i].extrudePosition / extruder[i].stepsPerMM); + firstOccurrence = false; + } + Com::printF(PSTR("],\"xyz\":[")); + Com::print(currentPosition[X_AXIS]); // X + Com::print(','); + Com::print(currentPosition[Y_AXIS]); // Y + Com::print(','); + Com::print(currentPosition[Z_AXIS]); // Z + Com::printF(PSTR("]},\"currentTool\":")); + Com::print(Extruder::current->id); + Com::printF(PSTR(",\"params\": {\"atxPower\":")); + Com::print(isPowerOn()?'1':'0'); + Com::printF(PSTR(",\"fanPercent\":[")); +#if FEATURE_FAN_CONTROL + Com::print(getFanSpeed() / 2.55f); +#endif +#if FEATURE_FAN2_CONTROL + Com::printF(Com::tComma,getFan2Speed() / 2.55f); +#endif + Com::printF(PSTR("],\"speedFactor\":")); + Com::print(Printer::feedrateMultiply); + Com::printF(PSTR(",\"extrFactors\":[")); + firstOccurrence = true; + for (int i = 0; i < NUM_EXTRUDER; i++) { + if (!firstOccurrence) Com::print(','); + Com::print((int)Printer::extrudeMultiply); // Really *100? 100 is normal + firstOccurrence = false; + } + Com::printF(PSTR("]},")); + // SEQ?? + Com::printF(PSTR("\"temps\": {")); +#if HAVE_HEATED_BED + Com::printF(PSTR("\"bed\": {\"current\":")); + Com::print(heatedBedController.currentTemperatureC); + Com::printF(PSTR(",\"active\":")); + Com::print(heatedBedController.targetTemperatureC); + Com::printF(PSTR(",\"state\":")); + Com::print(heatedBedController.targetTemperatureC > 0 ? '2' : '1'); + Com::printF(PSTR("},")); +#endif + Com::printF(PSTR("\"heads\": {\"current\": [")); + firstOccurrence = true; + for (int i = 0; i < NUM_EXTRUDER; i++) { + if (!firstOccurrence) Com::print(','); + Com::print(extruder[i].tempControl.currentTemperatureC); + firstOccurrence = false; + } + Com::printF(PSTR("],\"active\": [")); + firstOccurrence = true; + for (int i = 0; i < NUM_EXTRUDER; i++) { + if (!firstOccurrence) Com::print(','); + Com::print(extruder[i].tempControl.targetTemperatureC); + firstOccurrence = false; + } + Com::printF(PSTR("],\"state\": [")); + firstOccurrence = true; + for (int i = 0; i < NUM_EXTRUDER; i++) { + if (!firstOccurrence) Com::print(','); + Com::print(extruder[i].tempControl.targetTemperatureC > EXTRUDER_FAN_COOL_TEMP?'2':'1'); + firstOccurrence = false; + } + Com::printF(PSTR("]}},\"time\":")); + Com::print(HAL::timeInMilliseconds()); + + switch (type) { + default: + case 0: + case 1: + break; + case 2: + // UNTIL PRINT ESTIMATE TIMES ARE IMPLEMENTED + // NO DURATION INFO IS SUPPORTED + Com::printF(PSTR(",\"coldExtrudeTemp\":0,\"coldRetractTemp\":0.0,\"geometry\":\"")); +#if (DRIVE_SYSTEM == DELTA) + Com::printF(PSTR("delta")); +#elif (DRIVE_SYSTEM == CARTESIAN) + Com::printF(PSTR("cartesian")); +#elif ((DRIVE_SYSTEM == XY_GANTRY) || (DRIVE_SYSTEM == YX_GANTRY)) + Com::printF(PSTR("coreXY")); +#elif (DRIVE_SYSTEM == XZ_GANTRY) + Com::printF(PSTR("coreXZ")); +#endif + Com::printF(PSTR("\",\"name\":\"")); + Com::printF(PSTR(UI_PRINTER_NAME)); + Com::printF(PSTR("\",\"tools\":[")); + firstOccurrence = true; + for (int i = 0; i < NUM_EXTRUDER; i++) { + if (!firstOccurrence) Com::print(','); + Com::printF(PSTR("{\"number\":")); + Com::print(i); + Com::printF(PSTR(",\"heaters\":[1],\"drives\":[1]")); + Com::print('}'); + firstOccurrence = false; + } + Com::printFLN(PSTR("]")); + break; + case 3: + Com::printF(PSTR(",\"currentLayer\":")); +#if SDSUPPORT + if (sd.sdactive && sd.fileInfo.layerHeight > 0) { // ONLY CAN TELL WHEN SD IS PRINTING + Com::print((int) (currentPosition[Z_AXIS] / sd.fileInfo.layerHeight)); + } else Com::print('0'); +#else + Com::printF(PSTR("-1")); +#endif + Com::printF(PSTR("\",extrRaw\":[")); + firstOccurrence = true; + for (int i = 0; i < NUM_EXTRUDER; i++) { + if (!firstOccurrence) Com::print(','); + Com::print(extruder[i].extrudePosition * Printer::extrudeMultiply); + firstOccurrence = false; + } + Com::printF(PSTR("],")); +#if SDSUPPORT + if (sd.sdactive) { + Com::printF(PSTR("\"fractionPrinted\":")); + float fraction; + if (sd.filesize < 2000000) fraction = sd.sdpos / sd.filesize; + else fraction = (sd.sdpos >> 8) / (sd.filesize >> 8); + Com::print((float) floorf(fraction * 1000) / 1000); // ONE DECIMAL, COULD BE DONE BY SHIFTING, BUT MEH + Com::print(','); + } +#endif + Com::printF(PSTR("\"firstLayerHeight\":")); +#if SDSUPPORT + if (sd.sdactive) { + Com::print(sd.fileInfo.layerHeight); + } else Com::print('0'); +#else + Com::print('0'); +#endif + break; + case 4: + case 5: + Com::printF(PSTR(",\"axisMins\":[")); + Com::print((int) X_MIN_POS); + Com::print(','); + Com::print((int) Y_MIN_POS); + Com::print(','); + Com::print((int) Z_MIN_POS); + Com::printF(PSTR("],\"axisMaxes\":[")); + Com::print((int) X_MAX_LENGTH); + Com::print(','); + Com::print((int) Y_MAX_LENGTH); + Com::print(','); + Com::print((int) Z_MAX_LENGTH); + Com::printF(PSTR("],\"accelerations\":[")); + Com::print(maxAccelerationMMPerSquareSecond[X_AXIS]); + Com::print(','); + Com::print(maxAccelerationMMPerSquareSecond[Y_AXIS]); + Com::print(','); + Com::print(maxAccelerationMMPerSquareSecond[Z_AXIS]); + for (int i = 0; i < NUM_EXTRUDER; i++) { + Com::print(','); + Com::print(extruder[i].maxAcceleration); + } + Com::printF(PSTR("],\"firmwareElectronics\":\"")); +#ifdef RAMPS_V_1_3 + Com::printF(PSTR("RAMPS")); +#elif (CPU_ARCH == ARCH_ARM) + Com::printF(PSTR("Arduino Due")); +#else + Com::printF(PSTR("AVR")); +#endif + Com::printF(PSTR("\",\"firmwareName\":\"Repetier\",\"firmwareVersion\":\"")); + Com::printF(PSTR(REPETIER_VERSION)); + Com::printF(PSTR("\",\"minFeedrates\":[0,0,0")); + for (int i = 0; i < NUM_EXTRUDER; i++) { + Com::printF(PSTR(",0")); + } + Com::printF(PSTR("],\"maxFeedrates\":[")); + Com::print(maxFeedrate[X_AXIS]); + Com::print(','); + Com::print(maxFeedrate[Y_AXIS]); + Com::print(','); + Com::print(maxFeedrate[Z_AXIS]); + for (int i = 0; i < NUM_EXTRUDER; i++) { + Com::print(','); + Com::print(extruder[i].maxFeedrate); + } + Com::printFLN(PSTR("]")); + break; + } + + Com::printFLN(PSTR("}")); +} + + +#endif // JSON_OUTPUT + #if defined(CUSTOM_EVENTS) #include "CustomEventsImpl.h" #endif - - diff --git a/Repetier/Printer.h b/Repetier/Printer.h index a67138b..a4cd737 100644 --- a/Repetier/Printer.h +++ b/Repetier/Printer.h @@ -93,7 +93,8 @@ union wizardVar #define PRINTER_FLAG2_IGNORE_M106_COMMAND 8 #define PRINTER_FLAG2_DEBUG_JAM 16 #define PRINTER_FLAG2_JAMCONTROL_DISABLED 32 -#define PRINTER_FLAG2_HOMING 64 +#define PRINTER_FLAG2_HOMING 64 +#define PRINTER_FLAG2_ALL_E_MOTORS 128 // Set all e motors flag // List of possible interrupt events (1-255 allowed) #define PRINTER_INTERRUPT_EVENT_JAM_DETECTED 1 @@ -106,7 +107,7 @@ union wizardVar // define an integer number of steps more than large enough to get to endstop from anywhere #define HOME_DISTANCE_STEPS (Printer::zMaxSteps-Printer::zMinSteps+1000) #define HOME_DISTANCE_MM (HOME_DISTANCE_STEPS * invAxisStepsPerMM[Z_AXIS]) -// Some dfines to make clearer reading, as we overload these cartesion memory locations for delta +// Some defines to make clearer reading, as we overload these cartesian memory locations for delta #define towerAMaxSteps Printer::xMaxSteps #define towerBMaxSteps Printer::yMaxSteps #define towerCMaxSteps Printer::zMaxSteps @@ -126,18 +127,27 @@ public: int32_t correct(int32_t x, int32_t y, int32_t z) const; void updateDerived(); void reportStatus(); + bool isEnabled() {return enabled;} + int32_t zMaxSteps() {return zEnd;} + void set(float x,float y,float z); + void showMatrix(); + void resetCorrection(); private: - INLINE int matrixIndex(fast8_t x, fast8_t y) const; - INLINE int32_t getMatrix(int index) const; - INLINE void setMatrix(int32_t val, int index); + int matrixIndex(fast8_t x, fast8_t y) const; + int32_t getMatrix(int index) const; + void setMatrix(int32_t val, int index); bool isCorner(fast8_t i, fast8_t j) const; INLINE int32_t extrapolatePoint(fast8_t x1, fast8_t y1, fast8_t x2, fast8_t y2) const; void extrapolateCorner(fast8_t x, fast8_t y, fast8_t dx, fast8_t dy); void extrapolateCorners(); - void resetCorrection(); // attributes +#if DRIVE_SYSTEM == DELTA int32_t step; int32_t radiusCorrectionSteps; +#else + int32_t xCorrectionSteps,xOffsetSteps; + int32_t yCorrectionSteps,yOffsetSteps; +#endif int32_t zStart,zEnd; #if !DISTORTION_PERMANENT int32_t matrix[DISTORTION_CORRECTION_POINTS * DISTORTION_CORRECTION_POINTS]; @@ -167,9 +177,11 @@ private: class Endstops { static flag8_t lastState; static flag8_t lastRead; + static flag8_t accumulator; #ifdef EXTENDED_ENDSTOPS static flag8_t lastState2; static flag8_t lastRead2; + static flag8_t accumulator2; #endif public: static void update(); @@ -177,6 +189,18 @@ public: static INLINE bool anyXYZMax() { return (lastState & (ENDSTOP_X_MAX_ID|ENDSTOP_Z_MAX_ID|ENDSTOP_Z_MAX_ID)) != 0; } + static INLINE void resetAccumulator() { + accumulator = 0; +#ifdef EXTENDED_ENDSTOPS + accumulator2 = 0; +#endif + } + static INLINE void fillFromAccumulator() { + lastState = accumulator; +#ifdef EXTENDED_ENDSTOPS + lastState2 = accumulator2; +#endif + } static INLINE bool xMin() { #if (X_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_X return (lastState & ENDSTOP_X_MIN_ID) != 0; @@ -234,13 +258,26 @@ public: #endif } }; + +#ifndef DEFAULT_PRINTER_MODE +#if NUM_EXTRUDER > 0 +#define DEFAULT_PRINTER_MODE PRINTER_MODE_FFF +#elif defined(SUPPORT_LASER) && SUPPORT_LASER +#define DEFAULT_PRINTER_MODE PRINTER_MODE_LASER +#elif defined(SUPPORT_CNC) && SUPPORT_CNC +#define DEFAULT_PRINTER_MODE PRINTER_MODE_CNC +#else +#error No supported printer mode compiled +#endif +#endif class Printer { + static uint8_t debugLevel; public: #if USE_ADVANCE static volatile int extruderStepsNeeded; ///< This many extruder steps are still needed, <0 = reverse steps needed. - static uint8_t maxExtruderSpeed; ///< Timer delay for end extruder speed + static ufast8_t maxExtruderSpeed; ///< Timer delay for end extruder speed //static uint8_t extruderAccelerateDelay; ///< delay between 2 speec increases static int advanceStepsSet; #if ENABLE_QUADRATIC_ADVANCE @@ -259,12 +296,13 @@ public: static uint8_t relativeCoordinateMode; ///< Determines absolute (false) or relative Coordinates (true). static uint8_t relativeExtruderCoordinateMode; ///< Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode. - static uint8_t unitIsInches; - - static uint8_t debugLevel; + static uint8_t unitIsInches; + static uint8_t mode; + static uint8_t fanSpeed; // Last fan speed set with M106/M107 + static float zBedOffset; static uint8_t flag0,flag1; // 1 = stepper disabled, 2 = use external extruder interrupt, 4 = temp Sensor defect, 8 = homed static uint8_t flag2; - static uint8_t stepsPerTimerCall; + static fast8_t stepsPerTimerCall; static uint32_t interval; ///< Last step duration in ticks. static uint32_t timer; ///< used for acceleration/deceleration timing static uint32_t stepNumber; ///< Step number in current move. @@ -293,15 +331,17 @@ public: static int16_t travelMovesPerSecond; static int16_t printMovesPerSecond; static float radius0; +#else + static int32_t zCorrectionStepsIncluded; #endif #if FEATURE_Z_PROBE || MAX_HARDWARE_ENDSTOP_Z || NONLINEAR_SYSTEM static int32_t stepsRemainingAtZHit; #endif -#if DRIVE_SYSTEM==DELTA +#if DRIVE_SYSTEM == DELTA static int32_t stepsRemainingAtXHit; static int32_t stepsRemainingAtYHit; #endif -#if SOFTWARE_LEVELING +#ifdef SOFTWARE_LEVELING static int32_t levelingP1[3]; static int32_t levelingP2[3]; static int32_t levelingP3[3]; @@ -309,7 +349,11 @@ public: #if FEATURE_AUTOLEVEL static float autolevelTransformation[9]; ///< Transformation matrix #endif - static int8_t zBabystepsMissing; +#if FAN_THERMO_PIN > -1 + static float thermoMinTemp; + static float thermoMaxTemp; +#endif + static int16_t zBabystepsMissing; static float minimumSpeed; ///< lowest allowed speed to keep integration error small static float minimumZSpeed; ///< lowest allowed speed to keep integration error small static int32_t xMaxSteps; ///< For software endstops, limit of move in positive direction. @@ -343,9 +387,6 @@ public: static float backlashY; static float backlashZ; static uint8_t backlashDir; -#endif -#ifdef DEBUG_STEPCOUNT - static long totalStepsRemaining; #endif static float memoryX; static float memoryY; @@ -372,7 +413,7 @@ public: if(highPriority || interruptEvent == 0) interruptEvent = evt; } - + static void reportPrinterMode(); static INLINE void setMenuMode(uint8_t mode,bool on) { if(on) @@ -383,54 +424,63 @@ public: static INLINE bool isMenuMode(uint8_t mode) { - return (menuMode & mode)==mode; + return (menuMode & mode) == mode; } - + static void setDebugLevel(uint8_t newLevel); + static void toggleEcho(); + static void toggleInfo(); + static void toggleErrors(); + static void toggleDryRun(); + static void toggleCommunication(); + static void toggleNoMoves(); + static INLINE uint8_t getDebugLevel() {return debugLevel;} static INLINE bool debugEcho() { - return ((debugLevel & 1)!=0); + return ((debugLevel & 1) != 0); } static INLINE bool debugInfo() { - return ((debugLevel & 2)!=0); + return ((debugLevel & 2) != 0); } static INLINE bool debugErrors() { - return ((debugLevel & 4)!=0); + return ((debugLevel & 4) != 0); } static INLINE bool debugDryrun() { - return ((debugLevel & 8)!=0); + return ((debugLevel & 8) != 0); } static INLINE bool debugCommunication() { - return ((debugLevel & 16)!=0); + return ((debugLevel & 16) != 0); } static INLINE bool debugNoMoves() { - return ((debugLevel & 32)!=0); + return ((debugLevel & 32) != 0); } - static INLINE bool debugFlag(unsigned long flags) + static INLINE bool debugFlag(uint8_t flags) { return (debugLevel & flags); } - static INLINE void debugSet(unsigned long flags) + static INLINE void debugSet(uint8_t flags) { - debugLevel |= flags; + setDebugLevel(debugLevel | flags); } - static INLINE void debugReset(unsigned long flags) + static INLINE void debugReset(uint8_t flags) { - debugLevel &= ~flags; - } - + setDebugLevel(debugLevel & ~flags); + } + /** Sets the pwm for the fan speed. Gets called by motion control ot Commands::setFanSpeed. */ + static void setFanSpeedDirectly(uint8_t speed); + static void setFan2SpeedDirectly(uint8_t speed); /** \brief Disable stepper motor for x direction. */ static INLINE void disableXStepper() { @@ -460,6 +510,9 @@ public: #endif #if FEATURE_TWO_ZSTEPPER && (Z2_ENABLE_PIN > -1) WRITE(Z2_ENABLE_PIN, !Z_ENABLE_ON); +#endif +#if FEATURE_THREE_ZSTEPPER && (Z3_ENABLE_PIN > -1) + WRITE(Z3_ENABLE_PIN, !Z_ENABLE_ON); #endif } @@ -492,6 +545,9 @@ public: #endif #if FEATURE_TWO_ZSTEPPER && (Z2_ENABLE_PIN > -1) WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); +#endif +#if FEATURE_THREE_ZSTEPPER && (Z3_ENABLE_PIN > -1) + WRITE(Z3_ENABLE_PIN, Z_ENABLE_ON); #endif } @@ -537,6 +593,9 @@ public: WRITE(Z_DIR_PIN, !INVERT_Z_DIR); #if FEATURE_TWO_ZSTEPPER WRITE(Z2_DIR_PIN, !INVERT_Z_DIR); +#endif +#if FEATURE_THREE_ZSTEPPER + WRITE(Z3_DIR_PIN, !INVERT_Z_DIR); #endif } else @@ -544,6 +603,9 @@ public: WRITE(Z_DIR_PIN, INVERT_Z_DIR); #if FEATURE_TWO_ZSTEPPER WRITE(Z2_DIR_PIN, INVERT_Z_DIR); +#endif +#if FEATURE_THREE_ZSTEPPER + WRITE(Z3_DIR_PIN, INVERT_Z_DIR); #endif } } @@ -697,6 +759,15 @@ public: { flag2 = (b ? flag2 | PRINTER_FLAG2_HOMING : flag2 & ~PRINTER_FLAG2_HOMING); } + static INLINE uint8_t isAllEMotors() + { + return flag2 & PRINTER_FLAG2_ALL_E_MOTORS; + } + + static INLINE void setAllEMotors(uint8_t b) + { + flag2 = (b ? flag2 | PRINTER_FLAG2_ALL_E_MOTORS : flag2 & ~PRINTER_FLAG2_ALL_E_MOTORS); + } static INLINE uint8_t isDebugJam() { @@ -744,8 +815,8 @@ public: static INLINE void unsetAllSteppersDisabled() { flag0 &= ~PRINTER_FLAG0_STEPPER_DISABLED; -#if FAN_BOARD_PIN>-1 - pwm_pos[NUM_EXTRUDER + 1] = 255; +#if FAN_BOARD_PIN > -1 + pwm_pos[PWM_BOARD_FAN] = 255; #endif // FAN_BOARD_PIN } static INLINE bool isAnyTempsensorDefect() @@ -786,33 +857,33 @@ public: #if (GANTRY) if(motorX <= -2) { - WRITE(X_STEP_PIN,HIGH); + WRITE(X_STEP_PIN,START_STEP_WITH_HIGH); #if FEATURE_TWO_XSTEPPER - WRITE(X2_STEP_PIN,HIGH); + WRITE(X2_STEP_PIN,START_STEP_WITH_HIGH); #endif motorX += 2; } else if(motorX >= 2) { - WRITE(X_STEP_PIN,HIGH); + WRITE(X_STEP_PIN,START_STEP_WITH_HIGH); #if FEATURE_TWO_XSTEPPER - WRITE(X2_STEP_PIN,HIGH); + WRITE(X2_STEP_PIN,START_STEP_WITH_HIGH); #endif motorX -= 2; } if(motorYorZ <= -2) { - WRITE(Y_STEP_PIN,HIGH); + WRITE(Y_STEP_PIN,START_STEP_WITH_HIGH); #if FEATURE_TWO_YSTEPPER - WRITE(Y2_STEP_PIN,HIGH); + WRITE(Y2_STEP_PIN,START_STEP_WITH_HIGH); #endif motorYorZ += 2; } else if(motorYorZ >= 2) { - WRITE(Y_STEP_PIN,HIGH); + WRITE(Y_STEP_PIN,START_STEP_WITH_HIGH); #if FEATURE_TWO_YSTEPPER - WRITE(Y2_STEP_PIN,HIGH); + WRITE(Y2_STEP_PIN,START_STEP_WITH_HIGH); #endif motorYorZ -= 2; } @@ -823,53 +894,86 @@ public: #if (GANTRY) if(motorX <= -2) { - WRITE(X_STEP_PIN,HIGH); + WRITE(X_STEP_PIN,START_STEP_WITH_HIGH); #if FEATURE_TWO_XSTEPPER - WRITE(X2_STEP_PIN,HIGH); + WRITE(X2_STEP_PIN,START_STEP_WITH_HIGH); #endif motorX += 2; } else if(motorX >= 2) { - WRITE(X_STEP_PIN,HIGH); + WRITE(X_STEP_PIN,START_STEP_WITH_HIGH); #if FEATURE_TWO_XSTEPPER - WRITE(X2_STEP_PIN,HIGH); + WRITE(X2_STEP_PIN,START_STEP_WITH_HIGH); #endif motorX -= 2; } if(motorYorZ <= -2) { //ANALYZER_ON(ANALYZER_CH3); // I dont think i can use these as they are for the y - possible bug area though - WRITE(Z_STEP_PIN,HIGH); + WRITE(Z_STEP_PIN,START_STEP_WITH_HIGH); #if FEATURE_TWO_ZSTEPPER - WRITE(Z2_STEP_PIN,HIGH); + WRITE(Z2_STEP_PIN,START_STEP_WITH_HIGH); +#endif +#if FEATURE_THREE_ZSTEPPER + WRITE(Z3_STEP_PIN,START_STEP_WITH_HIGH); #endif motorYorZ += 2; } else if(motorYorZ >= 2) { //ANALYZER_ON(ANALYZER_CH3); // I dont think i can use these as they are for the y - possible bug area though - WRITE(Z_STEP_PIN,HIGH); + WRITE(Z_STEP_PIN,START_STEP_WITH_HIGH); #if FEATURE_TWO_ZSTEPPER - WRITE(Z2_STEP_PIN,HIGH); + WRITE(Z2_STEP_PIN,START_STEP_WITH_HIGH); +#endif +#if FEATURE_THREE_ZSTEPPER + WRITE(Z3_STEP_PIN,START_STEP_WITH_HIGH); #endif motorYorZ -= 2; } +#endif + } + static INLINE void startXStep() + { + WRITE(X_STEP_PIN,START_STEP_WITH_HIGH); +#if FEATURE_TWO_XSTEPPER + WRITE(X2_STEP_PIN,START_STEP_WITH_HIGH); +#endif + } + static INLINE void startYStep() + { + WRITE(Y_STEP_PIN,START_STEP_WITH_HIGH); +#if FEATURE_TWO_YSTEPPER + WRITE(Y2_STEP_PIN,START_STEP_WITH_HIGH); +#endif + } + static INLINE void startZStep() + { + WRITE(Z_STEP_PIN,START_STEP_WITH_HIGH); +#if FEATURE_TWO_ZSTEPPER + WRITE(Z2_STEP_PIN,START_STEP_WITH_HIGH); +#endif +#if FEATURE_THREE_ZSTEPPER + WRITE(Z3_STEP_PIN,START_STEP_WITH_HIGH); #endif } static INLINE void endXYZSteps() { - WRITE(X_STEP_PIN,LOW); + WRITE(X_STEP_PIN,!START_STEP_WITH_HIGH); #if FEATURE_TWO_XSTEPPER - WRITE(X2_STEP_PIN,LOW); + WRITE(X2_STEP_PIN,!START_STEP_WITH_HIGH); #endif - WRITE(Y_STEP_PIN,LOW); + WRITE(Y_STEP_PIN,!START_STEP_WITH_HIGH); #if FEATURE_TWO_YSTEPPER - WRITE(Y2_STEP_PIN,LOW); + WRITE(Y2_STEP_PIN,!START_STEP_WITH_HIGH); #endif - WRITE(Z_STEP_PIN,LOW); + WRITE(Z_STEP_PIN,!START_STEP_WITH_HIGH); #if FEATURE_TWO_ZSTEPPER - WRITE(Z2_STEP_PIN,LOW); + WRITE(Z2_STEP_PIN,!START_STEP_WITH_HIGH); +#endif +#if FEATURE_THREE_ZSTEPPER + WRITE(Z3_STEP_PIN,!START_STEP_WITH_HIGH); #endif } static INLINE speed_t updateStepsPerTimerCall(speed_t vbase) @@ -956,13 +1060,17 @@ public: static void defaultLoopActions(); static uint8_t setDestinationStepsFromGCode(GCode *com); static uint8_t moveTo(float x,float y,float z,float e,float f); - static uint8_t moveToReal(float x,float y,float z,float e,float f); + static uint8_t moveToReal(float x,float y,float z,float e,float f,bool pathOptimize = true); static void homeAxis(bool xaxis,bool yaxis,bool zaxis); /// Home axis static void setOrigin(float xOff,float yOff,float zOff); static bool isPositionAllowed(float x,float y,float z); static INLINE int getFanSpeed() { - return (int)pwm_pos[NUM_EXTRUDER + 2]; + return (int)pwm_pos[PWM_FAN1]; + } + static INLINE int getFan2Speed() + { + return (int)pwm_pos[PWM_FAN2]; } #if NONLINEAR_SYSTEM static INLINE void setDeltaPositions(long xaxis, long yaxis, long zaxis) @@ -977,8 +1085,11 @@ public: static float runZMaxProbe(); #endif #if FEATURE_Z_PROBE + static void startProbing(bool runScript); + static void finishProbing(); static float runZProbe(bool first,bool last,uint8_t repeat = Z_PROBE_REPETITIONS,bool runStartScript = true); static void waitForZProbeStart(); + static float bendingCorrectionAt(float x,float y); #endif // Moved outside FEATURE_Z_PROBE to allow auto-level functional test on // system without Z-probe @@ -1010,7 +1121,10 @@ public: } static void showConfiguration(); static void setCaseLight(bool on); - static void reportCaseLightStatus(); + static void reportCaseLightStatus(); +#if JSON_OUTPUT + static void showJSONStatus(int type); +#endif private: static void homeXAxis(); static void homeYAxis(); @@ -1018,5 +1132,3 @@ private: }; #endif // PRINTER_H_INCLUDED - - diff --git a/Repetier/Repetier.cbp b/Repetier/Repetier.cbp deleted file mode 100644 index 05654ec..0000000 --- a/Repetier/Repetier.cbp +++ /dev/null @@ -1,875 +0,0 @@ - - - - - - diff --git a/Repetier/Repetier.depend b/Repetier/Repetier.depend deleted file mode 100644 index f829e3e..0000000 --- a/Repetier/Repetier.depend +++ /dev/null @@ -1,1696 +0,0 @@ -# depslib dependency file v1.0 -1385559246 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\commands.cpp - "Repetier.h" - -1364243178 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\reptier.h - - "Configuration.h" - - "HAL.h" - "ui.h" - "SdFat.h" - "SdFat.h" - "Printer.h" - "motion.h" - "HAL.h" - "SdFat.h" - -1385747986 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\configuration.h - "pins.h" - -1385737874 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\pins.h - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\print.h - - - "WString.h" - "Printable.h" - -1371029533 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wstring.h - - - - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\printable.h - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\new.h - - -1371029501 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\arduino.h - - - - - - - "binary.h" - "WCharacter.h" - "WString.h" - "HardwareSerial.h" - "pins_arduino.h" - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\binary.h - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wcharacter.h - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\hardwareserial.h - - "Stream.h" - "USBAPI.h" - -1371029229 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\stream.h - - "Print.h" - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\usbapi.h - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\variants\mega\pins_arduino.h - - -1382096934 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\gcode.h - -1378480129 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\fastio.h - - -1385747922 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\ui.h - "gcode.h" - "uilang.h" - "uiconfig.h" - "uilang.h" - "uimenu.h" - -1385563205 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\uilang.h - -1385747464 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\uiconfig.h - -1385138626 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\uimenu.h - -1381855209 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\sdfat.h - - -1382973117 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\eeprom.h - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\cdc.cpp - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\cdc.cpp - "Platform.h" - "USBAPI.h" - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\platform.h - - - - - - "Arduino.h" - "USBDesc.h" - "USBCore.h" - "USBAPI.h" - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\usbdesc.h - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\usbcore.h - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\main.cpp - - -1371029218 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\main.cpp - - - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\new.cpp - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\new.cpp - - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\print.cpp - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\print.cpp - - - - - "Arduino.h" - "Print.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\stream.cpp - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\stream.cpp - "Arduino.h" - "Stream.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\usbcore.cpp - - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\hid.cpp - "Platform.h" - "USBAPI.h" - "USBDesc.h" - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\usbcore.cpp - "Platform.h" - "USBAPI.h" - "USBDesc.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\winterrupts.c - - -1371029247 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\winterrupts.c - - - - - - "wiring_private.h" - -1371029524 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wiring_private.h - - - - - "Arduino.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring.c - - -1371029270 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wiring.c - "wiring_private.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring_analog.c - - -1371029278 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wiring_analog.c - "wiring_private.h" - "pins_arduino.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring_digital.c - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wiring_digital.c - "wiring_private.h" - "pins_arduino.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring_pulse.c - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wiring_pulse.c - "wiring_private.h" - "pins_arduino.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring_shift.c - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wiring_shift.c - "wiring_private.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wmath.cpp - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wmath.cpp - "stdlib.h" - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wstring.cpp - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\wstring.cpp - "WString.h" - -1382356654 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\eeprom.cpp - "Repetier.h" - -1384098293 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\extruder.cpp - "Repetier.h" - "pins_arduino.h" - "ui.h" - "Eeprom.h" - -1384523174 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\gcode.cpp - "Repetier.h" - -1385135456 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\motion.cpp - "Repetier.h" - -1385747555 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\repetier.ino - "Repetier.h" - - - -1384524650 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\sdcard.cpp - "Repetier.h" - "ui.h" - -1382857032 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\sdfat.cpp - "Repetier.h" - "Arduino.h" - "WProgram.h" - - -1385747952 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\ui.cpp - "Repetier.h" - "ui.h" - - - - "Eeprom.h" - - - - -1385200613 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\printer.h - -1381767601 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\hal.h - - - - - - - "Print.h" - "Arduino.h" - "WProgram.h" - "fastio.h" - -1381070783 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\hal.cpp - "Repetier.h" - - - -1384508019 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\motion.h - -1361428610 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\cdc.cpp - "Platform.h" - "USBAPI.h" - - -1322479932 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\platform.h - - - - - - "Arduino.h" - "USBDesc.h" - "USBCore.h" - "USBAPI.h" - -1333276861 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\pgmspace.h - - - - - - -1263081802 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\io.h - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -1361522023 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\sfr_defs.h - - -1263081814 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\portpins.h - -1263081800 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\common.h - - -1263081814 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\version.h - -1263081802 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\iom1280.h - - -1228397784 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\iomxx0_1.h - -1263081804 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\iom2560.h - - -1263081806 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\iom328p.h - -1263081804 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\iom168p.h - -1263081802 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\fuse.h - - - - -1263081814 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\lock.h - - - -1263081800 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\eeprom.h - - - - -1231619566 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\stdint.h - - -1337179353 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\interrupt.h - - -1334462626 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\util\delay.h - - - - -1263081816 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\util\delay_basic.h - - - -1361529168 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\arduino.h - - - - "ardusim.h" - - - - "binary.h" - "WCharacter.h" - "WString.h" - "HardwareSerial.h" - "pins_arduino.h" - -1361531148 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ardusim.h - - - - - - - - - - - - - - - - - - -1322479932 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\binary.h - -1355115034 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\wcharacter.h - - -1361427512 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\wstring.h - - - - - - -1361463431 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\hardwareserial.h - - "Stream.h" - - "USBAPI.h" - -1355115034 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\stream.h - - "Print.h" - -1355115034 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\print.h - - - "WString.h" - "Printable.h" - -1322479934 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\printable.h - - -1361429299 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\new.h - - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\ctb.h - "ctb-0.16/fifo.h" - "ctb-0.16/gpib.h" - "ctb-0.16/getopt.h" - "ctb-0.16/iobase.h" - "ctb-0.16/kbhit.h" - "ctb-0.16/portscan.h" - "ctb-0.16/serport.h" - "ctb-0.16/serportx.h" - "ctb-0.16/timer.h" - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\fifo.h - - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\gpib.h - "ctb-0.16/iobase.h" - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\iobase.h - "ctb-0.16/fifo.h" - - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\getopt.h - "win32/getopt.h" - - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\win32\getopt.h - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\kbhit.h - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\portscan.h - - - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\serport.h - "ctb-0.16/win32/serport.h" - "ctb-0.16/linux/serport.h" - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\win32\serport.h - "../serportx.h" - - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\serportx.h - - - "ctb-0.16/iobase.h" - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\linux\serport.h - "ctb-0.16/serportx.h" - - - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\timer.h - "win32/timer.h" - "linux/timer.h" - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\win32\timer.h - - -1338884884 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\ctb-0.16\linux\timer.h - - -1355115034 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\usbapi.h - -1361531400 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\variants\standard\pins_arduino.h - - - -1355115034 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\usbdesc.h - -1355115034 c:\users\littwin\documents\arduino\codeblocks\ardusim\arduino\cores\usbcore.h - -1263081814 c:\users\littwin\documents\arduino\codeblocks\ardusim\include\avr\wdt.h - - - - - -1385138927 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\repetier.h - "Configuration.h" - "HAL.h" - "gcode.h" - "ui.h" - "Communication.h" - "SdFat.h" - "SdFat.h" - "Extruder.h" - "Printer.h" - "motion.h" - "HAL.h" - "SdFat.h" - "Commands.h" - "Eeprom.h" - -1382173675 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\extruder.h - -1378480129 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\tone.cpp - - -1362986950 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\tone.cpp - - - "Arduino.h" - "pins_arduino.h" - -1382357795 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\commands.h - -1385200383 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\printer.cpp - "Repetier.h" - -1385279439 y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\communication.h - -1385279431 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\communication.cpp - "Repetier.h" - -1332666599 source:y:\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\hardwareserial.cpp - - -1362990550 c:\users\littwin\documents\arduino\codeblocks\arduino\hardware\arduino\cores\arduino\hardwareserial.cpp - - - - - "Arduino.h" - "wiring_private.h" - "HardwareSerial.h" - -1393003764 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\commands.cpp - "Repetier.h" - -1392999863 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\repetier.h - "Configuration.h" - "HAL.h" - "gcode.h" - "ui.h" - "Communication.h" - "SdFat.h" - "SdFat.h" - "Extruder.h" - "Printer.h" - "motion.h" - "HAL.h" - "SdFat.h" - "Commands.h" - "Eeprom.h" - -1393004086 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\configuration.h - "pins.h" - -1392559164 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\pins.h - "userpins.h" - -1392737149 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\hal.h - - - - - - - "Print.h" - "Arduino.h" - "WProgram.h" - "fastio.h" - -1388425592 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\fastio.h - - -1388425592 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\gcode.h - -1392470522 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\ui.h - "gcode.h" - "uilang.h" - "uiconfig.h" - "uilang.h" - "uimenu.h" - -1388425592 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\uilang.h - -1389515580 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\uiconfig.h - -1392904516 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\uimenu.h - -1392999234 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\communication.h - -1388425592 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\sdfat.h - - -1388425592 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\extruder.h - -1393001834 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\printer.h - -1392830305 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\motion.h - -1389112236 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\commands.h - -1392999717 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\eeprom.h - -1392999209 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\communication.cpp - "Repetier.h" - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\cdc.cpp - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\main.cpp - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\new.cpp - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\print.cpp - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\stream.cpp - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\tone.cpp - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\usbcore.cpp - - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\winterrupts.c - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring.c - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring_analog.c - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring_digital.c - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring_pulse.c - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wiring_shift.c - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wmath.cpp - - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\cores\wstring.cpp - - -1392999214 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\eeprom.cpp - "Repetier.h" - -1392737088 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\extruder.cpp - "Repetier.h" - "pins_arduino.h" - "ui.h" - "Eeprom.h" - -1391866195 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\gcode.cpp - "Repetier.h" - -1392737088 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\hal.cpp - "Repetier.h" - - - -1393002577 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\motion.cpp - "Repetier.h" - -1393002381 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\printer.cpp - "Repetier.h" - -1391524354 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\repetier.ino - "Repetier.h" - - -1391523608 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\sdcard.cpp - "Repetier.h" - "ui.h" - -1388425592 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\sdfat.cpp - "Repetier.h" - "Arduino.h" - "WProgram.h" - - -1392831717 source:z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\ui.cpp - "Repetier.h" - - - - - - "u8glib_ex.h" - -1380830876 c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\u8glib.h - - "utility/u8g.h" - -1380830876 c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g.h - - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\u8glib.cpp - "U8glib.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\chessengine.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_bitmap.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_circle.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_clip.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_api.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_api_16gr.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_attiny85_hw_spi.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_common.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_fast_parallel.c - "u8g.h" - - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_hw_spi.c - "u8g.h" - - - - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_hw_usart_spi.c - "u8g.h" - - - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_no_en_parallel.c - "u8g.h" - - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_parallel.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_port_d_wr.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_ssd_i2c.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_st7920_custom.c - "u8g.h" - - "wiring_private.h" - "pins_arduino.h" - - "wiring_private.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_st7920_hw_spi.c - "u8g.h" - - "wiring_private.h" - "pins_arduino.h" - - "wiring_private.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_st7920_spi.c - "u8g.h" - - "wiring_private.h" - "pins_arduino.h" - - "wiring_private.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_std_sw_spi.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_sw_spi.c - "u8g.h" - - "wiring_private.h" - "pins_arduino.h" - - "wiring_private.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_arduino_t6963.c - "u8g.h" - - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_atmega_hw_spi.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_atmega_parallel.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_atmega_st7920_hw_spi.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_atmega_st7920_spi.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_atmega_sw_spi.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_i2c.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_io.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_com_null.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_cursor.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_delay.c - "u8g.h" - - - - - - - "plib.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_a2_micro_printer.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_flipdisc_2x7.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_gprof.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ht1632.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ili9325d_320x240.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ks0108_128x64.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_lc7981_160x80.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_lc7981_240x128.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_lc7981_240x64.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_lc7981_320x64.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_null.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_pcd8544_84x48.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_pcf8812_96x65.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_sbn1661_122x32.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1306_128x32.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1306_128x64.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1309_128x64.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1322_nhd31oled_bw.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1322_nhd31oled_gr.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1325_nhd27oled_bw.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1325_nhd27oled_bw_new.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1325_nhd27oled_gr.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1325_nhd27oled_gr_new.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1327_96x96_gr.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_ssd1351_128x128.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7565_64128n.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7565_dogm128.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7565_dogm132.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7565_lm6059.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7565_lm6063.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7565_nhd_c12832.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7565_nhd_c12864.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7687_c144mvgd.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7920_128x64.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7920_192x32.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_st7920_202x32.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_t6963_128x64.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_t6963_240x128.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_t6963_240x64.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_tls8204_84x48.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_uc1601_c128032.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_uc1610_dogxl160.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_uc1701_dogs102.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_dev_uc1701_mini12864.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_ellipse.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_font.c - "u8g.h" - -1385900599 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_font_data.c - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_line.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_ll_api.c - - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_page.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb14v1.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb16h1.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb16h2.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb16v1.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb16v2.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb32h1.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb8h1.c - "u8g.h" - - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb8h1f.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb8h2.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb8h8.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb8v1.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pb8v2.c - "u8g.h" - - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pbxh16.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_pbxh24.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_rect.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_rot.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_scale.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_state.c - - "u8g.h" - - "sam.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_u16toa.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_u8toa.c - "u8g.h" - -1380830876 source:c:\users\littwin\documents\arduino\codeblocks\arduino\libraries\u8glib\utility\u8g_virtual_screen.c - "u8g.h" - -1387028940 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\font_repetier_6x10.h - - - - - - - - "plib.h" - - "sam.h" - - - - "wiring_private.h" - "pins_arduino.h" - - "wiring_private.h" - -1388425592 z:\users\littwin\documents\projekte\repetier\repetier-firmware\src\arduinoavr\repetier\u8glib_ex.h - - - - - - - - "plib.h" - - "sam.h" - - - - "wiring_private.h" - "pins_arduino.h" - - "wiring_private.h" - diff --git a/Repetier/Repetier.h b/Repetier/Repetier.h index 7d3e20e..79d05dd 100644 --- a/Repetier/Repetier.h +++ b/Repetier/Repetier.h @@ -23,15 +23,16 @@ #define _REPETIER_H #include - -#define REPETIER_VERSION "0.92.3" +#include +#define REPETIER_VERSION "0.92.8" // ########################################################################################## // ## Debug configuration ## // ########################################################################################## // These are run time sqitchable debug flags enum debugFlags {DEB_ECHO = 0x1, DEB_INFO = 0x2, DEB_ERROR = 0x4,DEB_DRYRUN = 0x8, - DEB_COMMUNICATION = 0x10, DEB_NOMOVES = 0x20, DEB_DEBUG = 0x40}; + DEB_COMMUNICATION = 0x10, DEB_NOMOVES = 0x20, DEB_DEBUG = 0x40 + }; /** Uncomment, to see detailed data for every move. Only for debugging purposes! */ //#define DEBUG_QUEUE_MOVE @@ -62,6 +63,8 @@ usage or for seraching for memory induced errors. Switch it off for production, //#define DEBUG_SEGMENT_LENGTH // Find the maximum real jerk during a print //#define DEBUG_REAL_JERK +// Debug reason for not mounting a sd card +//#define DEBUG_SD_ERROR // Uncomment the following line to enable debugging. You can better control debugging below the following line //#define DEBUG @@ -150,6 +153,8 @@ usage or for seraching for memory induced errors. Switch it off for production, #define CONTROLLER_SPARKLCD 19 #define CONTROLLER_BAM_DICE_DUE 20 #define CONTROLLER_VIKI2 21 +#define CONTROLLER_LCD_MP_PHARAOH_DUE 22 +#define CONTROLLER_SPARKLCD_ADAPTER 23 #define CONTROLLER_FELIX_DUE 405 //direction flags @@ -174,9 +179,27 @@ usage or for seraching for memory induced errors. Switch it off for production, // add pid control #define TEMP_PID 1 + +#define PRINTER_MODE_FFF 0 +#define PRINTER_MODE_LASER 1 +#define PRINTER_MODE_CNC 2 +// we can not prevent this as some configs need a parameter and others not +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-variable" #include "Configuration.h" +inline void memcopy2(void *dest,void *source) { + *((int16_t*)dest) = *((int16_t*)source); +} +inline void memcopy4(void *dest,void *source) { + *((int32_t*)dest) = *((int32_t*)source); +} + +#ifndef JSON_OUTPUT +#define JSON_OUTPUT 0 +#endif + #if FEATURE_Z_PROBE && Z_PROBE_PIN < 0 #error You need to define Z_PROBE_PIN to use z probe! #endif @@ -230,10 +253,12 @@ usage or for seraching for memory induced errors. Switch it off for production, #define SPEED_MAX_MILLIS 60 #define SPEED_MAGNIFICATION 100.0f -#define SOFTWARE_LEVELING (FEATURE_SOFTWARE_LEVELING && (DRIVE_SYSTEM==DELTA)) +#define SOFTWARE_LEVELING (defined(FEATURE_SOFTWARE_LEVELING) && (DRIVE_SYSTEM==DELTA)) /** \brief Horizontal distance bridged by the diagonal push rod when the end effector is in the center. It is pretty close to 50% of the push rod length (250 mm). */ +#ifndef ROD_RADIUS #define ROD_RADIUS (PRINTER_RADIUS-END_EFFECTOR_HORIZONTAL_OFFSET-CARRIAGE_HORIZONTAL_OFFSET) +#endif #ifndef UI_SPEEDDEPENDENT_POSITIONING #define UI_SPEEDDEPENDENT_POSITIONING true @@ -276,16 +301,28 @@ usage or for seraching for memory induced errors. Switch it off for production, #define SHARED_COOLER 0 #endif +#ifndef START_STEP_WITH_HIGH +#define START_STEP_WITH_HIGH 1 +#endif + +#if NUM_EXTRUDER > 0 && EXT0_TEMPSENSOR_TYPE == 101 +#define SUPPORT_MAX6675 +#endif + +#if NUM_EXTRUDER > 0 && EXT0_TEMPSENSOR_TYPE == 102 +#define SUPPORT_MAX31855 +#endif + // Test for shared coolers between extruders and mainboard #if EXT0_EXTRUDER_COOLER_PIN > -1 && EXT0_EXTRUDER_COOLER_PIN == FAN_BOARD_PIN - #define SHARED_COOLER_BOARD_EXT 1 +#define SHARED_COOLER_BOARD_EXT 1 #else - #define SHARED_COOLER_BOARD_EXT 0 +#define SHARED_COOLER_BOARD_EXT 0 #endif #if defined(UI_SERVO_CONTROL) && UI_SERVO_CONTROL > FEATURE_SERVO - #undef UI_SERVO_CONTROL - #define UI_SERVO_CONTROL FEATURE_SERVO +#undef UI_SERVO_CONTROL +#define UI_SERVO_CONTROL FEATURE_SERVO #endif #if (defined(EXT0_JAM_PIN) && EXT0_JAM_PIN > -1) || (defined(EXT1_JAM_PIN) && EXT1_JAM_PIN > -1) || (defined(EXT2_JAM_PIN) && EXT2_JAM_PIN > -1) || (defined(EXT3_JAM_PIN) && EXT3_JAM_PIN > -1) || (defined(EXT4_JAM_PIN) && EXT4_JAM_PIN > -1) || (defined(EXT5_JAM_PIN) && EXT5_JAM_PIN > -1) @@ -293,6 +330,9 @@ usage or for seraching for memory induced errors. Switch it off for production, #else #define EXTRUDER_JAM_CONTROL 0 #endif +#ifndef JAM_METHOD +#define JAM_METHOD 1 +#endif #if NUM_EXTRUDER > 0 && EXT0_TEMPSENSOR_TYPE < 101 #define EXT0_ANALOG_INPUTS 1 @@ -306,7 +346,7 @@ usage or for seraching for memory induced errors. Switch it off for production, #define EXT0_ANALOG_CHANNEL #endif -#if NUM_EXTRUDER>1 && EXT1_TEMPSENSOR_TYPE<101 +#if NUM_EXTRUDER > 1 && EXT1_TEMPSENSOR_TYPE < 101 #define EXT1_ANALOG_INPUTS 1 #define EXT1_SENSOR_INDEX EXT0_ANALOG_INPUTS #define EXT1_ANALOG_CHANNEL ACCOMMA0 EXT1_TEMPSENSOR_PIN @@ -318,7 +358,7 @@ usage or for seraching for memory induced errors. Switch it off for production, #define EXT1_ANALOG_CHANNEL #endif -#if NUM_EXTRUDER>2 && EXT2_TEMPSENSOR_TYPE<101 +#if NUM_EXTRUDER > 2 && EXT2_TEMPSENSOR_TYPE<101 #define EXT2_ANALOG_INPUTS 1 #define EXT2_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS #define EXT2_ANALOG_CHANNEL ACCOMMA1 EXT2_TEMPSENSOR_PIN @@ -354,7 +394,7 @@ usage or for seraching for memory induced errors. Switch it off for production, #define EXT4_ANALOG_CHANNEL #endif -#if NUM_EXTRUDER>5 && EXT5_TEMPSENSOR_TYPE<101 +#if NUM_EXTRUDER > 5 && EXT5_TEMPSENSOR_TYPE<101 #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 ACCOMMA4 EXT5_TEMPSENSOR_PIN @@ -370,12 +410,22 @@ usage or for seraching for memory induced errors. Switch it off for production, #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 ACCOMMA5 HEATED_BED_SENSOR_PIN -#undef KOMMA -#define KOMMA , +#undef BEKOMMA +#define BED_KOMMA , #else #define BED_ANALOG_INPUTS 0 #define BED_SENSOR_INDEX HEATED_BED_SENSOR_PIN #define BED_ANALOG_CHANNEL +#define BED_KOMMA ACCOMMA5 +#endif + +#if FAN_THERMO_THERMISTOR_PIN > -1 && FAN_THERMO_PIN > -1 +#define THERMO_ANALOG_INPUTS 1 +#define THERMO_ANALOG_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS+BED_ANALOG_INPUTS +#define THERMO_ANALOG_CHANNEL BED_KOMMA FAN_THERMO_THERMISTOR_PIN +#else +#define THERMO_ANALOG_INPUTS 0 +#define THERMO_ANALOG_CHANNEL #endif #ifndef DEBUG_FREE_MEMORY @@ -385,10 +435,10 @@ usage or for seraching for memory induced errors. Switch it off for production, #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 +#define ANALOG_INPUTS (EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS+BED_ANALOG_INPUTS+THERMO_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} +#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 THERMO_ANALOG_CHANNEL} #endif #define MENU_MODE_SD_MOUNTED 1 @@ -399,6 +449,22 @@ usage or for seraching for memory induced errors. Switch it off for production, #define MENU_MODE_FULL_PID 32 #define MENU_MODE_DEADTIME 64 +#ifndef BENDING_CORRECTION_A +#define BENDING_CORRECTION_A 0 +#endif + +#ifndef BENDING_CORRECTION_B +#define BENDING_CORRECTION_B 0 +#endif + +#ifndef BENDING_CORRECTION_C +#define BENDING_CORRECTION_C 0 +#endif + +#ifndef Z_ACCELERATION_TOP +#define Z_ACCELERATION_TOP 0 +#endif + #include "HAL.h" #include "gcode.h" #define MAX_VFAT_ENTRIES (2) @@ -411,9 +477,9 @@ usage or for seraching for memory induced errors. Switch it off for production, #if UI_DISPLAY_TYPE != DISPLAY_U8G - #if (defined(USER_KEY1_PIN) && (USER_KEY1_PIN==UI_DISPLAY_D5_PIN || USER_KEY1_PIN==UI_DISPLAY_D6_PIN || USER_KEY1_PIN==UI_DISPLAY_D7_PIN)) || (defined(USER_KEY2_PIN) && (USER_KEY2_PIN==UI_DISPLAY_D5_PIN || USER_KEY2_PIN==UI_DISPLAY_D6_PIN || USER_KEY2_PIN==UI_DISPLAY_D7_PIN)) || (defined(USER_KEY3_PIN) && (USER_KEY3_PIN==UI_DISPLAY_D5_PIN || USER_KEY3_PIN==UI_DISPLAY_D6_PIN || USER_KEY3_PIN==UI_DISPLAY_D7_PIN)) || (defined(USER_KEY4_PIN) && (USER_KEY4_PIN==UI_DISPLAY_D5_PIN || USER_KEY4_PIN==UI_DISPLAY_D6_PIN || USER_KEY4_PIN==UI_DISPLAY_D7_PIN)) - #error "You cannot use DISPLAY_D5_PIN, DISPLAY_D6_PIN or DISPLAY_D7_PIN for "User Keys" with character LCD display" - #endif +#if (defined(USER_KEY1_PIN) && (USER_KEY1_PIN==UI_DISPLAY_D5_PIN || USER_KEY1_PIN==UI_DISPLAY_D6_PIN || USER_KEY1_PIN==UI_DISPLAY_D7_PIN)) || (defined(USER_KEY2_PIN) && (USER_KEY2_PIN==UI_DISPLAY_D5_PIN || USER_KEY2_PIN==UI_DISPLAY_D6_PIN || USER_KEY2_PIN==UI_DISPLAY_D7_PIN)) || (defined(USER_KEY3_PIN) && (USER_KEY3_PIN==UI_DISPLAY_D5_PIN || USER_KEY3_PIN==UI_DISPLAY_D6_PIN || USER_KEY3_PIN==UI_DISPLAY_D7_PIN)) || (defined(USER_KEY4_PIN) && (USER_KEY4_PIN==UI_DISPLAY_D5_PIN || USER_KEY4_PIN==UI_DISPLAY_D6_PIN || USER_KEY4_PIN==UI_DISPLAY_D7_PIN)) +#error You cannot use DISPLAY_D5_PIN, DISPLAY_D6_PIN or DISPLAY_D7_PIN for "User Keys" with character LCD display +#endif #endif @@ -442,65 +508,271 @@ usage or for seraching for memory induced errors. Switch it off for production, #undef min #undef max -class RMath { +class RMath +{ public: - static inline float min(float a,float b) { - if(a= 0 ? a : -a;} - static inline int32_t sqr(int32_t a) {return a*a;} - static inline uint32_t sqr(uint32_t a) {return a*a;} + static inline unsigned long absLong(long a) + { + return a >= 0 ? a : -a; + } + static inline int32_t sqr(int32_t a) + { + return a*a; + } + static inline uint32_t sqr(uint32_t a) + { + return a*a; + } #ifdef SUPPORT_64_BIT_MATH - static inline int64_t sqr(int64_t a) {return a*a;} - static inline uint64_t sqr(uint64_t a) {return a*a;} + static inline int64_t sqr(int64_t a) + { + return a*a; + } + static inline uint64_t sqr(uint64_t a) + { + return a*a; + } #endif - static inline float sqr(float a) {return a*a;} + static inline float sqr(float a) + { + return a*a; + } }; +class RVector3 +{ +public: + float x, y, z; + RVector3(float _x = 0,float _y = 0,float _z = 0):x(_x),y(_y),z(_z) {}; + RVector3(const RVector3 &a):x(a.x),y(a.y),z(a.z) {}; + + +/* const float &operator[](std::size_t idx) const + { + if(idx == 0) return x; + if(idx == 1) return y; + return z; + }; + + float &operator[](std::size_t idx) + { + switch(idx) { + case 0: return x; + case 1: return y; + case 2: return z; + } + return 0; + };*/ + + inline bool operator==(const RVector3 &rhs) + { + return x==rhs.x && y==rhs.y && z==rhs.z; + } + inline bool operator!=(const RVector3 &rhs) + { + return !(*this==rhs); + } + inline RVector3& operator=(const RVector3 &rhs) + { + if(this!=&rhs) + { + x = rhs.x; + y = rhs.y; + z = rhs.z; + } + return *this; + } + + inline RVector3& operator+=(const RVector3 &rhs) + { + x += rhs.x; + y += rhs.y; + z += rhs.z; + return *this; + } + + inline RVector3& operator-=(const RVector3 &rhs) + { + x -= rhs.x; + y -= rhs.y; + z -= rhs.z; + return *this; + } + inline RVector3 operator-() const + { + return RVector3(-x,-y,-z); + } + + inline float length() const + { + return sqrt(x * x + y * y + z * z); + } + + inline float lengthSquared() const + { + return (x*x+y*y+z*z); + } + + inline RVector3 cross(const RVector3 &b) const + { + return RVector3(y*b.z-z*b.y,z*b.x-x*b.z,x*b.y-y*b.x); + } + inline float scalar(const RVector3 &b) const + { + return (x*b.x+y*b.y+z*b.z); + } + inline RVector3 scale(float factor) const + { + return RVector3(x*factor,y*factor,z*factor); + } + inline void scaleIntern(float factor) + { + x*=factor; + y*=factor; + z*=factor; + } + inline void setMinimum(const RVector3 &b) + { + x = RMath::min(x,b.x); + y = RMath::min(y,b.y); + z = RMath::min(z,b.z); + } + inline void setMaximum(const RVector3 &b) + { + x = RMath::max(x,b.x); + y = RMath::max(y,b.y); + z = RMath::max(z,b.z); + } + inline float distance(const RVector3 &b) const + { + float dx = b.x-x,dy = b.y-y, dz = b.z-z; + return (sqrt(dx*dx+dy*dy+dz*dz)); + } + inline float angle(RVector3 &direction) + { + return static_cast(acos(scalar(direction)/(length()*direction.length()))); + } + + inline RVector3 normalize() const + { + float len = length(); + if(len != 0) len = static_cast(1.0/len); + return RVector3(x*len,y*len,z*len); + } + + inline RVector3 interpolatePosition(const RVector3 &b, float pos) const + { + float pos2 = 1.0f - pos; + return RVector3(x * pos2 + b.x * pos, y * pos2 + b.y * pos, z * pos2 + b.z * pos); + } + + inline RVector3 interpolateDirection(const RVector3 &b,float pos) const + { + //float pos2 = 1.0f - pos; + + float dot = scalar(b); + if (dot > 0.9995 || dot < -0.9995) + return interpolatePosition(b,pos); // cases cause trouble, use linear interpolation here + + float theta = acos(dot) * pos; // interpolated position + float st = sin(theta); + RVector3 t(b); + t -= scale(dot); + float lengthSq = t.lengthSquared(); + float dl = st * ((lengthSq < 0.0001f) ? 1.0f : 1.0f / sqrt(lengthSq)); + t.scaleIntern(dl); + t += scale(cos(theta)); + return t.normalize(); + } +}; + inline RVector3 operator+(RVector3 lhs, const RVector3& rhs) // first arg by value, second by const ref + { + lhs.x += rhs.x; + lhs.y += rhs.y; + lhs.z += rhs.z; + return lhs; + } + + inline RVector3 operator-(RVector3 lhs, const RVector3& rhs) // first arg by value, second by const ref + { + lhs.x -= rhs.x; + lhs.y -= rhs.y; + lhs.z -= rhs.z; + return lhs; + } + + inline RVector3 operator*(const RVector3 &lhs,float rhs) { + return lhs.scale(rhs); + } + + inline RVector3 operator*(float lhs,const RVector3 &rhs) { + return rhs.scale(lhs); + } 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 uint8_t 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 +//extern uint8 osAnalogInputPos; // Current sampling position +#if ANALOG_INPUTS > 0 +extern volatile uint osAnalogInputValues[ANALOG_INPUTS]; +#endif +#define PWM_HEATED_BED NUM_EXTRUDER +#define PWM_BOARD_FAN PWM_HEATED_BED+1 +#define PWM_FAN1 PWM_BOARD_FAN+1 +#define PWM_FAN2 PWM_FAN1+1 +#define PWM_FAN_THERMO PWM_FAN2+1 +#define NUM_PWM PWM_FAN_THERMO+1 +extern uint8_t pwm_pos[NUM_PWM]; // 0-NUM_EXTRUDER = Heater 0-NUM_EXTRUDER of extruder, NUM_EXTRUDER = Heated bed, NUM_EXTRUDER+1 Board fan, NUM_EXTRUDER+2 = Fan #if USE_ADVANCE #if ENABLE_QUADRATIC_ADVANCE extern int maxadv; @@ -542,10 +814,6 @@ extern void microstepInit(); #include "Printer.h" #include "motion.h" extern long baudrate; -#if OS_ANALOG_INPUTS>0 -// Get last result for pin x -extern volatile uint osAnalogInputValues[OS_ANALOG_INPUTS]; -#endif #include "HAL.h" @@ -554,8 +822,12 @@ extern unsigned int counterPeriodical; extern volatile uint8_t executePeriodical; extern uint8_t counter250ms; extern void writeMonitor(); +#if FEATURE_FAN_CONTROL extern uint8_t fanKickstart; - +#endif +#if FEATURE_FAN2_CONTROL +extern uint8_t fan2Kickstart; +#endif #if SDSUPPORT extern char tempLongFilename[LONG_FILENAME_LENGTH+1]; @@ -564,51 +836,65 @@ extern char fullName[LONG_FILENAME_LENGTH*SD_MAX_FOLDER_DEPTH+SD_MAX_FOLDER_DEPT #include "SdFat.h" enum LsAction {LS_SerialPrint,LS_Count,LS_GetFilename}; -class SDCard { +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 - uint8_t sdmode; // true if we are printing from sd card, 2 = stop accepting new commands - bool sdactive; - //int16_t n; - bool savetosd; - SdBaseFile parentFound; + SdFat fat; + //Sd2Card card; // ~14 Byte + //SdVolume volume; + //SdFile root; + //SdFile dir[SD_MAX_FOLDER_DEPTH+1]; + SdFile file; +#if JSON_OUTPUT + GCodeFileInfo fileInfo; +#endif + 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 + uint8_t sdmode; // true if we are printing from sd card, 2 = stop accepting new commands + bool sdactive; + //int16_t n; + bool savetosd; + SdBaseFile parentFound; - SDCard(); - void initsd(); - void writeCommand(GCode *code); - bool selectFile(const char *filename,bool silent=false); - void mount(); - void unmount(); - void startPrint(); - void pausePrint(bool intern = false); - void continuePrint(bool intern = false); - void stopPrint(); - 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(); + SDCard(); + void initsd(); + void writeCommand(GCode *code); + bool selectFile(const char *filename,bool silent=false); + void mount(); + void unmount(); + void startPrint(); + void pausePrint(bool intern = false); + void continuePrint(bool intern = false); + void stopPrint(); + inline void setIndex(uint32_t newpos) + { + if(!sdactive) return; + sdpos = newpos; + file.seekSet(sdpos); + } + void printStatus(); + void ls(); +#if JSON_OUTPUT + void lsJSON(const char *filename); + void JSONFileInfo(const char *filename); + static void printEscapeChars(const char *s); +#endif + 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(); #ifdef GLENN_DEBUG - void writeToFile(); + void writeToFile(); #endif private: - uint8_t lsRecursive(SdBaseFile *parent,uint8_t level,char *findFilename); - // SdFile *getDirectory(char* name); + uint8_t lsRecursive(SdBaseFile *parent,uint8_t level,char *findFilename); +// SdFile *getDirectory(char* name); }; extern SDCard sd; @@ -652,5 +938,3 @@ extern int debugWaitLoop; #endif #endif - - diff --git a/Repetier/Repetier.ino b/Repetier/Repetier.ino index 0dbf754..e7bc914 100644 --- a/Repetier/Repetier.ino +++ b/Repetier/Repetier.ino @@ -39,7 +39,7 @@ Implemented Codes - G0 -> G1 - G1 - Coordinated Movement X Y Z E, S1 disables boundary check, S0 enables it - G4 - Dwell S or P -- G10 S<1 = long retract, 0 = short retract = default> retracts filament accoridng to stored setting +- G10 S<1 = long retract, 0 = short retract = default> retracts filament according to stored setting - G11 S<1 = long retract, 0 = short retract = default> = Undo retraction according to stored setting - G20 - Units for G0/G1 are inches. - G21 - Units for G0/G1 are mm. @@ -47,19 +47,21 @@ Implemented Codes - G29 S<0..2> - Z-Probe at the 3 defined probe points. S = 1 measure avg. zHeight, S = 2 store avg zHeight - G30 P<0..3> - Single z-probe at current position P = 1 first measurement, P = 2 Last measurement P = 0 or 3 first and last measurement - G31 - Write signal of probe sensor -- G32 S<0..2> P<0..1> - Autolevel print bed. S = 1 measure zLength, S = 2 Measue and store new zLength +- G32 S<0..2> P<0..1> - Autolevel print bed. S = 1 measure zLength, S = 2 Measure and store new zLength - G90 - Use absolute coordinates - G91 - Use relative coordinates -- G92 - Set current position to cordinates given +- G92 - Set current position to coordinates given - G131 - set extruder offset position to 0 - needed for calibration with G132 - G132 - calibrate endstop positions. Call this, after calling G131 and after centering the extruder holder. +- G133 - measure steps until max endstops for deltas. Can be used to detect lost steps within tolerances of endstops. +- G134 Px Sx Zx - Calibrate nozzle height difference (need z probe in nozzle!) Px = reference extruder, Sx = only measure extrude x against reference, Zx = add to measured z distance for Sx for correction. RepRap M Codes - M104 - Set extruder target temp - M105 - Read current temp -- M106 - Fan on -- M107 - Fan off +- M106 S P - Fan on speed = 0..255, P = 0 or 1, 0 is default and can be omitted +- M107 P - Fan off, P = 0 or 1, 0 is default and can be omitted - M109 - Wait for extruder current temp to reach target temp. - M114 - Display current position @@ -108,7 +110,8 @@ Custom M Codes - M207 X Z E - Changes current jerk values, but do not store them in eeprom. - M209 S<0/1> - Enable/disable autoretraction - M220 S - Increase/decrease given feedrate -- M221 S - Increase/decrease given flow rate +- M221 S - Increase/decrease given flow rate +- M228 P S - Wait for pin getting state S. Add X0 to init as input without pullup and X1 for input with pullup. - M231 S X Y Z F - Set OPS parameter - M232 - Read and reset max. advance values - M233 X Y - Set temporary advance K-value to X and linear term advanceL to Y @@ -128,7 +131,12 @@ Custom M Codes - M360 - show configuration - M400 - Wait until move buffers empty. - M401 - Store x, y and z position. -- M402 - Go to stored position. If X, Y or Z is specified, only these coordinates are used. F changes feedrate fo rthat move. +- M402 - Go to stored position. If X, Y or Z is specified, only these coordinates are used. F changes feedrate fo rthat move. +- M450 - Reports printer mode +- M451 - Set printer mode to FFF +- M452 - Set printer mode to laser +- M453 - Set printer mode to CNC +- M460 X Y : Set temperature range for thermistor controlled fan - M500 Store settings to EEPROM - M501 Load settings from EEPROM - M502 Reset settings to the one in configuration.h. Does not store values in EEPROM! @@ -163,5 +171,3 @@ void loop() - - diff --git a/Repetier/Repetier.layout b/Repetier/Repetier.layout deleted file mode 100644 index 2c952fd..0000000 --- a/Repetier/Repetier.layout +++ /dev/null @@ -1,213 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/Repetier/SDCard.cpp b/Repetier/SDCard.cpp index a9e3687..e88f100 100644 --- a/Repetier/SDCard.cpp +++ b/Repetier/SDCard.cpp @@ -41,25 +41,26 @@ void SDCard::automount() #if SDCARDDETECT > -1 if(READ(SDCARDDETECT) != SDCARDDETECTINVERTED) { - if(sdactive) // Card removed + if(sdactive || sdmode == 100) // Card removed { Com::printFLN(PSTR("SD card removed")); #if UI_DISPLAY_TYPE != NO_DISPLAY uid.executeAction(UI_ACTION_TOP_MENU, true); #endif unmount(); - UI_STATUS(UI_TEXT_SD_REMOVED); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_SD_REMOVED_ID)); } } else { - if(!sdactive) + if(!sdactive && sdmode != 100) { - UI_STATUS(UI_TEXT_SD_INSERTED); - Com::printFLN(PSTR("SD card inserted")); // Not translateable or host will not understand signal - initsd(); + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_SD_INSERTED_ID)); + mount(); + if(sdmode != 100) // send message only if we have success + Com::printFLN(PSTR("SD card inserted")); // Not translatable or host will not understand signal #if UI_DISPLAY_TYPE != NO_DISPLAY - if(sdactive) { + if(sdactive && !uid.isWizardActive()) { // Wizards have priority Printer::setAutomount(true); uid.executeAction(UI_ACTION_SD_PRINT + UI_ACTION_TOPMENU, true); } @@ -77,11 +78,13 @@ void SDCard::initsd() if(READ(SDCARDDETECT) != SDCARDDETECTINVERTED) return; #endif + HAL::delayMilliseconds(50); // wait for stabilization of contacts, bootup ... /*if(dir[0].isOpen()) dir[0].close();*/ if(!fat.begin(SDSS, SPI_FULL_SPEED)) { Com::printFLN(Com::tSDInitFail); + sdmode = 100; // prevent automount loop! return; } sdactive = true; @@ -176,27 +179,31 @@ void SDCard::stopPrint() void SDCard::writeCommand(GCode *code) { - unsigned int sum1=0,sum2=0; // for fletcher-16 checksum + unsigned int sum1 = 0, sum2 = 0; // for fletcher-16 checksum uint8_t buf[100]; - uint8_t p=2; + uint8_t p = 2; file.writeError = false; - int params = 128 | (code->params & ~1); - *(int*)buf = params; + uint16_t params = 128 | (code->params & ~1); + memcopy2(buf,¶ms); + //*(int*)buf = params; if(code->isV2()) // Read G,M as 16 bit value { - *(int*)&buf[p] = code->params2; - p+=2; + memcopy2(&buf[p],&code->params2); + //*(int*)&buf[p] = code->params2; + p += 2; if(code->hasString()) buf[p++] = strlen(code->text); if(code->hasM()) { - *(int*)&buf[p] = code->M; - p+=2; + memcopy2(&buf[p],&code->M); + //*(int*)&buf[p] = code->M; + p += 2; } if(code->hasG()) { - *(int*)&buf[p]= code->G; - p+=2; + memcopy2(&buf[p],&code->G); + //*(int*)&buf[p]= code->G; + p += 2; } } else @@ -212,28 +219,33 @@ void SDCard::writeCommand(GCode *code) } if(code->hasX()) { - *(float*)&buf[p] = code->X; - p+=4; + memcopy4(&buf[p],&code->X); + //*(float*)&buf[p] = code->X; + p += 4; } if(code->hasY()) { - *(float*)&buf[p] = code->Y; - p+=4; + memcopy4(&buf[p],&code->Y); + //*(float*)&buf[p] = code->Y; + p += 4; } if(code->hasZ()) { - *(float*)&buf[p] = code->Z; - p+=4; + memcopy4(&buf[p],&code->Z); + //*(float*)&buf[p] = code->Z; + p += 4; } if(code->hasE()) { - *(float*)&buf[p] = code->E; - p+=4; + memcopy4(&buf[p],&code->E); + //*(float*)&buf[p] = code->E; + p += 4; } if(code->hasF()) { - *(float*)&buf[p] = code->F; - p+=4; + memcopy4(&buf[p],&code->F); + //*(float*)&buf[p] = code->F; + p += 4; } if(code->hasT()) { @@ -241,23 +253,81 @@ void SDCard::writeCommand(GCode *code) } if(code->hasS()) { - *(long int*)&buf[p] = code->S; - p+=4; + memcopy4(&buf[p],&code->S); + //*(int32_t*)&buf[p] = code->S; + p += 4; } if(code->hasP()) { - *(long int*)&buf[p] = code->P; - p+=4; + memcopy4(&buf[p],&code->P); + //*(int32_t*)&buf[p] = code->P; + p += 4; } if(code->hasI()) { - *(float*)&buf[p] = code->I; - p+=4; + memcopy4(&buf[p],&code->I); + //*(float*)&buf[p] = code->I; + p += 4; } if(code->hasJ()) { - *(float*)&buf[p] = code->J; - p+=4; + memcopy4(&buf[p],&code->J); + //*(float*)&buf[p] = code->J; + p += 4; + } + if(code->hasR()) + { + memcopy4(&buf[p],&code->R); + //*(float*)&buf[p] = code->R; + p += 4; + } + if(code->hasD()) + { + memcopy4(&buf[p],&code->D); + //*(float*)&buf[p] = code->D; + p += 4; + } + if(code->hasC()) + { + memcopy4(&buf[p],&code->C); + //*(float*)&buf[p] = code->C; + p += 4; + } + if(code->hasH()) + { + memcopy4(&buf[p],&code->H); + //*(float*)&buf[p] = code->H; + p += 4; + } + if(code->hasA()) + { + memcopy4(&buf[p],&code->A); + //*(float*)&buf[p] = code->A; + p += 4; + } + if(code->hasB()) + { + memcopy4(&buf[p],&code->B); + //*(float*)&buf[p] = code->B; + p += 4; + } + if(code->hasK()) + { + memcopy4(&buf[p],&code->K); + //*(float*)&buf[p] = code->K; + p += 4; + } + if(code->hasL()) + { + memcopy4(&buf[p],&code->L); + //*(float*)&buf[p] = code->L; + p += 4; + } + if(code->hasO()) + { + memcopy4(&buf[p],&code->O); + //*(float*)&buf[p] = code->O; + p += 4; } if(code->hasString()) // read 16 uint8_t into string { @@ -269,7 +339,7 @@ void SDCard::writeCommand(GCode *code) } else { - for(uint8_t i=0; i<16; ++i) buf[p++] = *sp++; + for(uint8_t i = 0; i < 16; ++i) buf[p++] = *sp++; } } uint8_t *ptr = buf; @@ -281,14 +351,19 @@ void SDCard::writeCommand(GCode *code) do { sum1 += *ptr++; - if(sum1>=255) sum1-=255; + if(sum1 >= 255) sum1 -= 255; sum2 += sum1; - if(sum2>=255) sum2-=255; + if(sum2 >= 255) sum2 -= 255; } while (--tlen); } buf[p++] = sum1; buf[p++] = sum2; + // Debug + /*Com::printF(PSTR("Buf: ")); + for(int i=0;iinit(targetFile); + } + if (!targetFile.isOpen()) { + Com::printF(Com::tJSONErrorStart); + Com::printF(Com::tNotSDPrinting); + Com::printFLN(Com::tJSONErrorEnd); + return; + } + + // {"err":0,"size":457574,"height":4.00,"layerHeight":0.25,"filament":[6556.3],"generatedBy":"Slic3r 1.1.7 on 2014-11-09 at 17:11:32"} + Com::printF(Com::tJSONFileInfoStart); + Com::print(info->fileSize); + Com::printF(Com::tJSONFileInfoHeight); + Com::print(info->objectHeight); + Com::printF(Com::tJSONFileInfoLayerHeight); + Com::print(info->layerHeight); + Com::printF(Com::tJSONFileInfoFilament); + Com::print(info->filamentNeeded); + Com::printF(Com::tJSONFileInfoGeneratedBy); + Com::print(info->generatedBy); + Com::print('"'); + if (strlen(filename) == 0) { + Com::printF(Com::tJSONFileInfoName); + file.printName(); + Com::print('"'); + } + Com::print('}'); + Com::println(); +}; + +#endif bool SDCard::selectFile(const char *filename, bool silent) { SdBaseFile parent; const char *oldP = filename; - boolean bFound; if(!sdactive) return false; sdmode = 0; @@ -375,7 +536,10 @@ bool SDCard::selectFile(const char *filename, bool silent) { Com::printF(Com::tFileOpened, oldP); Com::printFLN(Com::tSpaceSizeColon,file.fileSize()); - } + } +#if JSON_OUTPUT + fileInfo.init(file); +#endif sdpos = 0; filesize = file.fileSize(); Com::printFLN(Com::tFileSelected); @@ -414,7 +578,7 @@ void SDCard::startWrite(char *filename) } else { - UI_STATUS(UI_TEXT_UPLOADING); + UI_STATUS_F(Com::translatedF(UI_TEXT_UPLOADING_ID)); savetosd = true; Com::printFLN(Com::tWritingToFile,filename); } @@ -480,5 +644,3 @@ void SDCard::writeToFile() #endif - - diff --git a/Repetier/SdFat.cpp b/Repetier/SdFat.cpp index 54b1d72..8b8cd25 100644 --- a/Repetier/SdFat.cpp +++ b/Repetier/SdFat.cpp @@ -32,11 +32,6 @@ extern int8_t RFstrnicmp(const char* s1, const char* s2, size_t n); //#define GLENN_DEBUG -//------------------------------------------------------------------------------ -//------------------------------------------------------------------------------ -static void pstrPrint(FSTRINGPARAM(str)) { - Com::printF(str); -} //------------------------------------------------------------------------------ static void pstrPrintln(FSTRINGPARAM(str)) { Com::printFLN(str); @@ -652,11 +647,12 @@ void SdBaseFile::ls(uint8_t flags) { ls(flags, 0); } -uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFilename, SdBaseFile *pParentFound) +uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFilename, SdBaseFile *pParentFound, bool isJson) { dir_t *p = NULL; - uint8_t cnt=0; - char *oldpathend = pathend; + //uint8_t cnt=0; + //char *oldpathend = pathend; + bool firstFile = true; parent->rewind(); @@ -665,21 +661,29 @@ uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFil HAL::pingWatchdog(); if (! (DIR_IS_FILE(p) || DIR_IS_SUBDIR(p))) continue; if (strcmp(tempLongFilename, "..") == 0) continue; - if( DIR_IS_SUBDIR(p)) - { - if(level>=SD_MAX_FOLDER_DEPTH) continue; // can't go deeper - if(level= SD_MAX_FOLDER_DEPTH) continue; // can't go deeper + if (level < SD_MAX_FOLDER_DEPTH && findFilename == NULL) { + if (level && !isJson) { + Com::print(fullName); + Com::printF(Com::tSlash); + } +#if JSON_OUTPUT + if (isJson) { + if (!firstFile) Com::print(','); + Com::print('"');Com::print('*'); + SDCard::printEscapeChars(tempLongFilename); + Com::print('"'); + firstFile = false; + } else { + Com::print(tempLongFilename); + Com::printFLN(Com::tSlash); // End with / to mark it as directory entry, so we can see empty directories. + } +#else + Com::print(tempLongFilename); + Com::printFLN(Com::tSlash); // End with / to mark it as directory entry, so we can see empty directories. +#endif } SdBaseFile next; char *tmp; @@ -689,11 +693,11 @@ uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFil strcat(fullName, tempLongFilename); uint16_t index = (parent->curPosition()-31) >> 5; - if(next.open(parent, index, O_READ)) - { - if (next.lsRecursive(&next,level+1, findFilename, pParentFound)) + if(!isJson && next.open(parent, index, O_READ)) + { + if (next.lsRecursive(&next,level+1, findFilename, pParentFound,false)) return true; - } + } parent->seekSet(32 * (index + 1)); if ((tmp = strrchr(fullName, '/'))!= NULL) *tmp = 0; @@ -721,16 +725,27 @@ uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFil } else { - if(level) + if(level && !isJson) { Com::print(fullName); Com::printF(Com::tSlash); + } +#if JSON_OUTPUT + if (isJson) { + if (!firstFile) Com::printF(Com::tComma); + Com::print('"'); + SDCard::printEscapeChars(tempLongFilename); + Com::print('"'); + firstFile = false; + } else +#endif + { + Com::print(tempLongFilename); +#if SD_EXTENDED_DIR + Com::printF(Com::tSpace, (long) p->fileSize); +#endif + Com::println(); } - Com::print(tempLongFilename); -#if SD_EXTENDED_DIR - Com::printF(Com::tSpace,(long)p->fileSize); -#endif - Com::println(); } } } @@ -753,21 +768,31 @@ uint8_t SdBaseFile::lsRecursive(SdBaseFile *parent, uint8_t level, char *findFil * \param[in] indent Amount of space before file name. Used for recursive * list to indicate subdirectory level. */ -void SdBaseFile::ls(uint8_t flags, uint8_t indent) { - SdBaseFile parent; +void SdBaseFile::ls(uint8_t flags, uint8_t indent) { + SdBaseFile parent; + rewind(); + *fullName = 0; + pathend = fullName; + parent = *this; + lsRecursive(&parent, 0, NULL, NULL, false); +} + +#if JSON_OUTPUT +void SdBaseFile::lsJSON() { + SdBaseFile parent; + rewind(); + *fullName = 0; + parent = *this; + lsRecursive(&parent, 0, NULL, NULL, true); +} +#endif - rewind(); - *fullName = 0; - pathend = fullName; - parent = *this; - lsRecursive(&parent, 0, NULL, NULL); -} //------------------------------------------------------------------------------ // saves 32 bytes on stack for ls recursion // return 0 - EOF, 1 - normal file, or 2 - directory int8_t SdBaseFile::lsPrintNext(uint8_t flags, uint8_t indent) { dir_t dir; - uint8_t w = 0; + //uint8_t w = 0; while (1) { if (read(&dir, sizeof(dir)) != sizeof(dir)) return 0; if (dir.name[0] == DIR_NAME_FREE) return 0; @@ -876,8 +901,6 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const char* path, bool pFlag) { { return mkdir(&newParent, dname); } - - fail: return false; } //------------------------------------------------------------------------------ @@ -886,13 +909,13 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t *dname) { if (!parent->isDir()) { DBG_FAIL_MACRO; - goto fail; + return false; } // create a normal file if (!open(parent, dname, O_CREAT | O_EXCL | O_RDWR, true)) { DBG_FAIL_MACRO; - goto fail; + return false; } // make entry for '.' @@ -908,7 +931,7 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t *dname) { for (uint8_t i = 1; i < 11; i++) d.name[i] = ' '; if (write(&d, sizeof(dir_t)) < 0) - goto fail; + return false; sync(); // make entry for '..' @@ -921,18 +944,16 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t *dname) { d.firstClusterHigh = parent->firstCluster_ >> 16; } if (write(&d, sizeof(dir_t)) < 0) - goto fail; + return false; sync(); memset(&d, 0, sizeof(dir_t)); if (write(&d, sizeof(dir_t)) < 0) - goto fail; + return false; sync(); // fileSize_ = 0; type_ = FAT_FILE_TYPE_SUBDIR; flags_ |= F_FILE_DIR_DIRTY; return true; - fail: - return false; } //------------------------------------------------------------------------------ /** Open a file in the current working directory. @@ -1005,10 +1026,10 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t *dname) { SdBaseFile *newParent, boolean bMakeDirs) { SdBaseFile dir1, dir2; SdBaseFile *parent = dirFile; - dir_t *pEntry; + //dir_t *pEntry; SdBaseFile *sub = &dir1; char *p; - boolean bFound; + //boolean bFound; #ifdef GLENN_DEBUG Commands::checkFreeMemory(); @@ -1052,7 +1073,7 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t *dname) { Commands::checkFreeMemory(); Commands::writeLowestFreeRAM(); #endif - bFound = false; + //bFound = false; if (!sub->open(parent, dname, O_READ, false)) { if (!bMakeDirs) @@ -1093,7 +1114,6 @@ bool SdBaseFile::open(SdBaseFile* dirFile, const char* path, uint8_t oflag) return open(&parent, dname, oflag, false); } - fail: return false; } @@ -1113,11 +1133,11 @@ uint8_t SdBaseFile::lfn_checksum(const unsigned char *pFCBName) bool SdBaseFile::open(SdBaseFile* dirFile,const uint8_t *dname, uint8_t oflag, bool bDir) { bool emptyFound = false; uint8_t index = 0; - dir_t tempDir, *p; + dir_t tempDir, *p = NULL; const char *tempPtr; char newName[SHORT_FILENAME_LENGTH+2]; boolean bShortName = false; - int8_t cVFATNeeded = -1, wIndex, cVFATFoundCur; + int8_t cVFATNeeded = -1, cVFATFoundCur; uint32_t wIndexPos = 0; uint8_t cbFilename; char *Filename = (char *)dname; @@ -1570,6 +1590,9 @@ bool SdBaseFile::openParent(SdBaseFile* dir) { bool SdBaseFile::openRoot(SdVolume* vol) { // error if file is already open if (isOpen()) { +#if defined(DEBUG_SD_ERROR) + Com::printErrorFLN(PSTR("Root already open")); +#endif DBG_FAIL_MACRO; goto fail; } @@ -1587,6 +1610,10 @@ bool SdBaseFile::openRoot(SdVolume* vol) { } } else { // volume is not initialized, invalid, or FAT12 without support +#if defined(DEBUG_SD_ERROR) + Com::printErrorF(PSTR("volume is not initialized, invalid, or FAT12 without support, type:")); + Com::print((int)vol->fatType());Com::println(); +#endif DBG_FAIL_MACRO; goto fail; } @@ -1603,6 +1630,9 @@ bool SdBaseFile::openRoot(SdVolume* vol) { return true; fail: +#if defined(DEBUG_SD_ERROR) + Com::printErrorFLN(PSTR("SD open root dir failed")); +#endif return false; } //------------------------------------------------------------------------------ @@ -2055,7 +2085,7 @@ dir_t *SdBaseFile::getLongFilename(dir_t *dir, char *longFilename, int8_t cVFATN bool SdBaseFile::findSpace(dir_t *dir, int8_t cVFATNeeded, int8_t *pcVFATFound, uint32_t *pwIndexPos) { - int16_t n; + //int16_t n; // unused int8_t cVFATFound = 0; // if not a directory file or miss-positioned return an error if (!isDir()) return -1; @@ -2081,7 +2111,7 @@ bool SdBaseFile::findSpace(dir_t *dir, int8_t cVFATNeeded, int8_t *pcVFATFound, { if (DIR_IS_LONG_NAME(dir)) { - vfat_t *VFAT = (vfat_t*)dir; + //vfat_t *VFAT = (vfat_t*)dir; // unused cVFATFound++; } else @@ -3202,7 +3232,7 @@ uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) { #if USE_SD_CRC // form message - uint8_t d[6] = {cmd | 0X40, pa[3], pa[2], pa[1], pa[0]}; + uint8_t d[6] = {static_cast(cmd | static_cast(0X40)), pa[3], pa[2], pa[1], pa[0]}; // add crc d[5] = CRC7(d, 5); @@ -3415,6 +3445,9 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { fail: chipSelectHigh(); +#if defined(DEBUG_SD_ERROR) + Com::printErrorFLN(PSTR("SD card initalization failed")); +#endif return false; } //------------------------------------------------------------------------------ @@ -3469,7 +3502,7 @@ bool Sd2Card::readData(uint8_t* dst, size_t count) { goto fail; } // transfer data - if (status_ = spiRec(dst, count)) { + if ((status_ = spiRec(dst, count))) { error(SD_CARD_ERROR_SPI_DMA); goto fail; } @@ -4224,7 +4257,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { cacheStatus_ = 0; // cacheSync() will write block if true cacheBlockNumber_ = 0XFFFFFFFF; cacheFatOffset_ = 0; -#if USE_SERARATEFAT_CACHE +#if defined(USE_SERARATEFAT_CACHE) && USE_SERARATEFAT_CACHE cacheFatStatus_ = 0; // cacheSync() will write block if true cacheFatBlockNumber_ = 0XFFFFFFFF; #endif // USE_SERARATEFAT_CACHE @@ -4232,11 +4265,17 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { // if part > 0 assume mbr volume with partition table if (part) { if (part > 4) { +#if defined(DEBUG_SD_ERROR) + Com::printErrorFLN(PSTR("volume init: illegal part")); +#endif DBG_FAIL_MACRO; goto fail; } pc = cacheFetch(volumeStartBlock, CACHE_FOR_READ); if (!pc) { +#if defined(DEBUG_SD_ERROR) + Com::printErrorFLN(PSTR("volume init: cache fetch failed")); +#endif DBG_FAIL_MACRO; goto fail; } @@ -4245,6 +4284,9 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { p->totalSectors < 100 || p->firstSector == 0) { // not a valid partition +#if defined(DEBUG_SD_ERROR) + Com::printErrorFLN(PSTR("volume init: invalid partition")); +#endif DBG_FAIL_MACRO; goto fail; } @@ -4252,6 +4294,9 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { } pc = cacheFetch(volumeStartBlock, CACHE_FOR_READ); if (!pc) { +#if defined(DEBUG_SD_ERROR) +Com::printErrorFLN(PSTR("volume init: cache fetch failed")); +#endif DBG_FAIL_MACRO; goto fail; } @@ -4261,6 +4306,13 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { fbs->reservedSectorCount == 0 || fbs->sectorsPerCluster == 0) { // not valid FAT volume +#if defined(DEBUG_SD_ERROR) + Com::printErrorFLN(PSTR("volume init: not a valid FAT volume")); + Com::printFLN(PSTR("BytesPerSector:"),fbs->bytesPerSector); + Com::printFLN(PSTR("fatCount:"),fbs->fatCount); + Com::printFLN(PSTR("reservedSectorCount:"),fbs->reservedSectorCount); + Com::printFLN(PSTR("sectorsPerCluster:"),fbs->sectorsPerCluster); +#endif DBG_FAIL_MACRO; goto fail; } @@ -4303,6 +4355,9 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { if (clusterCount_ < 4085) { fatType_ = 12; if (!FAT12_SUPPORT) { +#if defined(DEBUG_SD_ERROR) + Com::printErrorFLN(PSTR("volume init: No FAT 12 support")); +#endif DBG_FAIL_MACRO; goto fail; } @@ -4315,6 +4370,9 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { return true; fail: +#if defined(DEBUG_SD_ERROR) + Com::printErrorFLN(PSTR("SD volume open failed")); +#endif return false; } // =============== SdFile.cpp ==================== @@ -4434,5 +4492,3 @@ void SdFatUtil::SerialPrintln_P(FSTRINGPARAM(str)) { #endif // SDSUPPORT - - diff --git a/Repetier/SdFat.h b/Repetier/SdFat.h index 00bfdc1..6c6cb60 100644 --- a/Repetier/SdFat.h +++ b/Repetier/SdFat.h @@ -1937,7 +1937,7 @@ class SdBaseFile { uint8_t lfn_checksum(const unsigned char *pFCBName); bool openParentReturnFile(SdBaseFile* dirFile, const char* path, uint8_t *dname, SdBaseFile *newParent, boolean bMakeDirs); - + /** \return True if this is a directory else false. */ bool isDir() const {return type_ >= FAT_FILE_TYPE_MIN_DIR;} /** \return True if this is a normal file else false. */ @@ -2057,7 +2057,7 @@ class SdBaseFile { dir_t* readDirCacheSpecial(); dir_t *getLongFilename(dir_t *dir, char *longFilename, int8_t cVFATNeeded, uint32_t *pwIndexPos); bool findSpace(dir_t *dir, int8_t cVFATNeeded, int8_t *pcVFATFound, uint32_t *pwIndexPos); - uint8_t lsRecursive(SdBaseFile *parent, uint8_t level, char *findFilename, SdBaseFile *pParentFound); + uint8_t lsRecursive(SdBaseFile *parent, uint8_t level, char *findFilename, SdBaseFile *pParentFound, bool isJson); bool setDirSize(); //------------------------------------------------------------------------------ @@ -2208,6 +2208,9 @@ class SdBaseFile { static bool remove(SdBaseFile& dirFile, const char* path) // NOLINT __attribute__((error("use remove(&dirFile, path)"))); #endif // ALLOW_DEPRECATED_FUNCTIONS +#if JSON_OUTPUT + void lsJSON(); +#endif }; //------------------------------------------------------------------------------ /** @@ -2321,5 +2324,3 @@ class SdFat { SdBaseFile vwd_; }; #endif // SdFat_h - - diff --git a/Repetier/cores/CDC.cpp b/Repetier/cores/CDC.cpp deleted file mode 100644 index 6e19e7e..0000000 --- a/Repetier/cores/CDC.cpp +++ /dev/null @@ -1,3 +0,0 @@ -/* Stub for CDC.cpp */ - -#include \ No newline at end of file diff --git a/Repetier/cores/HardwareSerial.cpp b/Repetier/cores/HardwareSerial.cpp deleted file mode 100644 index 33f301e..0000000 --- a/Repetier/cores/HardwareSerial.cpp +++ /dev/null @@ -1,3 +0,0 @@ -/* Stub for HardwareSerial.cpp */ - -#include \ No newline at end of file diff --git a/Repetier/cores/IPAddress.cpp b/Repetier/cores/IPAddress.cpp deleted file mode 100644 index a09cc86..0000000 --- a/Repetier/cores/IPAddress.cpp +++ /dev/null @@ -1,3 +0,0 @@ -/* Stub for IPAddress.cpp */ - -#include \ No newline at end of file diff --git a/Repetier/cores/Print.cpp b/Repetier/cores/Print.cpp deleted file mode 100644 index dedc1af..0000000 --- a/Repetier/cores/Print.cpp +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/Stream.cpp b/Repetier/cores/Stream.cpp deleted file mode 100644 index 5e18362..0000000 --- a/Repetier/cores/Stream.cpp +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/Tone.cpp b/Repetier/cores/Tone.cpp deleted file mode 100644 index e86a51f..0000000 --- a/Repetier/cores/Tone.cpp +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/USBCore.cpp b/Repetier/cores/USBCore.cpp deleted file mode 100644 index 507b97b..0000000 --- a/Repetier/cores/USBCore.cpp +++ /dev/null @@ -1,2 +0,0 @@ -#include -#include \ No newline at end of file diff --git a/Repetier/cores/WInterrupts.c b/Repetier/cores/WInterrupts.c deleted file mode 100644 index 67e386e..0000000 --- a/Repetier/cores/WInterrupts.c +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/WMath.cpp b/Repetier/cores/WMath.cpp deleted file mode 100644 index 22ac58c..0000000 --- a/Repetier/cores/WMath.cpp +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/WString.cpp b/Repetier/cores/WString.cpp deleted file mode 100644 index 835c753..0000000 --- a/Repetier/cores/WString.cpp +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/main.cpp b/Repetier/cores/main.cpp deleted file mode 100644 index 14a9885..0000000 --- a/Repetier/cores/main.cpp +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/new.cpp b/Repetier/cores/new.cpp deleted file mode 100644 index 2ba8b6b..0000000 --- a/Repetier/cores/new.cpp +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/wiring.c b/Repetier/cores/wiring.c deleted file mode 100644 index b986fad..0000000 --- a/Repetier/cores/wiring.c +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/wiring_analog.c b/Repetier/cores/wiring_analog.c deleted file mode 100644 index 0c23337..0000000 --- a/Repetier/cores/wiring_analog.c +++ /dev/null @@ -1 +0,0 @@ -#include \ No newline at end of file diff --git a/Repetier/cores/wiring_digital.c b/Repetier/cores/wiring_digital.c deleted file mode 100644 index 2dd1326..0000000 --- a/Repetier/cores/wiring_digital.c +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/cores/wiring_pulse.c b/Repetier/cores/wiring_pulse.c deleted file mode 100644 index bd3c4e8..0000000 --- a/Repetier/cores/wiring_pulse.c +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/cores/wiring_shift.c b/Repetier/cores/wiring_shift.c deleted file mode 100644 index 8542ec8..0000000 --- a/Repetier/cores/wiring_shift.c +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/fastio.h b/Repetier/fastio.h index 81d97d8..ad602e0 100644 --- a/Repetier/fastio.h +++ b/Repetier/fastio.h @@ -3735,5 +3735,3 @@ pins #endif /* _ARDUINO_H */ - - diff --git a/Repetier/gcode.cpp b/Repetier/gcode.cpp index 5852403..510bf88 100644 --- a/Repetier/gcode.cpp +++ b/Repetier/gcode.cpp @@ -183,11 +183,11 @@ void GCode::checkAndPushCommand() } #ifdef DEBUG_COM_ERRORS if(M == 666) // force an communication error - { + { lastLineNumber++; return; - } else if(M == 668) { - lastLineNumber = 0; // simulate a reset so lines are out of resend buffer + } else if(M == 668) { + lastLineNumber = 0; // simulate a reset so lines are out of resend buffer } #endif // DEBUG_COM_ERRORS } @@ -222,10 +222,10 @@ void GCode::checkAndPushCommand() } lastLineNumber = actLineNumber; } - pushCommand(); + pushCommand(); #ifdef DEBUG_COM_ERRORS - if(M == 667) - return; // omit ok + if(hasM() && M == 667) + return; // omit ok #endif #if ACK_WITH_LINENUMBER Com::printFLN(Com::tOkSpace, actLineNumber); @@ -342,7 +342,7 @@ void GCode::readFromSerial() if(!HAL::serialByteAvailable()) { if((waitingForResend >= 0 || commandsReceivingWritePosition > 0) && time - timeOfLastDataPacket > 200) - { + { // Com::printF(PSTR("WFR:"),waitingForResend);Com::printF(PSTR(" CRWP:"),commandsReceivingWritePosition);commandReceiving[commandsReceivingWritePosition] = 0;Com::printFLN(PSTR(" GOT:"),(char*)commandReceiving); requestResend(); // Something is wrong, a started line was not continued in the last second timeOfLastDataPacket = time; @@ -428,7 +428,7 @@ void GCode::readFromSerial() } } #if SDSUPPORT - if(sd.sdmode == 0 || commandsReceivingWritePosition != 0) // not reading or incoming serial command + if(sd.sdmode == 0 || sd.sdmode >= 100 || commandsReceivingWritePosition != 0) // not reading or incoming serial command return; while( sd.filesize > sd.sdpos && commandsReceivingWritePosition < MAX_CMD_SIZE) // consume data until no data or buffer full { @@ -520,7 +520,7 @@ void GCode::readFromSerial() bool GCode::parseBinary(uint8_t *buffer,bool fromSerial) { internalCommand = !fromSerial; - unsigned int sum1 = 0,sum2 = 0; // for fletcher-16 checksum + unsigned int sum1 = 0, sum2 = 0; // for fletcher-16 checksum // first do fletcher-16 checksum tests see // http://en.wikipedia.org/wiki/Fletcher's_checksum uint8_t *p = buffer; @@ -549,13 +549,13 @@ bool GCode::parseBinary(uint8_t *buffer,bool fromSerial) return false; } p = buffer; - params = *(unsigned int *)p; + params = *(uint16_t *)p; p += 2; uint8_t textlen = 16; if(isV2()) { - params2 = *(unsigned int *)p; - p+=2; + params2 = *(uint16_t *)p; + p += 2; if(hasString()) textlen = *p++; } @@ -563,16 +563,16 @@ bool GCode::parseBinary(uint8_t *buffer,bool fromSerial) if(params & 1) { actLineNumber = N = *(uint16_t *)p; - p+=2; + p += 2; } if(isV2()) // Read G,M as 16 bit value { - if(params & 2) + if(hasM()) { M = *(uint16_t *)p; p += 2; } - if(params & 4) + if(hasG()) { G = *(uint16_t *)p; p += 2; @@ -580,51 +580,51 @@ bool GCode::parseBinary(uint8_t *buffer,bool fromSerial) } else { - if(params & 2) + if(hasM()) { M = *p++; } - if(params & 4) + if(hasG()) { G = *p++; } } //if(code->params & 8) {memcpy(&code->X,p,4);p+=4;} - if(params & 8) + if(hasX()) { X = *(float *)p; p += 4; } - if(params & 16) + if(hasY()) { Y = *(float *)p; p += 4; } - if(params & 32) + if(hasZ()) { Z = *(float *)p; p += 4; } - if(params & 64) + if(hasE()) { E = *(float *)p; p += 4; } - if(params & 256) + if(hasF()) { F = *(float *)p; p += 4; } - if(params & 512) + if(hasT()) { T = *p++; } - if(params & 1024) + if(hasS()) { S = *(int32_t*)p; p += 4; } - if(params & 2048) + if(hasP()) { P = *(int32_t*)p; p += 4; @@ -688,7 +688,7 @@ bool GCode::parseBinary(uint8_t *buffer,bool fromSerial) { text = (char*)p; text[textlen] = 0; // Terminate string overwriting checksum - waitUntilAllCommandsAreParsed=true; // Don't destroy string until executed + waitUntilAllCommandsAreParsed = true; // Don't destroy string until executed } formatErrors = 0; return true; @@ -705,7 +705,8 @@ bool GCode::parseAscii(char *line,bool fromSerial) internalCommand = !fromSerial; char c; while ( (c = *(pos++)) ) - { + { + if(c == '(' || c == '%') break; // alternative comment or program block switch(c) { case 'N': @@ -728,10 +729,10 @@ bool GCode::parseAscii(char *line,bool fromSerial) case 'm': { M = parseLongValue(pos) & 0xffff; - params |=2; + params |= 2; if(M > 255) params |= 4096; // handle non standard text arguments that some M codes have - if (M == 23 || M == 28 || M == 29 || M == 30 || M == 32 || M == 117) + if (M == 20 || M == 23 || M == 28 || M == 29 || M == 30 || M == 32 || M == 36 || M == 117) { // after M command we got a filename or text char digit; @@ -749,7 +750,7 @@ bool GCode::parseAscii(char *line,bool fromSerial) text = pos; while (*pos) { - if((M != 117 && *pos==' ') || *pos=='*') break; + if((M != 117 && M != 20 && *pos==' ') || *pos=='*') break; pos++; // find a space as file name end } *pos = 0; // truncate filename by erasing space with nul, also skips checksum @@ -845,12 +846,68 @@ bool GCode::parseAscii(char *line,bool fromSerial) params2 |= 8; params |= 4096; // Needs V2 for saving break; - } + } + case 'C': + case 'c': + { + D = parseFloatValue(pos); + params2 |= 16; + params |= 4096; // Needs V2 for saving + break; + } + case 'H': + case 'h': + { + D = parseFloatValue(pos); + params2 |= 32; + params |= 4096; // Needs V2 for saving + break; + } + case 'A': + case 'a': + { + D = parseFloatValue(pos); + params2 |= 64; + params |= 4096; // Needs V2 for saving + break; + } + case 'B': + case 'b': + { + D = parseFloatValue(pos); + params2 |= 128; + params |= 4096; // Needs V2 for saving + break; + } + case 'K': + case 'k': + { + D = parseFloatValue(pos); + params2 |= 256; + params |= 4096; // Needs V2 for saving + break; + } + case 'L': + case 'l': + { + D = parseFloatValue(pos); + params2 |= 512; + params |= 4096; // Needs V2 for saving + break; + } + case 'O': + case 'o': + { + D = parseFloatValue(pos); + params2 |= 1024; + params |= 4096; // Needs V2 for saving + break; + } case '*' : //checksum { uint8_t checksum_given = parseLongValue(pos); uint8_t checksum = 0; - while(line != (pos-1)) checksum ^= *line++; + while(line != (pos - 1)) checksum ^= *line++; #if FEATURE_CHECKSUM_FORCED Printer::flag0 |= PRINTER_FLAG0_FORCE_CHECKSUM; #endif @@ -869,12 +926,12 @@ bool GCode::parseAscii(char *line,bool fromSerial) }// end switch }// end while - if(hasFormatError() || (params & 518)==0) // Must contain G, M or T command and parameter need to have variables! + if(hasFormatError() || (params & 518) == 0) // Must contain G, M or T command and parameter need to have variables! { formatErrors++; if(Printer::debugErrors()) Com::printErrorFLN(Com::tFormatError); - if(formatErrors<3) return false; + if(formatErrors < 3) return false; } else formatErrors = 0; return true; @@ -885,7 +942,7 @@ void GCode::printCommand() { if(hasN()) { Com::print('N'); - Com::print((long)N); + Com::print((int32_t)N); Com::print(' '); } if(hasM()) @@ -952,5 +1009,193 @@ void GCode::printCommand() } Com::println(); } - - + +#if JSON_OUTPUT + +// --------------------------------------------------------------- // +// Code that gets gcode information is adapted from RepRapFirmware // +// Originally licenced under GPL // +// Authors: reprappro, dc42, dcnewman, others // +// Source: https://github.com/dcnewman/RepRapFirmware // +// Copy date: 15 Nov 2015 // +// --------------------------------------------------------------- // + +void GCodeFileInfo::init(SdBaseFile &file) { + this->fileSize = file.fileSize(); + this->filamentNeeded = 0.0; + this->objectHeight = 0.0; + this->layerHeight = 0.0; + if (!file.isOpen()) return; + bool genByFound = false, layerHeightFound = false, filamentNeedFound = false; + #if CPU_ARCH==ARCH_AVR + #define GCI_BUF_SIZE 120 + #else + #define GCI_BUF_SIZE 1024 + #endif + // READ 4KB FROM THE BEGINNING + char buf[GCI_BUF_SIZE]; + for (int i = 0; i < 4096; i += GCI_BUF_SIZE-50) { + if(!file.seekSet(i)) break; + file.read(buf, GCI_BUF_SIZE); + if (!genByFound && findGeneratedBy(buf, this->generatedBy)) genByFound = true; + if (!layerHeightFound && findLayerHeight(buf, this->layerHeight)) layerHeightFound = true; + if (!filamentNeedFound && findFilamentNeed(buf, this->filamentNeeded)) filamentNeedFound = true; + if(genByFound && layerHeightFound && filamentNeedFound) goto get_objectHeight; + } + + // READ 4KB FROM END + for (int i = 0; i < 4096; i += GCI_BUF_SIZE-50) { + if(!file.seekEnd(-4096 + i)) break; + file.read(buf, GCI_BUF_SIZE); + if (!genByFound && findGeneratedBy(buf, this->generatedBy)) genByFound = true; + if (!layerHeightFound && findLayerHeight(buf, this->layerHeight)) layerHeightFound = true; + if (!filamentNeedFound && findFilamentNeed(buf, this->filamentNeeded)) filamentNeedFound = true; + if(genByFound && layerHeightFound && filamentNeedFound) goto get_objectHeight; + } + + get_objectHeight: + // MOVE FROM END UP IN 1KB BLOCKS UP TO 30KB + for (int i = GCI_BUF_SIZE; i < 30000; i += GCI_BUF_SIZE-50) { + if(!file.seekEnd(-i)) break; + file.read(buf, GCI_BUF_SIZE); + if (findTotalHeight(buf, this->objectHeight)) break; + } + file.seekSet(0); +} + +bool GCodeFileInfo::findGeneratedBy(char *buf, char *genBy) { + // Slic3r & S3D + const char* generatedByString = PSTR("generated by "); + char* pos = strstr_P(buf, generatedByString); + if (pos) { + pos += strlen_P(generatedByString); + size_t i = 0; + while (i < GENBY_SIZE - 1 && *pos >= ' ') { + char c = *pos++; + if (c == '"' || c == '\\') { + // Need to escape the quote-mark for JSON + if (i > GENBY_SIZE - 3) break; + genBy[i++] = '\\'; + } + genBy[i++] = c; + } + genBy[i] = 0; + return true; + } + + // CURA + const char* slicedAtString = PSTR(";Sliced at: "); + pos = strstr_P(buf, slicedAtString); + if (pos) { + strcpy_P(genBy, PSTR("Cura")); + return true; + } + + // UNKNOWN + strcpy_P(genBy, PSTR("Unknown")); + return false; +} + +bool GCodeFileInfo::findLayerHeight(char *buf, float &layerHeight) { + // SLIC3R + layerHeight = 0; + const char* layerHeightSlic3r = PSTR("; layer_height "); + char *pos = strstr_P(buf, layerHeightSlic3r); + if (pos) { + pos += strlen_P(layerHeightSlic3r); + while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') { + ++pos; + } + layerHeight = strtod(pos, NULL); + return true; + } + + // CURA + const char* layerHeightCura = PSTR("Layer height: "); + pos = strstr_P(buf, layerHeightCura); + if (pos) { + pos += strlen_P(layerHeightCura); + while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') { + ++pos; + } + layerHeight = strtod(pos, NULL); + return true; + } + + return false; +} + +bool GCodeFileInfo::findFilamentNeed(char *buf, float &filament) { + const char* filamentUsedStr = PSTR("filament used"); + const char* pos = strstr_P(buf, filamentUsedStr); + filament = 0; + if (pos != NULL) { + pos += strlen_P(filamentUsedStr); + while (*pos == ' ' || *pos == 't' || *pos == '=' || *pos == ':') { + ++pos; // this allows for " = " from default slic3r comment and ": " from default Cura comment + } + if (isDigit(*pos)) { + char *q; + filament += strtod(pos, &q); + if (*q == 'm' && *(q + 1) != 'm') { + filament *= 1000.0; // Cura outputs filament used in metres not mm + } + } + return true; + } + return false; +} + +bool GCodeFileInfo::findTotalHeight(char *buf, float &height) { + int len = 1024; + bool inComment, inRelativeMode = false; + unsigned int zPos; + for (int i = len - 5; i > 0; i--) { + if (inRelativeMode) { + inRelativeMode = !(buf[i] == 'G' && buf[i + 1] == '9' && buf[i + 2] == '1' && buf[i + 3] <= ' '); + } else if (buf[i] == 'G') { + // Ignore G0/G1 codes if absolute mode was switched back using G90 (typical for Cura files) + if (buf[i + 1] == '9' && buf[i + 2] == '0' && buf[i + 3] <= ' ') { + inRelativeMode = true; + } else if ((buf[i + 1] == '0' || buf[i + 1] == '1') && buf[i + 2] == ' ') { + // Look for last "G0/G1 ... Z#HEIGHT#" command as generated by common slicers + // Looks like we found a controlled move, however it could be in a comment, especially when using slic3r 1.1.1 + inComment = false; + size_t j = i; + while (j != 0) { + --j; + char c = buf[j]; + if (c == '\n' || c == '\r') break; + if (c == ';') { + // It is in a comment, so give up on this one + inComment = true; + break; + } + } + if (inComment) continue; + + // Find 'Z' position and grab that value + zPos = 0; + for (int j = i + 3; j < len - 2; j++) { + char c = buf[j]; + if (c < ' ') { + // Skip all whitespaces... + while (j < len - 2 && c <= ' ') { + c = buf[++j]; + } + // ...to make sure ";End" doesn't follow G0 .. Z#HEIGHT# + if (zPos != 0) { + //debugPrintf("Found at offset %u text: %.100s\n", zPos, &buf[zPos + 1]); + height = strtod(&buf[zPos + 1], NULL); + return true; + } + break; + } else if (c == ';') break; + else if (c == 'Z') zPos = j; + } + } + } + } + return false; +} +#endif // JSON_OUTPUT diff --git a/Repetier/gcode.h b/Repetier/gcode.h index 0281689..b5c6a52 100644 --- a/Repetier/gcode.h +++ b/Repetier/gcode.h @@ -18,23 +18,24 @@ #ifndef _GCODE_H #define _GCODE_H -#define MAX_CMD_SIZE 96 +#define MAX_CMD_SIZE 96 +#define ARRAY_SIZE(_x) (sizeof(_x)/sizeof(_x[0])) class SDCard; class GCode // 52 uint8_ts per command needed { - unsigned int params; - unsigned int params2; + uint16_t params; + uint16_t params2; public: - unsigned int N; // Line number - unsigned int M; - unsigned int G; + uint16_t N; // Line number + uint16_t M; + uint16_t G; float X; float Y; float Z; float E; float F; - long S; - long P; + int32_t S; + int32_t P; float I; float J; float R; @@ -191,13 +192,15 @@ private: inline float parseFloatValue(char *s) { char *endPtr; + while(*s == 32) s++; // skip spaces float f = (strtod(s, &endPtr)); if(s == endPtr) f=0.0; // treat empty string "x " as "x0" return f; } inline long parseLongValue(char *s) { - char *endPtr; + char *endPtr; + while(*s == 32) s++; // skip spaces long l = (strtol(s, &endPtr, 10)); if(s == endPtr) l=0; // treat empty string argument "p " as "p0" return l; @@ -221,8 +224,26 @@ private: static uint8_t formatErrors; ///< Number of sequential format errors }; +#if JSON_OUTPUT +#include "SdFat.h" +// Struct to hold Gcode file information 32 bytes +#define GENBY_SIZE 16 +class GCodeFileInfo { +public: + void init(SdBaseFile &file); + + unsigned long fileSize; + float objectHeight; + float layerHeight; + float filamentNeeded; + char generatedBy[GENBY_SIZE]; + + bool findGeneratedBy(char *buf, char *genBy); + bool findLayerHeight(char *buf, float &layerHeight); + bool findFilamentNeed(char *buf, float &filament); + bool findTotalHeight(char *buf, float &objectHeight); +}; +#endif #endif - - diff --git a/Repetier/libraries/EEPROM.cpp b/Repetier/libraries/EEPROM.cpp deleted file mode 100644 index 1bba553..0000000 --- a/Repetier/libraries/EEPROM.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/Ethernet.cpp b/Repetier/libraries/Ethernet.cpp deleted file mode 100644 index 6d1e821..0000000 --- a/Repetier/libraries/Ethernet.cpp +++ /dev/null @@ -1,8 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include diff --git a/Repetier/libraries/Firmata.cpp b/Repetier/libraries/Firmata.cpp deleted file mode 100644 index c2ebf11..0000000 --- a/Repetier/libraries/Firmata.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/LiquidCrystal.cpp b/Repetier/libraries/LiquidCrystal.cpp deleted file mode 100644 index b5a531d..0000000 --- a/Repetier/libraries/LiquidCrystal.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/OBD.cpp b/Repetier/libraries/OBD.cpp deleted file mode 100644 index 6376863..0000000 --- a/Repetier/libraries/OBD.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/SD.cpp b/Repetier/libraries/SD.cpp deleted file mode 100644 index d922fc8..0000000 --- a/Repetier/libraries/SD.cpp +++ /dev/null @@ -1,5 +0,0 @@ -#include -#include -#include -#include -#include diff --git a/Repetier/libraries/SPI.cpp b/Repetier/libraries/SPI.cpp deleted file mode 100644 index 0ff41ea..0000000 --- a/Repetier/libraries/SPI.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/Servo.cpp b/Repetier/libraries/Servo.cpp deleted file mode 100644 index 51e7241..0000000 --- a/Repetier/libraries/Servo.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/SoftwareSerial.cpp b/Repetier/libraries/SoftwareSerial.cpp deleted file mode 100644 index 251e3ea..0000000 --- a/Repetier/libraries/SoftwareSerial.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/Stepper.cpp b/Repetier/libraries/Stepper.cpp deleted file mode 100644 index 9fd399b..0000000 --- a/Repetier/libraries/Stepper.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/TinyGPS.cpp b/Repetier/libraries/TinyGPS.cpp deleted file mode 100644 index fc0392a..0000000 --- a/Repetier/libraries/TinyGPS.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/U8gui.cpp b/Repetier/libraries/U8gui.cpp deleted file mode 100644 index 611e5db..0000000 --- a/Repetier/libraries/U8gui.cpp +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/libraries/WiFi.cpp b/Repetier/libraries/WiFi.cpp deleted file mode 100644 index edeb083..0000000 --- a/Repetier/libraries/WiFi.cpp +++ /dev/null @@ -1,7 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include diff --git a/Repetier/libraries/Wire.cpp b/Repetier/libraries/Wire.cpp deleted file mode 100644 index 4c29653..0000000 --- a/Repetier/libraries/Wire.cpp +++ /dev/null @@ -1,2 +0,0 @@ -#include -#include diff --git a/Repetier/libraries/twi.c b/Repetier/libraries/twi.c deleted file mode 100644 index 70d56f6..0000000 --- a/Repetier/libraries/twi.c +++ /dev/null @@ -1 +0,0 @@ -#include diff --git a/Repetier/logo.h b/Repetier/logo.h index efabd56..01804c5 100644 --- a/Repetier/logo.h +++ b/Repetier/logo.h @@ -2,7 +2,8 @@ // File generated by LCD Assistant // http://en.radzio.dxp.pl/bitmap_converter/ //------------------------------------------------------------------------------ - + +#ifndef CUSTOM_LOGO #define LOGO_WIDTH 60 #define LOGO_HEIGHT 64 @@ -39,41 +40,7 @@ const unsigned char logo[] PROGMEM = { //AVR-GCC, WinAVR 0x00, 0x07, 0xFF, 0xFF, 0xF8, 0x7E, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFF, 0xFF, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xF8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0D, 0xF8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -/* -0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, -0xFF, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0x0F, -0xFF, 0xFF, 0xF7, 0x83, 0xC1, 0xF0, 0x1E, 0x0F, 0xFF, 0xFF, 0x7C, 0x0F, 0x07, 0xC0, 0x78, 0x0F, -0xFF, 0xFD, 0xE0, 0x00, 0x00, 0x01, 0xE0, 0x3F, 0xFF, 0xDF, 0x80, 0x00, 0x00, 0x07, 0xC0, 0x7F, -0xFE, 0x3F, 0xFF, 0xFF, 0xFF, 0xDF, 0x01, 0xFF, 0xF8, 0x00, 0x00, 0x0B, 0xFF, 0xFC, 0x03, 0xFF, -0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, 0xFF, -0xF0, 0x50, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xFF, 0xF1, 0xFF, 0xFF, 0xFF, 0xD0, 0x00, 0x7F, 0x7F, -0xF9, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x7E, 0x7F, 0xF3, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFC, 0x7F, -0xF9, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF8, 0x3F, 0xF1, 0xEF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF0, 0x3F, -0xF9, 0xE0, 0x00, 0x0F, 0xFF, 0xF0, 0xE0, 0x3F, 0xF1, 0xE0, 0x00, 0x00, 0xFF, 0xF8, 0xE0, 0x3F, -0xF9, 0xE0, 0x00, 0x00, 0x3F, 0xF0, 0xE3, 0x3F, 0xF1, 0xE0, 0x00, 0x00, 0x1F, 0xF8, 0xE3, 0x7F, -0xF9, 0xE0, 0x00, 0x00, 0x0F, 0xF0, 0xE7, 0x3F, 0xF1, 0xE0, 0x00, 0x00, 0x0F, 0xF8, 0xE7, 0x7F, -0xF9, 0xE0, 0x08, 0x00, 0x0F, 0xF0, 0xE7, 0x7F, 0xF1, 0xE0, 0x0F, 0xE0, 0x07, 0xF8, 0xE7, 0x7F, -0xF9, 0xE0, 0x0F, 0xE0, 0x07, 0xF0, 0xE7, 0x7F, 0xF1, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, 0xE6, 0x7F, -0xF9, 0xE0, 0x0F, 0xF0, 0x07, 0xF0, 0xE0, 0x7F, 0xF9, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, 0xE0, 0xFF, -0xF9, 0xE0, 0x0F, 0xE0, 0x07, 0xF0, 0xE0, 0xFF, 0xF9, 0xE0, 0x00, 0x00, 0x07, 0xF8, 0xE1, 0xFF, -0xF9, 0xE0, 0x00, 0x00, 0x0F, 0xF0, 0xE3, 0xFF, 0xF9, 0xE0, 0x00, 0x00, 0x0F, 0xF8, 0xE3, 0xFF, -0xF9, 0xE0, 0x00, 0x00, 0x1F, 0xF8, 0xE7, 0xFF, 0xF9, 0xE0, 0x00, 0x00, 0x3F, 0xF8, 0xE7, 0xFF, -0xF9, 0xE0, 0x00, 0x01, 0xFF, 0xF8, 0xE7, 0xFF, 0xF9, 0xE0, 0x0C, 0x01, 0xFF, 0xF8, 0xE7, 0xFF, -0xF9, 0xE0, 0x0E, 0x00, 0x7F, 0xF8, 0xE7, 0xFF, 0xF9, 0xE0, 0x0F, 0x00, 0x7F, 0xF8, 0xE7, 0xFF, -0xF9, 0xE0, 0x0F, 0x00, 0x3F, 0xF8, 0xE7, 0xFF, 0xF9, 0xE0, 0x0F, 0x80, 0x1F, 0xF8, 0xE7, 0xFF, -0xF9, 0xE0, 0x0F, 0x80, 0x1F, 0xF8, 0xE7, 0xFF, 0xF9, 0xE0, 0x0F, 0xC0, 0x0F, 0xF8, 0xE7, 0xFF, -0xF9, 0xE0, 0x0F, 0xC0, 0x0F, 0xF8, 0xE7, 0xFF, 0xF9, 0xE0, 0x0F, 0xE0, 0x07, 0xF8, 0xEF, 0xFF, -0xF9, 0xF0, 0x0F, 0xE0, 0x07, 0xF8, 0xEF, 0xFF, 0xF9, 0xE0, 0x0F, 0xF0, 0x03, 0xF8, 0xFF, 0xFF, -0xF9, 0xF0, 0x0F, 0xF0, 0x03, 0xF8, 0xFF, 0xFF, 0xF9, 0xFE, 0x0F, 0xF8, 0x03, 0xF8, 0xFF, 0xFF, -0xF9, 0xFF, 0xFF, 0xF8, 0x01, 0xF8, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFF, 0x81, 0xF8, 0xFF, 0xFF, -0xF8, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, -0xF8, 0x00, 0xFF, 0xFF, 0xFF, 0xF8, 0xDF, 0xFF, 0xF8, 0x00, 0x00, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, -0xFF, 0x40, 0x00, 0x00, 0xFF, 0xF0, 0x3F, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0xC0, 0x7F, 0xFF, -0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x80, 0x00, 0xFF, 0xFF, -0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x40, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFA, 0xAF, 0xFF, 0xFF, 0xFF, -0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF -*/ }; - - - +#else +LOGO_BITMAP +#endif diff --git a/Repetier/motion.cpp b/Repetier/motion.cpp index aa3cc6f..82bec1b 100644 --- a/Repetier/motion.cpp +++ b/Repetier/motion.cpp @@ -1,2492 +1,2727 @@ -/* - 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 . - - 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 "Repetier.h" - -// ================ Sanity checks ================ -#ifndef STEP_DOUBLER_FREQUENCY -#error Please add new parameter STEP_DOUBLER_FREQUENCY to your configuration. -#else -#if STEP_DOUBLER_FREQUENCY < 10000 || STEP_DOUBLER_FREQUENCY > 20000 -#if CPU_ARCH==ARCH_AVR -#error STEP_DOUBLER_FREQUENCY should be in range 10000-16000. -#endif -#endif -#endif -#ifdef EXTRUDER_SPEED -#error EXTRUDER_SPEED is not used any more. Values are now taken from extruder definition. -#endif -#ifdef ENDSTOPPULLUPS -#error ENDSTOPPULLUPS is now replaced by individual pullup configuration! -#endif -#ifdef EXT0_PID_PGAIN -#error The PID system has changed. Please use the new float number options! -#endif -// #################################################################################### -// # No configuration below this line - just some errorchecking # -// #################################################################################### -#ifdef SUPPORT_MAX6675 -#if !defined SCK_PIN || !defined MOSI_PIN || !defined MISO_PIN -#error For MAX6675 support, you need to define SCK_PIN, MISO_PIN and MOSI_PIN in pins.h -#endif -#endif -#if X_STEP_PIN<0 || Y_STEP_PIN<0 || Z_STEP_PIN<0 -#error One of the following pins is not assigned: X_STEP_PIN,Y_STEP_PIN,Z_STEP_PIN -#endif -#if EXT0_STEP_PIN<0 && NUM_EXTRUDER>0 -#error EXT0_STEP_PIN not set to a pin number. -#endif -#if EXT0_DIR_PIN<0 && NUM_EXTRUDER>0 -#error EXT0_DIR_PIN not set to a pin number. -#endif -#if PRINTLINE_CACHE_SIZE<4 -#error PRINTLINE_CACHE_SIZE must be at least 5 -#endif - -//Inactivity shutdown variables -millis_t previousMillisCmd = 0; -millis_t maxInactiveTime = MAX_INACTIVE_TIME*1000L; -millis_t stepperInactiveTime = STEPPER_INACTIVE_TIME*1000L; -long baudrate = BAUDRATE; ///< Communication speed rate. -#if USE_ADVANCE -#if ENABLE_QUADRATIC_ADVANCE -int maxadv = 0; -#endif -int maxadv2 = 0; -float maxadvspeed = 0; -#endif -uint8_t 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 -volatile int waitRelax = 0; // Delay filament relax at the end of print, could be a simple timeout - -PrintLine PrintLine::lines[PRINTLINE_CACHE_SIZE]; ///< Cache for print moves. -PrintLine *PrintLine::cur = 0; ///< Current printing line -#if CPU_ARCH == ARCH_ARM -volatile bool PrintLine::nlFlag = false; -#endif -ufast8_t PrintLine::linesWritePos = 0; ///< Position where we write the next cached line move. -volatile ufast8_t PrintLine::linesCount = 0; ///< Number of lines cached 0 = nothing to do. -ufast8_t PrintLine::linesPos = 0; ///< Position for executing line movement. - -/** -Move printer the given number of steps. Puts the move into the queue. Used by e.g. homing commands. -*/ -void PrintLine::moveRelativeDistanceInSteps(int32_t x, int32_t y, int32_t z, int32_t e, float feedrate, bool waitEnd, bool checkEndstop) -{ -#if NUM_EXTRUDER > 0 - if(Printer::debugDryrun() || (MIN_EXTRUDER_TEMP > 30 && Extruder::current->tempControl.currentTemperatureC < MIN_EXTRUDER_TEMP && !Printer::isColdExtrusionAllowed())) - e = 0; // should not be allowed for current temperature -#endif - float savedFeedrate = Printer::feedrate; - Printer::destinationSteps[X_AXIS] = Printer::currentPositionSteps[X_AXIS] + x; - Printer::destinationSteps[Y_AXIS] = Printer::currentPositionSteps[Y_AXIS] + y; - Printer::destinationSteps[Z_AXIS] = Printer::currentPositionSteps[Z_AXIS] + z; - Printer::destinationSteps[E_AXIS] = Printer::currentPositionSteps[E_AXIS] + e; - Printer::feedrate = feedrate; -#if NONLINEAR_SYSTEM - if (!queueDeltaMove(checkEndstop, false, false)) - { - Com::printWarningFLN(PSTR("moveRelativeDistanceInSteps / queueDeltaMove returns error")); - } -#else - queueCartesianMove(checkEndstop, false); -#endif - Printer::feedrate = savedFeedrate; - Printer::updateCurrentPosition(false); - if(waitEnd) - Commands::waitUntilEndOfAllMoves(); - previousMillisCmd = HAL::timeInMilliseconds(); -} - -void PrintLine::moveRelativeDistanceInStepsReal(int32_t x, int32_t y, int32_t z, int32_t e, float feedrate, bool waitEnd) -{ - Printer::lastCmdPos[X_AXIS] += x * Printer::invAxisStepsPerMM[X_AXIS]; - Printer::lastCmdPos[Y_AXIS] += y * Printer::invAxisStepsPerMM[Y_AXIS]; - Printer::lastCmdPos[Z_AXIS] += z * Printer::invAxisStepsPerMM[Z_AXIS]; - if(!Printer::isPositionAllowed( Printer::lastCmdPos[X_AXIS], Printer::lastCmdPos[Y_AXIS], Printer::lastCmdPos[Z_AXIS])) - { - return; // ignore move - } -#if NUM_EXTRUDER > 0 - if(Printer::debugDryrun() || (MIN_EXTRUDER_TEMP > 30 && Extruder::current->tempControl.currentTemperatureC < MIN_EXTRUDER_TEMP && !Printer::isColdExtrusionAllowed())) - e = 0; // should not be allowed for current temperature -#endif - Printer::moveToReal(Printer::lastCmdPos[X_AXIS], Printer::lastCmdPos[Y_AXIS], Printer::lastCmdPos[Z_AXIS], - (Printer::currentPositionSteps[E_AXIS] + e) * Printer::invAxisStepsPerMM[E_AXIS],feedrate); - Printer::updateCurrentPosition(); - if(waitEnd) - Commands::waitUntilEndOfAllMoves(); - previousMillisCmd = HAL::timeInMilliseconds(); -} - -#if !NONLINEAR_SYSTEM -/** - Put a move to the current destination coordinates into the movement cache. - If the cache is full, the method will wait, until a place gets free. During - wait communication and temperature control is enabled. - @param check_endstops Read endstop during move. -*/ -void PrintLine::queueCartesianMove(uint8_t check_endstops, uint8_t pathOptimize) -{ - Printer::unsetAllSteppersDisabled(); - waitForXFreeLines(1); - uint8_t newPath = insertWaitMovesIfNeeded(pathOptimize, 0); - PrintLine *p = getNextWriteLine(); - - float axis_diff[E_AXIS_ARRAY]; // Axis movement in mm - if(check_endstops) p->flags = FLAG_CHECK_ENDSTOPS; - else p->flags = 0; - p->joinFlags = 0; - if(!pathOptimize) p->setEndSpeedFixed(true); - p->dir = 0; - Printer::constrainDestinationCoords(); - //Find direction - for(uint8_t axis = 0; axis < 4; axis++) - { - p->delta[axis] = Printer::destinationSteps[axis] - Printer::currentPositionSteps[axis]; - if(axis == E_AXIS) - { - Printer::extrudeMultiplyError += (static_cast(p->delta[E_AXIS]) * Printer::extrusionFactor); - p->delta[E_AXIS] = static_cast(Printer::extrudeMultiplyError); - Printer::extrudeMultiplyError -= p->delta[E_AXIS]; - Printer::filamentPrinted += p->delta[E_AXIS] * Printer::invAxisStepsPerMM[axis]; - } - if(p->delta[axis] >= 0) - p->setPositiveDirectionForAxis(axis); - else - p->delta[axis] = -p->delta[axis]; - axis_diff[axis] = p->delta[axis] * Printer::invAxisStepsPerMM[axis]; - if(p->delta[axis]) p->setMoveOfAxis(axis); - Printer::currentPositionSteps[axis] = Printer::destinationSteps[axis]; - } - if(p->isNoMove()) - { - if(newPath) // need to delete dummy elements, otherwise commands can get locked. - resetPathPlanner(); - return; // No steps included - } - float xydist2; -#if ENABLE_BACKLASH_COMPENSATION - if((p->isXYZMove()) && ((p->dir & XYZ_DIRPOS)^(Printer::backlashDir & XYZ_DIRPOS)) & (Printer::backlashDir >> 3)) // We need to compensate backlash, add a move - { - waitForXFreeLines(2); - uint8_t wpos2 = linesWritePos + 1; - if(wpos2 >= PRINTLINE_CACHE_SIZE) wpos2 = 0; - PrintLine *p2 = &lines[wpos2]; - memcpy(p2,p,sizeof(PrintLine)); // Move current data to p2 - uint8_t changed = (p->dir & XYZ_DIRPOS)^(Printer::backlashDir & XYZ_DIRPOS); - float back_diff[4]; // Axis movement in mm - back_diff[E_AXIS] = 0; - back_diff[X_AXIS] = (changed & 1 ? (p->isXPositiveMove() ? Printer::backlashX : -Printer::backlashX) : 0); - back_diff[Y_AXIS] = (changed & 2 ? (p->isYPositiveMove() ? Printer::backlashY : -Printer::backlashY) : 0); - back_diff[Z_AXIS] = (changed & 4 ? (p->isZPositiveMove() ? Printer::backlashZ : -Printer::backlashZ) : 0); - p->dir &= XYZ_DIRPOS; // x,y and z are already correct - for(uint8_t i = 0; i < 4; i++) - { - float f = back_diff[i]*Printer::axisStepsPerMM[i]; - p->delta[i] = abs((long)f); - if(p->delta[i]) p->dir |= XSTEP << i; - } - //Define variables that are needed for the Bresenham algorithm. Please note that Z is not currently included in the Bresenham algorithm. - if(p->delta[Y_AXIS] > p->delta[X_AXIS] && p->delta[Y_AXIS] > p->delta[Z_AXIS]) p->primaryAxis = Y_AXIS; - else if (p->delta[X_AXIS] > p->delta[Z_AXIS] ) p->primaryAxis = X_AXIS; - else p->primaryAxis = Z_AXIS; - p->stepsRemaining = p->delta[p->primaryAxis]; - //Feedrate calc based on XYZ travel distance - xydist2 = back_diff[X_AXIS] * back_diff[X_AXIS] + back_diff[Y_AXIS] * back_diff[Y_AXIS]; - if(p->isZMove()) - p->distance = sqrt(xydist2 + back_diff[Z_AXIS] * back_diff[Z_AXIS]); - else - p->distance = sqrt(xydist2); - // 56 seems to be xstep|ystep|e_posdir which just seems odd - Printer::backlashDir = (Printer::backlashDir & 56) | (p2->dir & XYZ_DIRPOS); - p->calculateMove(back_diff,pathOptimize); - p = p2; // use saved instance for the real move - } -#endif - - //Define variables that are needed for the Bresenham algorithm. Please note that Z is not currently included in the Bresenham algorithm. - if(p->delta[Y_AXIS] > p->delta[X_AXIS] && p->delta[Y_AXIS] > p->delta[Z_AXIS] && p->delta[Y_AXIS] > p->delta[E_AXIS]) p->primaryAxis = Y_AXIS; - else if (p->delta[X_AXIS] > p->delta[Z_AXIS] && p->delta[X_AXIS] > p->delta[E_AXIS]) p->primaryAxis = X_AXIS; - else if (p->delta[Z_AXIS] > p->delta[E_AXIS]) p->primaryAxis = Z_AXIS; - else p->primaryAxis = E_AXIS; - p->stepsRemaining = p->delta[p->primaryAxis]; - if(p->isXYZMove()) - { - xydist2 = axis_diff[X_AXIS] * axis_diff[X_AXIS] + axis_diff[Y_AXIS] * axis_diff[Y_AXIS]; - if(p->isZMove()) - p->distance = RMath::max((float)sqrt(xydist2 + axis_diff[Z_AXIS] * axis_diff[Z_AXIS]),fabs(axis_diff[E_AXIS])); - else - p->distance = RMath::max((float)sqrt(xydist2),fabs(axis_diff[E_AXIS])); - } - else - p->distance = fabs(axis_diff[E_AXIS]); - p->calculateMove(axis_diff,pathOptimize); -} -#endif - -void PrintLine::calculateMove(float axis_diff[], uint8_t pathOptimize) -{ -#if NONLINEAR_SYSTEM - long axisInterval[VIRTUAL_AXIS_ARRAY]; // shortest interval possible for that axis -#else - long axisInterval[E_AXIS_ARRAY]; -#endif - float timeForMove = (float)(F_CPU)*distance / (isXOrYMove() ? RMath::max(Printer::minimumSpeed, Printer::feedrate) : Printer::feedrate); // time is in ticks - bool critical = Printer::isZProbingActive(); - if(linesCount < MOVE_CACHE_LOW && timeForMove < LOW_TICKS_PER_MOVE) // Limit speed to keep cache full. - { - //OUT_P_I("L:",lines_count); - timeForMove += (3 * (LOW_TICKS_PER_MOVE - timeForMove)) / (linesCount + 1); // Increase time if queue gets empty. Add more time if queue gets smaller. - //OUT_P_F_LN("Slow ",time_for_move); - critical = true; - } - timeInTicks = timeForMove; - UI_MEDIUM; // do check encoder - // Compute the solwest allowed interval (ticks/step), so maximum feedrate is not violated - long limitInterval = timeForMove / stepsRemaining; // until not violated by other constraints it is your target speed - if(isXMove()) - { - axisInterval[X_AXIS] = fabs(axis_diff[X_AXIS]) * F_CPU / (Printer::maxFeedrate[X_AXIS] * stepsRemaining); // mm*ticks/s/(mm/s*steps) = ticks/step -#if !NONLINEAR_SYSTEM - limitInterval = RMath::max(axisInterval[X_AXIS], limitInterval); -#endif - } - else axisInterval[X_AXIS] = 0; - if(isYMove()) - { - axisInterval[Y_AXIS] = fabs(axis_diff[Y_AXIS]) * F_CPU / (Printer::maxFeedrate[Y_AXIS] * stepsRemaining); -#if !NONLINEAR_SYSTEM - limitInterval = RMath::max(axisInterval[Y_AXIS], limitInterval); -#endif - } - else axisInterval[Y_AXIS] = 0; - if(isZMove()) // normally no move in z direction - { - axisInterval[Z_AXIS] = fabs(axis_diff[Z_AXIS]) * (float)F_CPU / (float)(Printer::maxFeedrate[Z_AXIS] * stepsRemaining); // must prevent overflow! -#if !NONLINEAR_SYSTEM - limitInterval = RMath::max(axisInterval[Z_AXIS], limitInterval); -#endif - } - else axisInterval[Z_AXIS] = 0; - if(isEMove()) - { - axisInterval[E_AXIS] = fabs(axis_diff[E_AXIS]) * F_CPU / (Printer::maxFeedrate[E_AXIS] * stepsRemaining); -#if !NONLINEAR_SYSTEM - limitInterval = RMath::max(axisInterval[E_AXIS], limitInterval); -#endif - } - else axisInterval[E_AXIS] = 0; -#if NONLINEAR_SYSTEM - if(axis_diff[VIRTUAL_AXIS] >= 0) - axisInterval[VIRTUAL_AXIS] = fabs(axis_diff[VIRTUAL_AXIS]) * F_CPU / (Printer::maxFeedrate[Z_AXIS] * stepsRemaining); - else - axisInterval[VIRTUAL_AXIS] = fabs(axis_diff[VIRTUAL_AXIS]) * F_CPU / (Printer::maxFeedrate[E_AXIS] * stepsRemaining); - limitInterval = RMath::max(axisInterval[VIRTUAL_AXIS], limitInterval); -#endif - - fullInterval = limitInterval = limitInterval>LIMIT_INTERVAL ? limitInterval : LIMIT_INTERVAL; // This is our target speed - // new time at full speed = limitInterval*p->stepsRemaining [ticks] - timeForMove = (float)limitInterval * (float)stepsRemaining; // for large z-distance this overflows with long computation - float inv_time_s = (float)F_CPU / timeForMove; - if(isXMove()) - { - axisInterval[X_AXIS] = timeForMove / delta[X_AXIS]; - speedX = axis_diff[X_AXIS] * inv_time_s; - if(isXNegativeMove()) speedX = -speedX; - } - else speedX = 0; - if(isYMove()) - { - axisInterval[Y_AXIS] = timeForMove / delta[Y_AXIS]; - speedY = axis_diff[Y_AXIS] * inv_time_s; - if(isYNegativeMove()) speedY = -speedY; - } - else speedY = 0; - if(isZMove()) - { - axisInterval[Z_AXIS] = timeForMove / delta[Z_AXIS]; - speedZ = axis_diff[Z_AXIS] * inv_time_s; - if(isZNegativeMove()) speedZ = -speedZ; - } - else speedZ = 0; - if(isEMove()) - { - axisInterval[E_AXIS] = timeForMove / delta[E_AXIS]; - speedE = axis_diff[E_AXIS] * inv_time_s; - if(isENegativeMove()) speedE = -speedE; - } -#if NONLINEAR_SYSTEM - axisInterval[VIRTUAL_AXIS] = limitInterval; //timeForMove/stepsRemaining; -#endif - fullSpeed = distance * inv_time_s; - //long interval = axis_interval[primary_axis]; // time for every step in ticks with full speed - //If acceleration is enabled, do some Bresenham calculations depending on which axis will lead it. -#if RAMP_ACCELERATION - // slowest time to accelerate from v0 to limitInterval determines used acceleration - // t = (v_end-v_start)/a - float slowest_axis_plateau_time_repro = 1e15; // repro to reduce division Unit: 1/s - unsigned long *accel = (isEPositiveMove() ? Printer::maxPrintAccelerationStepsPerSquareSecond : Printer::maxTravelAccelerationStepsPerSquareSecond); - - for(uint8_t i = 0; i < 4 ; i++) - { - if(isMoveOfAxis(i)) - // v = a * t => t = v/a = F_CPU/(c*a) => 1/t = c*a/F_CPU - slowest_axis_plateau_time_repro = RMath::min(slowest_axis_plateau_time_repro, (float)axisInterval[i] * (float)accel[i]); // steps/s^2 * step/tick Ticks/s^2 - } - // Errors for delta move are initialized in timer (except extruder) -#if !NONLINEAR_SYSTEM - error[X_AXIS] = error[Y_AXIS] = error[Z_AXIS] = delta[primaryAxis] >> 1; -#endif -#if NONLINEAR_SYSTEM - error[E_AXIS] = stepsRemaining >> 1; -#endif - invFullSpeed = 1.0 / fullSpeed; - accelerationPrim = slowest_axis_plateau_time_repro / axisInterval[primaryAxis]; // a = v/t = F_CPU/(c*t): Steps/s^2 - //Now we can calculate the new primary axis acceleration, so that the slowest axis max acceleration is not violated - fAcceleration = 262144.0 * (float)accelerationPrim / F_CPU; // will overflow without float! - accelerationDistance2 = 2.0 * distance * slowest_axis_plateau_time_repro * fullSpeed/((float)F_CPU); // mm^2/s^2 - startSpeed = endSpeed = minSpeed = safeSpeed(); - // Can accelerate to full speed within the line - if (startSpeed * startSpeed + accelerationDistance2 >= fullSpeed * fullSpeed) - setNominalMove(); - - vMax = F_CPU / fullInterval; // maximum steps per second, we can reach - // if(p->vMax>46000) // gets overflow in N computation - // p->vMax = 46000; - //p->plateauN = (p->vMax*p->vMax/p->accelerationPrim)>>1; -#if USE_ADVANCE - if(!isXYZMove() || !isEMove()) - { -#if ENABLE_QUADRATIC_ADVANCE - advanceRate = 0; // No head move or E move only or sucking filament back - advanceFull = 0; -#endif - advanceL = 0; - } - else - { - float advlin = fabs(speedE) * Extruder::current->advanceL * 0.001 * Printer::axisStepsPerMM[E_AXIS]; - advanceL = (uint16_t)((65536L * advlin)/vMax); //advanceLscaled = (65536*vE*k2)/vMax -#if ENABLE_QUADRATIC_ADVANCE - advanceFull = 65536*Extruder::current->advanceK * speedE * speedE; // Steps*65536 at full speed - long steps = (HAL::U16SquaredToU32(vMax)) / (accelerationPrim << 1); // v^2/(2*a) = steps needed to accelerate from 0-vMax - advanceRate = advanceFull / steps; - if((advanceFull >> 16) > maxadv) - { - maxadv = (advanceFull >> 16); - maxadvspeed = fabs(speedE); - } -#endif - if(advlin > maxadv2) - { - maxadv2 = advlin; - maxadvspeed = fabs(speedE); - } - } -#endif - UI_MEDIUM; // do check encoder - updateTrapezoids(); - // how much steps on primary axis do we need to reach target feedrate - //p->plateauSteps = (long) (((float)p->acceleration *0.5f / slowest_axis_plateau_time_repro + p->vMin) *1.01f/slowest_axis_plateau_time_repro); -#else -#if USE_ADVANCE -#if ENABLE_QUADRATIC_ADVANCE - advanceRate = 0; // No advance for constant speeds - advanceFull = 0; -#endif -#endif -#endif - -#ifdef DEBUG_STEPCOUNT -// Set in delta move calculation -#if !NONLINEAR_SYSTEM - totalStepsRemaining = delta[X_AXIS] + delta[Y_AXIS] + delta[Z_AXIS]; -#endif -#endif -#ifdef DEBUG_QUEUE_MOVE - if(Printer::debugEcho()) - { - logLine(); - Com::printFLN(Com::tDBGLimitInterval, limitInterval); - Com::printFLN(Com::tDBGMoveDistance, distance); - Com::printFLN(Com::tDBGCommandedFeedrate, Printer::feedrate); - Com::printFLN(Com::tDBGConstFullSpeedMoveTime, timeForMove); - } -#endif - // Make result permanent - if (pathOptimize) waitRelax = 70; - pushLine(); - DEBUG_MEMORY; -} - -/** -This is the path planner. - -It goes from the last entry and tries to increase the end speed of previous moves in a fashion that the maximum jerk -is never exceeded. If a segment with reached maximum speed is met, the planner stops. Everything left from this -is already optimal from previous updates. -The first 2 entries in the queue are not checked. The first is the one that is already in print and the following will likely to become active. - -The method is called before lines_count is increased! -*/ -void PrintLine::updateTrapezoids() -{ - ufast8_t first = linesWritePos; - PrintLine *firstLine; - PrintLine *act = &lines[linesWritePos]; - InterruptProtectedBlock noInts; - - // First we find out how far back we could go with optimization. - - ufast8_t maxfirst = linesPos; // first non fixed segment we might change - if(maxfirst != linesWritePos) - nextPlannerIndex(maxfirst); // don't touch the line printing - // Now ignore enough segments to gain enough time for path planning - millis_t timeleft = 0; - // Skip as many stored moves as needed to gain enough time for computation -#if PRINTLINE_CACHE_SIZE < 10 -#define minTime 4500L * PRINTLINE_CACHE_SIZE -#else -#define minTime 45000L -#endif - while(timeleft < minTime && maxfirst != linesWritePos) - { - timeleft += lines[maxfirst].timeInTicks; - nextPlannerIndex(maxfirst); - } - // Search last fixed element - while(first != maxfirst && !lines[first].isEndSpeedFixed()) - previousPlannerIndex(first); - if(first != linesWritePos && lines[first].isEndSpeedFixed()) - nextPlannerIndex(first); - // now first points to last segment before the end speed is fixed - // so start speed is also fixed. - - if(first == linesWritePos) // Nothing to plan, only new element presend - { - act->block(); // Prevent steppe rinterrupt from using this - noInts.unprotect(); - act->setStartSpeedFixed(true); - act->updateStepsParameter(); - act->unblock(); - return; - } - // now we have at least one additional move for optimization - // that is not a wait move - // First is now the new element or the first element with non fixed end speed. - // anyhow, the start speed of first is fixed - firstLine = &lines[first]; - firstLine->block(); // don't let printer touch this or following segments during update - noInts.unprotect(); - ufast8_t previousIndex = linesWritePos; - previousPlannerIndex(previousIndex); - PrintLine *previous = &lines[previousIndex]; // segment before the one we are inserting -#if DRIVE_SYSTEM != DELTA - // filters z-move<->not z-move - if((previous->primaryAxis == Z_AXIS && act->primaryAxis != Z_AXIS) || (previous->primaryAxis != Z_AXIS && act->primaryAxis == Z_AXIS)) - { - previous->setEndSpeedFixed(true); - act->setStartSpeedFixed(true); - act->updateStepsParameter(); - firstLine->unblock(); - return; - } -#endif // DRIVE_SYSTEM - - if(previous->isEOnlyMove() != act->isEOnlyMove()) - { - previous->maxJunctionSpeed = previous->endSpeed; - previous->setEndSpeedFixed(true); - act->setStartSpeedFixed(true); - act->updateStepsParameter(); - firstLine->unblock(); - return; - } else { - computeMaxJunctionSpeed(previous, act); // Set maximum junction speed if we have a real move before - } - // Increase speed if possible neglecting current speed - backwardPlanner(linesWritePos,first); - // Reduce speed to reachable speeds - forwardPlanner(first); - - // Update precomputed data - do - { - lines[first].updateStepsParameter(); - //noInts.protect(); - lines[first].unblock(); // start with first block to release next used segment as early as possible - nextPlannerIndex(first); - lines[first].block(); - //noInts.unprotect(); - } - while(first != linesWritePos); - act->updateStepsParameter(); - act->unblock(); -} - -/* Computes the maximum junction speed of the newly added segment under -optimal conditions. There is no guarantee that the previous move will be able to reach the -speed at all, but if it could exceed it will never exceed this theoretical limit. - -if you define ALTERNATIVE_JERK teh new jerk computations are used. These -use the cosine of the angle and the maximum speed -Jerk = (1-cos(alpha))*min(v1,v2) -This sets jerk to 0 on zero angle change. - - Old New -0��: 0 0 -30��: 51,8 13.4 -45��: 76.53 29.3 -90��: 141 100 -180��: 200 200 - - -von 100 auf 200 - Old New(min) New(max) -0��: 100 0 0 -30��: 123,9 13.4 26.8 -45��: 147.3 29.3 58.6 -90��: 223 100 200 -180��: 300 200 400 - -*/ -inline void PrintLine::computeMaxJunctionSpeed(PrintLine *previous, PrintLine *current) -{ -#if NONLINEAR_SYSTEM - if (previous->moveID == current->moveID) // Avoid computing junction speed for split delta lines - { - if(previous->fullSpeed > current->fullSpeed) - previous->maxJunctionSpeed = current->fullSpeed; - else - previous->maxJunctionSpeed = previous->fullSpeed; - return; - } -#endif -#if USE_ADVANCE - if(Printer::isAdvanceActivated()) - { - // if we start/stop extrusion we need to do so with lowest possible end speed - // or advance would leave a drolling extruder and can not adjust fast enough. - if(previous->isEMove() != current->isEMove()) - { - previous->setEndSpeedFixed(true); - current->setStartSpeedFixed(true); - previous->endSpeed = current->startSpeed = previous->maxJunctionSpeed = RMath::min(previous->endSpeed, current->startSpeed); - previous->invalidateParameter(); - current->invalidateParameter(); - return; - } - } -#endif // USE_ADVANCE - // if we are here we have to identical move types - // either pure extrusion -> pure extrusion or - // move -> move (with or without extrusion) - // First we compute the normalized jerk for speed 1 - float factor = 1.0; - float maxJoinSpeed = RMath::min(current->fullSpeed,previous->fullSpeed); -#if (DRIVE_SYSTEM == DELTA) // No point computing Z Jerk separately for delta moves -#ifdef ALTERNATIVE_JERK - float jerk = maxJoinSpeed * (1.0 - (current->speedX * previous->speedX + current->speedY * previous->speedY + current->speedZ * previous->speedZ) / (current->fullSpeed * previous->fullSpeed)); -#else - float dx = current->speedX - previous->speedX; - float dy = current->speedY - previous->speedY; - float dz = current->speedZ - previous->speedZ; - float jerk = sqrt(dx * dx + dy * dy + dz * dz); -#endif // ALTERNATIVE_JERK -#else // DELTA -#ifdef ALTERNATIVE_JERK - float jerk = maxJoinSpeed * (1.0 - (current->speedX * previous->speedX + current->speedY * previous->speedY + current->speedZ * previous->speedZ) / (current->fullSpeed * previous->fullSpeed)); -#else - float dx = current->speedX - previous->speedX; - float dy = current->speedY - previous->speedY; - float jerk = sqrt(dx * dx + dy * dy); -#endif // ALTERNATIVE_JERK -#endif // DELTA - if(jerk > Printer::maxJerk) - factor = Printer::maxJerk / jerk; // always < 1.0! -#if DRIVE_SYSTEM != DELTA - if((previous->dir | current->dir) & ZSTEP) - { - float dz = fabs(current->speedZ - previous->speedZ); - if(dz > Printer::maxZJerk) - factor = RMath::min(factor, Printer::maxZJerk / dz); - } -#endif - float eJerk = fabs(current->speedE - previous->speedE); - if(eJerk > Extruder::current->maxStartFeedrate) - factor = RMath::min(factor, Extruder::current->maxStartFeedrate / eJerk); - - previous->maxJunctionSpeed = maxJoinSpeed * factor; // set speed limit -#ifdef DEBUG_QUEUE_MOVE - if(Printer::debugEcho()) - { - Com::printF(PSTR("ID:"), (int)previous); - Com::printFLN(PSTR(" MJ:"), previous->maxJunctionSpeed); - } -#endif // DEBUG_QUEUE_MOVE -} - -/** Update parameter used by updateTrapezoids - -Computes the acceleration/decelleration steps and advanced parameter associated. -*/ -void PrintLine::updateStepsParameter() -{ - if(areParameterUpToDate() || isWarmUp()) return; - float startFactor = startSpeed * invFullSpeed; - float endFactor = endSpeed * invFullSpeed; - vStart = vMax * startFactor; //starting speed - vEnd = vMax * endFactor; -#if CPU_ARCH == ARCH_AVR - uint32_t vmax2 = HAL::U16SquaredToU32(vMax); - accelSteps = ((vmax2 - HAL::U16SquaredToU32(vStart)) / (accelerationPrim << 1)) + 1; // Always add 1 for missing precision - decelSteps = ((vmax2 - HAL::U16SquaredToU32(vEnd)) /(accelerationPrim << 1)) + 1; -#else - uint64_t vmax2 = static_cast(vMax) * static_cast(vMax); - accelSteps = ((vmax2 - static_cast(vStart) * static_cast(vStart)) / (accelerationPrim << 1)) + 1; // Always add 1 for missing precision - decelSteps = ((vmax2 - static_cast(vEnd) * static_cast(vEnd)) / (accelerationPrim << 1)) + 1; -#endif - -#if USE_ADVANCE -#if ENABLE_QUADRATIC_ADVANCE - advanceStart = (float)advanceFull * startFactor * startFactor; - advanceEnd = (float)advanceFull * endFactor * endFactor; -#endif -#endif - if(accelSteps + decelSteps >= stepsRemaining) // can't reach limit speed - { - uint16_t red = (accelSteps + decelSteps + 2 - stepsRemaining) >> 1; - accelSteps = accelSteps - RMath::min(accelSteps, red); - decelSteps = decelSteps - RMath::min(decelSteps, red); - } - setParameterUpToDate(); -#ifdef DEBUG_QUEUE_MOVE - if(Printer::debugEcho()) - { - Com::printFLN(Com::tDBGId,(int)this); - Com::printF(Com::tDBGVStartEnd,(long)vStart); - Com::printFLN(Com::tSlash,(long)vEnd); - Com::printF(Com::tDBAccelSteps,(long)accelSteps); - Com::printF(Com::tSlash,(long)decelSteps); - Com::printFLN(Com::tSlash,(long)stepsRemaining); - Com::printF(Com::tDBGStartEndSpeed,startSpeed,1); - Com::printFLN(Com::tSlash,endSpeed,1); - Com::printFLN(Com::tDBGFlags,(uint32_t)flags); - Com::printFLN(Com::tDBGJoinFlags,(uint32_t)joinFlags); - } -#endif -} - -/** -Compute the maximum speed from the last entered move. -The backwards planner traverses the moves from last to first looking at deceleration. The RHS of the accelerate/decelerate ramp. - -start = last line inserted -last = last element until we check -*/ -inline void PrintLine::backwardPlanner(ufast8_t start,ufast8_t last) -{ - PrintLine *act = &lines[start], *previous; - float lastJunctionSpeed = act->endSpeed; // Start always with safe speed - - //PREVIOUS_PLANNER_INDEX(last); // Last element is already fixed in start speed - while(start != last) - { - previousPlannerIndex(start); - previous = &lines[start]; - previous->block(); - // Avoid speed calc once crusing in split delta move -#if NONLINEAR_SYSTEM - if (previous->moveID == act->moveID && lastJunctionSpeed == previous->maxJunctionSpeed) - { - act->startSpeed = RMath::max(act->minSpeed, previous->endSpeed = lastJunctionSpeed); - previous->invalidateParameter(); - act->invalidateParameter(); - } -#endif - - /* if(prev->isEndSpeedFixed()) // Nothing to update from here on, happens when path optimize disabled - { - act->setStartSpeedFixed(true); - return; - }*/ - - // Avoid speed calcs if we know we can accelerate within the line - lastJunctionSpeed = (act->isNominalMove() ? act->fullSpeed : sqrt(lastJunctionSpeed * lastJunctionSpeed + act->accelerationDistance2)); // acceleration is acceleration*distance*2! What can be reached if we try? - // If that speed is more that the maximum junction speed allowed then ... - if(lastJunctionSpeed >= previous->maxJunctionSpeed) // Limit is reached - { - // If the previous line's end speed has not been updated to maximum speed then do it now - if(previous->endSpeed != previous->maxJunctionSpeed) - { - previous->invalidateParameter(); // Needs recomputation - previous->endSpeed = RMath::max(previous->minSpeed, previous->maxJunctionSpeed); // possibly unneeded??? - } - // If actual line start speed has not been updated to maximum speed then do it now - if(act->startSpeed != previous->maxJunctionSpeed) - { - act->startSpeed = RMath::max(act->minSpeed, previous->maxJunctionSpeed); // possibly unneeded??? - act->invalidateParameter(); - } - lastJunctionSpeed = previous->endSpeed; - } - else - { - // Block prev end and act start as calculated speed and recalculate plateau speeds (which could move the speed higher again) - act->startSpeed = RMath::max(act->minSpeed, lastJunctionSpeed); - lastJunctionSpeed = previous->endSpeed = RMath::max(lastJunctionSpeed, previous->minSpeed); - previous->invalidateParameter(); - act->invalidateParameter(); - } - act = previous; - } // while loop -} - -void PrintLine::forwardPlanner(ufast8_t first) -{ - PrintLine *act; - PrintLine *next = &lines[first]; - float vmaxRight; - float leftSpeed = next->startSpeed; - while(first != linesWritePos) // All except last segment, which has fixed end speed - { - act = next; - nextPlannerIndex(first); - next = &lines[first]; - /* if(act->isEndSpeedFixed()) - { - leftSpeed = act->endSpeed; - continue; // Nothing to do here - }*/ - // Avoid speed calc once crusing in split delta move -#if NONLINEAR_SYSTEM - if (act->moveID == next->moveID && act->endSpeed == act->maxJunctionSpeed) - { - act->startSpeed = leftSpeed; - leftSpeed = act->endSpeed; - act->setEndSpeedFixed(true); - next->setStartSpeedFixed(true); - continue; - } -#endif - // Avoid speed calcs if we know we can accelerate within the line. - vmaxRight = (act->isNominalMove() ? act->fullSpeed : sqrt(leftSpeed * leftSpeed + act->accelerationDistance2)); - if(vmaxRight > act->endSpeed) // Could be higher next run? - { - if(leftSpeed < act->minSpeed) - { - leftSpeed = act->minSpeed; - act->endSpeed = sqrt(leftSpeed * leftSpeed + act->accelerationDistance2); - } - act->startSpeed = leftSpeed; - next->startSpeed = leftSpeed = RMath::max(RMath::min(act->endSpeed, act->maxJunctionSpeed), next->minSpeed); - if(act->endSpeed == act->maxJunctionSpeed) // Full speed reached, don't compute again! - { - act->setEndSpeedFixed(true); - next->setStartSpeedFixed(true); - } - act->invalidateParameter(); - } - else // We can accelerate full speed without reaching limit, which is as fast as possible. Fix it! - { - act->fixStartAndEndSpeed(); - act->invalidateParameter(); - if(act->minSpeed > leftSpeed) - { - leftSpeed = act->minSpeed; - vmaxRight = sqrt(leftSpeed * leftSpeed + act->accelerationDistance2); - } - act->startSpeed = leftSpeed; - act->endSpeed = RMath::max(act->minSpeed,vmaxRight); - next->startSpeed = leftSpeed = RMath::max(RMath::min(act->endSpeed, act->maxJunctionSpeed), next->minSpeed); - next->setStartSpeedFixed(true); - } - } // While - next->startSpeed = RMath::max(next->minSpeed, leftSpeed); // This is the new segment, which is updated anyway, no extra flag needed. -} - - -inline float PrintLine::safeSpeed() -{ - float safe(Printer::maxJerk * 0.5); -#if DRIVE_SYSTEM != DELTA - if(isZMove()) - { - float mz = Printer::maxZJerk * 0.5; - if(isXOrYMove()) { - if(fabs(speedZ) > mz) - safe = RMath::min(safe,mz * fullSpeed / fabs(speedZ)); - } else { - safe = mz; - } - } -#endif - if(isEMove()) - { - if(isXYZMove()) - safe = RMath::min(safe, 0.5 * Extruder::current->maxStartFeedrate * fullSpeed / fabs(speedE)); - else - safe = 0.5 * Extruder::current->maxStartFeedrate; // This is a retraction move - } - if(DRIVE_SYSTEM == DELTA || primaryAxis == X_AXIS || primaryAxis == Y_AXIS) // enforce minimum speed for numerical stability of explicit speed integration - safe = RMath::max(Printer::minimumSpeed, safe); - else if(primaryAxis == Z_AXIS) - { - safe = RMath::max(Printer::minimumZSpeed, safe); - } - return RMath::min(safe, fullSpeed); -} - - -/** Check if move is new. If it is insert some dummy moves to allow the path optimizer to work since it does -not act on the first two moves in the queue. The stepper timer will spot these moves and leave some time for -processing. -*/ -uint8_t PrintLine::insertWaitMovesIfNeeded(uint8_t pathOptimize, uint8_t waitExtraLines) -{ - if(linesCount == 0 && waitRelax == 0 && pathOptimize) // First line after some time - warmup needed - { -#if NONLINEAR_SYSTEM - uint8_t w = 3; -#else - uint8_t w = 4; -#endif - while(w--) - { - PrintLine *p = getNextWriteLine(); - p->flags = FLAG_WARMUP; - p->joinFlags = FLAG_JOIN_STEPPARAMS_COMPUTED | FLAG_JOIN_END_FIXED | FLAG_JOIN_START_FIXED; - p->dir = 0; - p->setWaitForXLinesFilled(w + waitExtraLines); -#if NONLINEAR_SYSTEM - p->setWaitTicks(50000); -#else - p->setWaitTicks(25000); -#endif // NONLINEAR_SYSTEM - pushLine(); - } - return 1; - } - return 0; -} - -void PrintLine::logLine() -{ -#ifdef DEBUG_QUEUE_MOVE - Com::printFLN(Com::tDBGId,(int)this); - Com::printArrayFLN(Com::tDBGDelta,delta); - Com::printFLN(Com::tDBGDir,(uint32_t)dir); - Com::printFLN(Com::tDBGFlags,(uint32_t)flags); - Com::printFLN(Com::tDBGFullSpeed,fullSpeed); - Com::printFLN(Com::tDBGVMax,(int32_t)vMax); - Com::printFLN(Com::tDBGAcceleration,accelerationDistance2); - Com::printFLN(Com::tDBGAccelerationPrim,(int32_t)accelerationPrim); - Com::printFLN(Com::tDBGRemainingSteps,stepsRemaining); -#if USE_ADVANCE -#if ENABLE_QUADRATIC_ADVANCE - Com::printFLN(Com::tDBGAdvanceFull,advanceFull >> 16); - Com::printFLN(Com::tDBGAdvanceRate,advanceRate); -#endif -#endif -#endif // DEBUG_QUEUE_MOVE -} - -void PrintLine::waitForXFreeLines(uint8_t b, bool allowMoves) -{ - while(getLinesCount() + b > PRINTLINE_CACHE_SIZE) // wait for a free entry in movement cache - { - GCode::readFromSerial(); - Commands::checkForPeriodicalActions(allowMoves); - } -} - - -#if DRIVE_SYSTEM == DELTA -// pick one for verbose the other silent -#define RETURN_0(s) { Com::printErrorFLN(PSTR(s)); return 0; } -/*#define RETURN_0(s) { Com::print(s " "); SHOWS(temp); SHOWS(opt);\ - SHOWS(cartesianPosSteps[Z_AXIS]);\ - SHOWS(towerAMinSteps); ;\ - SHOWS(deltaPosSteps[A_TOWER]); \ - SHOWS(Printer::deltaAPosYSteps);\ - SHOWS(cartesianPosSteps[Y_AXIS]); \ - SHOW(Printer::deltaDiagonalStepsSquaredA.l); return 0; } - */ -/** - Calculate the delta tower position from a cartesian position - @param cartesianPosSteps Array containing cartesian coordinates. - @param deltaPosSteps Result array with tower coordinates. - @returns 1 if cartesian coordinates have a valid delta tower position 0 if not. -*/ -uint8_t transformCartesianStepsToDeltaSteps(int32_t cartesianPosSteps[], int32_t deltaPosSteps[]) -{ - int32_t zSteps = cartesianPosSteps[Z_AXIS]; -#if DISTORTION_CORRECTION - static int cnt = 0; - static int32_t lastZSteps = 9999999; - static int32_t lastZCorrection = 0; - cnt++; - if(cnt >= DISTORTION_UPDATE_FREQUENCY || lastZSteps != zSteps) - { - cnt = 0; - lastZSteps = zSteps; - lastZCorrection = Printer::distortion.correct(cartesianPosSteps[X_AXIS], cartesianPosSteps[Y_AXIS], cartesianPosSteps[Z_AXIS]); - } - zSteps += lastZCorrection; -#endif - //SHOWA("motion.c transformCart... cartesian ",cartesianPosSteps, 3); - if(Printer::isLargeMachine()) - { -#ifdef SUPPORT_64_BIT_MATH - // 64 bit is better for precision, so we use that if available. - // A TOWER height - uint64_t temp = RMath::absLong(Printer::deltaAPosYSteps - cartesianPosSteps[Y_AXIS]); - uint64_t opt = Printer::deltaDiagonalStepsSquaredA.L; - - temp *= temp; - if (opt < temp) - RETURN_0("Apos y square "); - opt -= temp; - - temp = RMath::absLong(Printer::deltaAPosXSteps - cartesianPosSteps[X_AXIS]); - temp *= temp; - if (opt < temp) - RETURN_0("Apos x square "); - - deltaPosSteps[A_TOWER] = HAL::integer64Sqrt(opt - temp) + zSteps; - if (deltaPosSteps[A_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) - RETURN_0("A hit floor"); - - // B TOWER height - temp = RMath::absLong(Printer::deltaBPosYSteps - cartesianPosSteps[Y_AXIS]); - opt = Printer::deltaDiagonalStepsSquaredB.L; - temp *= temp; - if (opt < temp) - RETURN_0("Bpos y square "); - opt -= temp; - - temp = RMath::absLong(Printer::deltaBPosXSteps - cartesianPosSteps[X_AXIS]); - temp *= temp; - if (opt < temp) - RETURN_0("Bpos x square "); - - deltaPosSteps[B_TOWER] = HAL::integer64Sqrt(opt - temp) + zSteps ; - if (deltaPosSteps[B_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) - RETURN_0("B hit floor"); - - // C TOWER height - temp = RMath::absLong(Printer::deltaCPosYSteps - cartesianPosSteps[Y_AXIS]); - opt = Printer::deltaDiagonalStepsSquaredC.L ; - - temp = temp * temp; - if ( opt < temp ) - RETURN_0("Cpos y square "); - opt -= temp; - - temp = RMath::absLong(Printer::deltaCPosXSteps - cartesianPosSteps[X_AXIS]); - temp = temp * temp; - if ( opt < temp ) - RETURN_0("Cpos x square "); - - deltaPosSteps[C_TOWER] = HAL::integer64Sqrt(opt - temp) + zSteps; - if (deltaPosSteps[C_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) - RETURN_0("C hit floor"); -#else - float temp = Printer::deltaAPosYSteps - cartesianPosSteps[Y_AXIS]; - float opt = Printer::deltaDiagonalStepsSquaredA.f - temp * temp; - float temp2 = Printer::deltaAPosXSteps - cartesianPosSteps[X_AXIS]; - if ((temp = opt - temp2 * temp2) >= 0) - deltaPosSteps[A_TOWER] = floor(0.5 + sqrt(temp) - + zSteps); - else - return 0; - if (deltaPosSteps[A_TOWER]< Printer::deltaFloorSafetyMarginSteps) return 0; - - temp = Printer::deltaBPosYSteps - cartesianPosSteps[Y_AXIS]; - opt = Printer::deltaDiagonalStepsSquaredB.f - temp * temp; - temp2 = Printer::deltaBPosXSteps - cartesianPosSteps[X_AXIS]; - if ((temp = opt - temp2 * temp2) >= 0) - deltaPosSteps[B_TOWER] = floor(0.5 + sqrt(temp) - + zSteps); - else - return 0; - if (deltaPosSteps[B_TOWER]< Printer::deltaFloorSafetyMarginSteps) return 0; - - temp = Printer::deltaCPosYSteps - cartesianPosSteps[Y_AXIS]; - opt = Printer::deltaDiagonalStepsSquaredC.f - temp * temp; - temp2 = Printer::deltaCPosXSteps - cartesianPosSteps[X_AXIS]; - if ((temp = opt - temp2*temp2) >= 0) - deltaPosSteps[C_TOWER] = floor(0.5 + sqrt(temp) - + zSteps); - else - return 0; - if (deltaPosSteps[C_TOWER]< Printer::deltaFloorSafetyMarginSteps) return 0; - - return 1; -#endif - } - else - { - // As we are right on the edge of many printers arm lengths, this is rewrittent to use unsigned long - // This allows 52% longer arms to be used without performance penalty - // the code is a bit longer, because we cannot use negative to test for invalid conditions - // Also, previous code did not check for overflow of squared result - // Overflow is also detected as a fault condition - - const uint32_t LIMIT = 65534; // Largest squarable int without overflow; - - // A TOWER height - uint32_t temp = RMath::absLong(Printer::deltaAPosYSteps - cartesianPosSteps[Y_AXIS]); - uint32_t opt = Printer::deltaDiagonalStepsSquaredA.l; - - if (temp > LIMIT) - RETURN_0("Apos y steps "); - temp *= temp; - if (opt < temp) - RETURN_0("Apos y square "); - opt -= temp; - - temp = RMath::absLong(Printer::deltaAPosXSteps - cartesianPosSteps[X_AXIS]); - if (temp > LIMIT) - RETURN_0("Apos x steps "); - temp *= temp; - if (opt < temp) - RETURN_0("Apos x square "); - - deltaPosSteps[A_TOWER] = SQRT(opt-temp) + zSteps; - if (deltaPosSteps[A_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) - RETURN_0("A hit floor"); - - // B TOWER height - temp = RMath::absLong(Printer::deltaBPosYSteps - cartesianPosSteps[Y_AXIS]); - opt = Printer::deltaDiagonalStepsSquaredB.l; - - if (temp > LIMIT) - RETURN_0("Bpos y steps "); - temp *= temp; - if (opt < temp) - RETURN_0("Bpos y square "); - opt -= temp; - - temp = RMath::absLong(Printer::deltaBPosXSteps - cartesianPosSteps[X_AXIS]); - if (temp > LIMIT ) - RETURN_0("Bpos x steps "); - temp *= temp; - if (opt < temp) - RETURN_0("Bpos x square "); - - deltaPosSteps[B_TOWER] = SQRT(opt-temp) + zSteps ; - if (deltaPosSteps[B_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) - RETURN_0("B hit floor"); - - // C TOWER height - temp = RMath::absLong(Printer::deltaCPosYSteps - cartesianPosSteps[Y_AXIS]); - opt = Printer::deltaDiagonalStepsSquaredC.l ; - - if (temp > LIMIT) - RETURN_0("Cpos y steps "); - temp = temp * temp; - if ( opt < temp ) - RETURN_0("Cpos y square "); - opt -= temp; - - temp = RMath::absLong(Printer::deltaCPosXSteps - cartesianPosSteps[X_AXIS]); - if (temp > LIMIT) - RETURN_0("Cpos x steps "); - temp = temp * temp; - if ( opt < temp ) - RETURN_0("Cpos x square "); - - deltaPosSteps[C_TOWER] = SQRT(opt - temp) + zSteps; - if (deltaPosSteps[C_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) - RETURN_0("C hit floor"); - /* - long temp = Printer::deltaAPosYSteps - cartesianPosSteps[Y_AXIS]; - long opt = Printer::deltaDiagonalStepsSquaredA.l - temp * temp; - long temp2 = Printer::deltaAPosXSteps - cartesianPosSteps[X_AXIS]; - if ((temp = opt - temp2 * temp2) >= 0) - #ifdef FAST_INTEGER_SQRT - deltaPosSteps[A_TOWER] = HAL::integerSqrt(temp) + cartesianPosSteps[Z_AXIS]; - #else - deltaPosSteps[A_TOWER] = sqrt(temp) + cartesianPosSteps[Z_AXIS]; - #endif - else - return 0; - - temp = Printer::deltaBPosYSteps - cartesianPosSteps[Y_AXIS]; - opt = Printer::deltaDiagonalStepsSquaredB.l - temp * temp; - temp2 = Printer::deltaBPosXSteps - cartesianPosSteps[X_AXIS]; - if ((temp = opt - temp2*temp2) >= 0) - #ifdef FAST_INTEGER_SQRT - deltaPosSteps[B_TOWER] = HAL::integerSqrt(temp) + cartesianPosSteps[Z_AXIS]; - #else - deltaPosSteps[B_TOWER] = sqrt(temp) + cartesianPosSteps[Z_AXIS]; - #endif - else - return 0; - - temp = Printer::deltaCPosYSteps - cartesianPosSteps[Y_AXIS]; - opt = Printer::deltaDiagonalStepsSquaredC.l - temp * temp; - temp2 = Printer::deltaCPosXSteps - cartesianPosSteps[X_AXIS]; - if ((temp = opt - temp2*temp2) >= 0) - #ifdef FAST_INTEGER_SQRT - deltaPosSteps[C_TOWER] = HAL::integerSqrt(temp) + cartesianPosSteps[Z_AXIS]; - #else - deltaPosSteps[C_TOWER] = sqrt(temp) + cartesianPosSteps[Z_AXIS]; - #endif - else - return 0;*/ - } - return 1; -} -#endif - -#if DRIVE_SYSTEM==TUGA - -/** - Calculate the delta tower position from a cartesian position - @param cartesianPosSteps Array containing cartesian coordinates. - @param deltaPosSteps Result array with tower coordinates. - @returns 1 if cartesian coordinates have a valid delta tower position 0 if not. - - X Y - * * - \ / - \ / - \ / - \/ - / - / - / - / - * Extruder - - -*/ -uint8_t transformCartesianStepsToDeltaSteps(int32_t cartesianPosSteps[], int32_t tugaPosSteps[]) -{ - tugaPosSteps[0] = cartesianPosSteps[0]; - tugaPosSteps[2] = cartesianPosSteps[2]; - int32_t y2 = Printer::deltaBPosXSteps-cartesianPosSteps[1]; - if(Printer::isLargeMachine()) - { - float y2f = (float)y2 * (float)y2; - float temp = Printer::deltaDiagonalStepsSquaredF - y2f; - if(temp < 0) return 0; - tugaPosSteps[1] = tugaPosSteps[0] + sqrt(temp); - } - else - { - y2 = y2*y2; - int32_t temp = Printer::deltaDiagonalStepsSquared - y2; - if(temp < 0) return 0; - tugaPosSteps[1] = tugaPosSteps[0] + HAL::integerSqrt(temp); - } - return 1; -} -#endif - - -#if NONLINEAR_SYSTEM - -void DeltaSegment::checkEndstops(PrintLine *cur,bool checkall) -{ - if(Printer::isZProbingActive()) - { -#if FEATURE_Z_PROBE - if(isZNegativeMove() && Endstops::zProbe()) - { - cur->setXMoveFinished(); - cur->setYMoveFinished(); - cur->setZMoveFinished(); - dir = 0; - Printer::stepsRemainingAtZHit = cur->stepsRemaining; - cur->stepsRemaining = 0; - return; - } -#endif -#if DRIVE_SYSTEM == DELTA - if(isZPositiveMove() && isXPositiveMove() && isYPositiveMove() && Endstops::anyXYZMax()) -#else - if(isZPositiveMove() && Endstops::zMax()) -#endif - { - cur->setXMoveFinished(); - cur->setYMoveFinished(); - cur->setZMoveFinished(); - dir = 0; - Printer::stepsRemainingAtZHit = cur->stepsRemaining; - return; - } - } - if(checkall) - { - if(isXPositiveMove() && Endstops::xMax()) - { -#if DRIVE_SYSTEM == DELTA - if(Printer::stepsRemainingAtXHit < 0) - Printer::stepsRemainingAtXHit = cur->stepsRemaining; -#endif - setXMoveFinished(); - cur->setXMoveFinished(); - } - if(isYPositiveMove() && Endstops::yMax()) - { -#if DRIVE_SYSTEM == DELTA - if(Printer::stepsRemainingAtYHit < 0) - Printer::stepsRemainingAtYHit = cur->stepsRemaining; -#endif - setYMoveFinished(); - cur->setYMoveFinished(); - } -#if DRIVE_SYSTEM != DELTA - if(isXNegativeMove() && Endstops::xMin()) - { - setXMoveFinished(); - cur->setXMoveFinished(); - } - if(isYNegativeMove() && Endstops::yMin()) - { - setYMoveFinished(); - cur->setYMoveFinished(); - } -#endif - if(isZPositiveMove() && Endstops::zMax()) - { -#if MAX_HARDWARE_ENDSTOP_Z - if(Printer::stepsRemainingAtZHit) - Printer::stepsRemainingAtZHit = cur->stepsRemaining; -#endif - setZMoveFinished(); - cur->setZMoveFinished(); - } - } - if(isZNegativeMove() && Endstops::zMin()) - { - setZMoveFinished(); - cur->setZMoveFinished(); - } - -} - -void PrintLine::calculateDirectionAndDelta(int32_t difference[], ufast8_t *dir, int32_t delta[]) -{ - *dir = 0; - //Find direction - for(uint8_t i = 0; i < 4; i++) - { - if(difference[i] >= 0) - { - delta[i] = difference[i]; - *dir |= X_DIRPOS << i; - } - else - { - delta[i] = -difference[i]; - } - if(delta[i]) *dir |= XSTEP << i; - } -} -/** - Calculate and cache the delta robot positions of the cartesian move in a line. - @return The largest delta axis move in a single segment - @param p The line to examine. -*/ -inline uint16_t PrintLine::calculateDeltaSubSegments(uint8_t softEndstop) -{ - uint8_t i; - int32_t delta,diff; - int32_t destinationSteps[Z_AXIS_ARRAY], destinationDeltaSteps[TOWER_ARRAY]; - // Save current position -#if (CPU_ARCH == ARCH_AVR) && !EXACT_DELTA_MOVES - for(uint8_t i = 0; i < Z_AXIS_ARRAY; i++) - destinationSteps[i] = Printer::currentPositionSteps[i]; -#else - float dx[Z_AXIS_ARRAY]; - for(int i = 0; i < Z_AXIS_ARRAY; i++) - dx[i] = static_cast(Printer::destinationSteps[i] - Printer::currentPositionSteps[i]) / static_cast(numDeltaSegments); -#endif -// out.println_byte_P(PSTR("Calculate delta segments:"), p->numDeltaSegments); -#ifdef DEBUG_STEPCOUNT - totalStepsRemaining = 0; -#endif - - uint16_t maxAxisMove = 0; - for (int s = numDeltaSegments; s > 0; s--) - { - DeltaSegment *d = &segments[s - 1]; - -#if (CPU_ARCH == ARCH_AVR) && !EXACT_DELTA_MOVES - for(i = 0; i < Z_AXIS_ARRAY; i++) - { - // End of segment in cartesian steps - - // This method generates small waves which get larger with increasing number of delta segments. smaller?? - diff = Printer::destinationSteps[i] - destinationSteps[i]; - if(s == 1) - destinationSteps[i] += diff; - else if(s == 2) - destinationSteps[i] += (diff >> 1); - else if(s == 4) - destinationSteps[i] += (diff >> 2); - else if(diff<0) - destinationSteps[i] -= HAL::Div4U2U(-diff, s); - else - destinationSteps[i] += HAL::Div4U2U(diff, s); - } -#else - float segment = static_cast(numDeltaSegments - s + 1); - for(i = 0; i < Z_AXIS_ARRAY; i++) // End of segment in cartesian steps - // Perfect approximation, but slower, so we limit it to faster processors like arm - destinationSteps[i] = static_cast(floor(0.5 + dx[i] * segment)) + Printer::currentPositionSteps[i]; -#endif - // Verify that delta calc has a solution - if (transformCartesianStepsToDeltaSteps(destinationSteps, destinationDeltaSteps)) - { - d->dir = 0; - if (softEndstop) - { - destinationDeltaSteps[A_TOWER] = RMath::min(destinationDeltaSteps[A_TOWER], Printer::maxDeltaPositionSteps); - destinationDeltaSteps[B_TOWER] = RMath::min(destinationDeltaSteps[B_TOWER], Printer::maxDeltaPositionSteps); - destinationDeltaSteps[C_TOWER] = RMath::min(destinationDeltaSteps[C_TOWER], Printer::maxDeltaPositionSteps); - } - - for(i = 0; i < TOWER_ARRAY; i++) - { - delta = destinationDeltaSteps[i] - Printer::currentDeltaPositionSteps[i]; - if (delta > 0) - { - d->setPositiveMoveOfAxis(i); -#ifdef DEBUG_DELTA_OVERFLOW - if (delta > 65535) - Com::printFLN(Com::tDBGDeltaOverflow, delta); -#endif - d->deltaSteps[i] = static_cast(delta); - } - else - { - d->setMoveOfAxis(i); -#ifdef DEBUG_DELTA_OVERFLOW - if (-delta > 65535) - Com::printFLN(Com::tDBGDeltaOverflow, delta); -#endif - d->deltaSteps[i] = static_cast(-delta); - } -#ifdef DEBUG_STEPCOUNT - totalStepsRemaining += d->deltaSteps[i]; -#endif - maxAxisMove = RMath::max(maxAxisMove,d->deltaSteps[i]); - Printer::currentDeltaPositionSteps[i] = destinationDeltaSteps[i]; - } - } - else - { - // Illegal position - ignore move - Com::printWarningF(Com::tInvalidDeltaCoordinate); - Com::printF(PSTR(" x:"), destinationSteps[X_AXIS]); - Com::printF(PSTR(" y:"), destinationSteps[Y_AXIS]); - Com::printFLN(PSTR(" z:"), destinationSteps[Z_AXIS]); - d->dir = 0; - d->deltaSteps[A_TOWER] = d->deltaSteps[B_TOWER] = d->deltaSteps[C_TOWER] = 0; - return 65535; // flag error - } - } -#ifdef DEBUG_STEPCOUNT -// out.println_long_P(PSTR("initial StepsRemaining:"), p->totalStepsRemaining); -#endif - return maxAxisMove; -} - -uint8_t PrintLine::calculateDistance(float axisDiff[], uint8_t dir, float *distance) -{ - // Calculate distance depending on direction - if(dir & XYZ_STEP) - { - if(dir & XSTEP) - *distance = axisDiff[X_AXIS] * axisDiff[X_AXIS]; - else - *distance = 0; - if(dir & YSTEP) - *distance += axisDiff[Y_AXIS] * axisDiff[Y_AXIS]; - if(dir & ZSTEP) - *distance += axisDiff[Z_AXIS] * axisDiff[Z_AXIS]; - *distance = RMath::max((float)sqrt(*distance),fabs(axisDiff[E_AXIS])); - return 1; - } - else - { - if(dir & ESTEP) - { - *distance = fabs(axisDiff[E_AXIS]); - return 1; - } - *distance = 0; - return 0; - } -} - -#if SOFTWARE_LEVELING -void PrintLine::calculatePlane(int32_t factors[], int32_t p1[], int32_t p2[], int32_t p3[]) -{ - factors[0] = p1[1] * (p2[2] - p3[2]) + p2[1] * (p3[2] - p1[2]) + p3[1] * (p1[2] - p2[2]); - factors[1] = p1[2] * (p2[0] - p3[0]) + p2[2] * (p3[0] - p1[0]) + p3[2] * (p1[0] - p2[0]); - factors[2] = p1[0] * (p2[1] - p3[1]) + p2[0] * (p3[1] - p1[1]) + p3[0] * (p1[1] - p2[1]); - factors[3] = p1[0] * ((p2[1] * p3[2]) - (p3[1] * p2[2])) + p2[0] * ((p3[1] * p1[2]) - (p1[1] * p3[2])) + p3[0] * ((p1[1] * p2[2]) - (p2[1] * p1[2])); -} - -float PrintLine::calcZOffset(int32_t factors[], int32_t pointX, int32_t pointY) -{ - return (factors[3] - factors[X_AXIS] * pointX - factors[Y_AXIS] * pointY) / (float) factors[2]; -} -#endif - -inline void PrintLine::queueEMove(int32_t extrudeDiff,uint8_t check_endstops,uint8_t pathOptimize) -{ - Printer::unsetAllSteppersDisabled(); - waitForXFreeLines(1); - uint8_t newPath = insertWaitMovesIfNeeded(pathOptimize, 1); - PrintLine *p = getNextWriteLine(); - float axisDiff[5]; // Axis movement in mm - if(check_endstops) p->flags = FLAG_CHECK_ENDSTOPS; - else p->flags = 0; - p->joinFlags = 0; - if(!pathOptimize) p->setEndSpeedFixed(true); - //Find direction - for(uint8_t i = 0; i < 3; i++) - { - p->delta[i] = 0; - axisDiff[i] = 0; - } - if (extrudeDiff >= 0) - { - p->delta[E_AXIS] = extrudeDiff; - p->dir = E_STEP_DIRPOS; - } - else - { - p->delta[E_AXIS] = -extrudeDiff; - p->dir = ESTEP; - } - Printer::currentPositionSteps[E_AXIS] = Printer::destinationSteps[E_AXIS]; - - p->numDeltaSegments = 0; - //Define variables that are needed for the Bresenham algorithm. Please note that Z is not currently included in the Bresenham algorithm. - p->primaryAxis = E_AXIS; - p->stepsRemaining = p->delta[E_AXIS]; - axisDiff[E_AXIS] = p->distance = p->delta[E_AXIS] * Printer::invAxisStepsPerMM[E_AXIS]; - axisDiff[VIRTUAL_AXIS] = -p->distance; - p->moveID = lastMoveID++; - p->calculateMove(axisDiff,pathOptimize); -} - -/** - Split a line up into a series of lines with at most DELTASEGMENTS_PER_PRINTLINE delta segments. - @param check_endstops Check endstops during the move. - @param pathOptimize Run the path optimizer. - @param delta_step_rate delta step rate in segments per second for the move. -*/ -uint8_t PrintLine::queueDeltaMove(uint8_t check_endstops,uint8_t pathOptimize, uint8_t softEndstop) -{ - //if (softEndstop && Printer::destinationSteps[Z_AXIS] < 0) Printer::destinationSteps[Z_AXIS] = 0; // now constrained at entry level including cylinder test - int32_t difference[E_AXIS_ARRAY]; - float axis_diff[VIRTUAL_AXIS_ARRAY]; // Axis movement in mm. Virtual axis in 4; - for(fast8_t axis = 0; axis < E_AXIS_ARRAY; axis++) - { - difference[axis] = Printer::destinationSteps[axis] - Printer::currentPositionSteps[axis]; - if(axis == E_AXIS) - { - Printer::extrudeMultiplyError += (static_cast(difference[E_AXIS]) * Printer::extrusionFactor); - difference[E_AXIS] = static_cast(Printer::extrudeMultiplyError); - Printer::extrudeMultiplyError -= difference[E_AXIS]; - axis_diff[E_AXIS] = difference[E_AXIS] * Printer::invAxisStepsPerMM[E_AXIS]; - Printer::filamentPrinted += axis_diff[E_AXIS]; - axis_diff[E_AXIS] = fabs(axis_diff[E_AXIS]); - } - else - axis_diff[axis] = fabs(difference[axis] * Printer::invAxisStepsPerMM[axis]); - } - - float cartesianDistance; - ufast8_t cartesianDir; - int32_t cartesianDeltaSteps[E_AXIS_ARRAY]; - calculateDirectionAndDelta(difference, &cartesianDir, cartesianDeltaSteps); - if (!calculateDistance(axis_diff, cartesianDir, &cartesianDistance)) - { - // Appears the intent is to do nothing if no distance is detected. - // This apparently is not an error condition, just early exit. - return true; - } - - if (!(cartesianDir & XYZ_STEP)) - { - queueEMove(difference[E_AXIS], check_endstops,pathOptimize); - return true; - } - - int16_t segmentCount; - float feedrate = RMath::min(Printer::feedrate, Printer::maxFeedrate[Z_AXIS]); - if (cartesianDir & XY_STEP) - { - // Compute number of seconds for move and hence number of segments needed - //float seconds = 100 * cartesianDistance / (Printer::feedrate * Printer::feedrateMultiply); multiply in feedrate included - float seconds = cartesianDistance / feedrate; -#ifdef DEBUG_SPLIT - Com::printFLN(Com::tDBGDeltaSeconds, seconds); -#endif - float sps = static_cast((cartesianDir & E_STEP_DIRPOS) == E_STEP_DIRPOS ? Printer::printMovesPerSecond : Printer::travelMovesPerSecond); - segmentCount = RMath::max(1, static_cast(sps * seconds)); -#ifdef DEBUG_SEGMENT_LENGTH - float segDist = cartesianDistance/(float)segmentCount; - if(segDist > Printer::maxRealSegmentLength) - { - Printer::maxRealSegmentLength = segDist; - Com::printFLN("StepsPerSecond:",sps); - Com::printFLN(PSTR("New max. segment length:"),segDist); - } -#endif - //Com::printFLN(PSTR("Segments:"),segmentCount); - } - else - { - // Optimize pure Z axis move. Since a pure Z axis move is linear all we have to watch out for is unsigned integer overuns in - // the queued moves; -#ifdef DEBUG_SPLIT - Com::printFLN(Com::tDBGDeltaZDelta, cartesianDeltaSteps[Z_AXIS]); -#endif - segmentCount = (cartesianDeltaSteps[Z_AXIS] + (uint32_t)65534) / (uint32_t)65535; - } - // Now compute the number of lines needed - int numLines = (segmentCount + DELTASEGMENTS_PER_PRINTLINE - 1) / DELTASEGMENTS_PER_PRINTLINE; - // There could be some error here but it doesn't matter since the number of segments will just be reduced slightly - int segmentsPerLine = segmentCount / numLines; - - int32_t startPosition[E_AXIS_ARRAY], fractionalSteps[E_AXIS_ARRAY]; - if(numLines > 1) - { - for (fast8_t i = 0; i < Z_AXIS_ARRAY; i++) - startPosition[i] = Printer::currentPositionSteps[i]; - startPosition[E_AXIS] = 0; - cartesianDistance /= numLines; - } - -#ifdef DEBUG_SPLIT - Com::printFLN(Com::tDBGDeltaSegments, segmentCount); - Com::printFLN(Com::tDBGDeltaNumLines, numLines); - Com::printFLN(Com::tDBGDeltaSegmentsPerLine, segmentsPerLine); -#endif - Printer::unsetAllSteppersDisabled(); // Motor is enabled now - waitForXFreeLines(1); - - // Insert dummy moves if necessary - // Nead to leave at least one slot open for the first split move - insertWaitMovesIfNeeded(pathOptimize, RMath::min(PRINTLINE_CACHE_SIZE - 4, numLines)); - uint32_t oldEDestination = Printer::destinationSteps[E_AXIS]; // flow and volumetric extrusion changed virtual target - Printer::currentPositionSteps[E_AXIS] = 0; - - for (int lineNumber = 1; lineNumber < numLines + 1; lineNumber++) - { - waitForXFreeLines(1); - PrintLine *p = getNextWriteLine(); - // Downside a comparison per loop. Upside one less distance calculation and simpler code. - if (numLines == 1) - { - // p->numDeltaSegments = segmentCount; // not neede, gets overwritten further down - p->dir = cartesianDir; - for (fast8_t i = 0; i < E_AXIS_ARRAY; i++) - { - p->delta[i] = cartesianDeltaSteps[i]; - fractionalSteps[i] = difference[i]; - } - p->distance = cartesianDistance; - } - else - { - for (fast8_t i = 0; i < E_AXIS_ARRAY; i++) - { - Printer::destinationSteps[i] = startPosition[i] + (difference[i] * lineNumber) / numLines; - fractionalSteps[i] = Printer::destinationSteps[i] - Printer::currentPositionSteps[i]; - axis_diff[i] = fabs(fractionalSteps[i] * Printer::invAxisStepsPerMM[i]); - } - calculateDirectionAndDelta(fractionalSteps, &p->dir, p->delta); - p->distance = cartesianDistance; - } - - p->joinFlags = 0; - p->moveID = lastMoveID; - - // Only set fixed on last segment - if (lineNumber == numLines && !pathOptimize) - p->setEndSpeedFixed(true); - - p->flags = (check_endstops ? FLAG_CHECK_ENDSTOPS : 0); - p->numDeltaSegments = segmentsPerLine; - - uint16_t maxDeltaStep = p->calculateDeltaSubSegments(softEndstop); - if (maxDeltaStep == 65535) - { - Com::printWarningFLN(PSTR("in queueDeltaMove to calculateDeltaSubSegments returns error.")); - return false; - } - -#ifdef DEBUG_SPLIT - Com::printFLN(Com::tDBGDeltaMaxDS, (int32_t)maxDeltaStep); -#endif - int32_t virtual_axis_move = (int32_t)maxDeltaStep * segmentsPerLine; - if (virtual_axis_move == 0 && p->delta[E_AXIS] == 0) - { - if (numLines != 1) - { - Com::printErrorFLN(Com::tDBGDeltaNoMoveinDSegment); - return false; // Line too short in low precision area - } - } - p->primaryAxis = VIRTUAL_AXIS; // Virtual axis will lead bresenham step either way - if (virtual_axis_move > p->delta[E_AXIS]) // Is delta move or E axis leading - { - p->stepsRemaining = virtual_axis_move; - axis_diff[VIRTUAL_AXIS] = p->distance; //virtual_axis_move * Printer::invAxisStepsPerMM[Z_AXIS]; // Steps/unit same as all the towers - // Virtual axis steps per segment - p->numPrimaryStepPerSegment = maxDeltaStep; - } - else - { - // Round up the E move to get something divisible by segment count which is greater than E move - p->numPrimaryStepPerSegment = (p->delta[E_AXIS] + segmentsPerLine - 1) / segmentsPerLine; - p->stepsRemaining = p->numPrimaryStepPerSegment * segmentsPerLine; - axis_diff[VIRTUAL_AXIS] = -p->distance; //p->stepsRemaining * Printer::invAxisStepsPerMM[Z_AXIS]; - } -#ifdef DEBUG_SPLIT - Com::printFLN(Com::tDBGDeltaStepsPerSegment, p->numPrimaryStepPerSegment); - Com::printFLN(Com::tDBGDeltaVirtualAxisSteps, p->stepsRemaining); -#endif - p->calculateMove(axis_diff, pathOptimize); - for (uint8_t i = 0; i < E_AXIS_ARRAY; i++) - { - Printer::currentPositionSteps[i] += fractionalSteps[i]; - } - } - Printer::currentPositionSteps[E_AXIS] = Printer::destinationSteps[E_AXIS] = oldEDestination; - lastMoveID++; // Will wrap at 255 - - return true; // flag success -} - -#endif - -#if ARC_SUPPORT -// Arc function taken from grbl -// The arc is approximated by generating a huge number of tiny, linear segments. The length of each -// segment is configured in settings.mm_per_arc_segment. -void PrintLine::arc(float *position, float *target, float *offset, float radius, uint8_t isclockwise) -{ - // int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled(); - // plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc - float center_axis0 = position[X_AXIS] + offset[X_AXIS]; - float center_axis1 = position[Y_AXIS] + offset[Y_AXIS]; - float linear_travel = 0; //target[axis_linear] - position[axis_linear]; - float extruder_travel = (Printer::destinationSteps[E_AXIS] - Printer::currentPositionSteps[E_AXIS]) * Printer::invAxisStepsPerMM[E_AXIS]; - float r_axis0 = -offset[0]; // Radius vector from center to current location - float r_axis1 = -offset[1]; - float rt_axis0 = target[0] - center_axis0; - float rt_axis1 = target[1] - center_axis1; - /*long xtarget = Printer::destinationSteps[X_AXIS]; - long ytarget = Printer::destinationSteps[Y_AXIS]; - long ztarget = Printer::destinationSteps[Z_AXIS]; - long etarget = Printer::destinationSteps[E_AXIS]; - */ - // CCW angle between position and target from circle center. Only one atan2() trig computation required. - float angular_travel = atan2(r_axis0 * rt_axis1 - r_axis1 * rt_axis0, r_axis0 * rt_axis0 + r_axis1 * rt_axis1); - if (angular_travel < 0) - { - angular_travel += 2.0f * M_PI; - } - if (isclockwise) - { - angular_travel -= 2.0f * M_PI; - } - - float millimeters_of_travel = fabs(angular_travel)*radius; //hypot(angular_travel*radius, fabs(linear_travel)); - if (millimeters_of_travel < 0.001f) - { - return;// treat as succes because there is nothing to do; - } - //uint16_t segments = (radius>=BIG_ARC_RADIUS ? floor(millimeters_of_travel/MM_PER_ARC_SEGMENT_BIG) : floor(millimeters_of_travel/MM_PER_ARC_SEGMENT)); - // Increase segment size if printing faster then computation speed allows - uint16_t segments = (Printer::feedrate > 60.0f ? floor(millimeters_of_travel / RMath::min(static_cast(MM_PER_ARC_SEGMENT_BIG), Printer::feedrate * 0.01666f * static_cast(MM_PER_ARC_SEGMENT))) : floor(millimeters_of_travel / static_cast(MM_PER_ARC_SEGMENT))); - if(segments == 0) segments = 1; - /* - // Multiply inverse feed_rate to compensate for the fact that this movement is approximated - // by a number of discrete segments. The inverse feed_rate should be correct for the sum of - // all segments. - if (invert_feed_rate) { feed_rate *= segments; } - */ - float theta_per_segment = angular_travel / segments; - //float linear_per_segment = linear_travel/segments; - float extruder_per_segment = extruder_travel / segments; - - /* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, - and phi is the angle of rotation. Based on the solution approach by Jens Geisler. - r_T = [cos(phi) -sin(phi); - sin(phi) cos(phi] * r ; - - For arc generation, the center of the circle is the axis of rotation and the radius vector is - defined from the circle center to the initial position. Each line segment is formed by successive - vector rotations. This requires only two cos() and sin() computations to form the rotation - matrix for the duration of the entire arc. Error may accumulate from numerical round-off, since - all double numbers are single precision on the Arduino. (True double precision will not have - round off issues for CNC applications.) Single precision error can accumulate to be greater than - tool precision in some cases. Therefore, arc path correction is implemented. - - Small angle approximation may be used to reduce computation overhead further. This approximation - holds for everything, but very small circles and large mm_per_arc_segment values. In other words, - theta_per_segment would need to be greater than 0.1 rad and N_ARC_CORRECTION would need to be large - to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for - numerical drift error. N_ARC_CORRECTION may be on the order a hundred(s) before error becomes an - issue for CNC machines with the single precision Arduino calculations. - - This approximation also allows mc_arc to immediately insert a line segment into the planner - without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied - a correction, the planner should have caught up to the lag caused by the initial mc_arc overhead. - This is important when there are successive arc motions. - */ - // Vector rotation matrix values - float cos_T = 1 - 0.5 * theta_per_segment * theta_per_segment; // Small angle approximation - float sin_T = theta_per_segment; - - float arc_target[4]; - float sin_Ti; - float cos_Ti; - float r_axisi; - uint16_t i; - int8_t count = 0; - - // Initialize the linear axis - //arc_target[axis_linear] = position[axis_linear]; - - // Initialize the extruder axis - arc_target[E_AXIS] = Printer::currentPositionSteps[E_AXIS] * Printer::invAxisStepsPerMM[E_AXIS]; - - for (i = 1; i < segments; i++) - { - // Increment (segments-1) - - if((count & 3) == 0) - { - GCode::readFromSerial(); - Commands::checkForPeriodicalActions(false); - UI_MEDIUM; // do check encoder - } - - if (count < N_ARC_CORRECTION) //25 pieces - { - // Apply vector rotation matrix - r_axisi = r_axis0 * sin_T + r_axis1 * cos_T; - r_axis0 = r_axis0 * cos_T - r_axis1 * sin_T; - r_axis1 = r_axisi; - count++; - } - else - { - // Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. - // Compute exact location by applying transformation matrix from initial radius vector(=-offset). - cos_Ti = cos(i * theta_per_segment); - sin_Ti = sin(i * theta_per_segment); - r_axis0 = -offset[0] * cos_Ti + offset[1] * sin_Ti; - r_axis1 = -offset[0] * sin_Ti - offset[1] * cos_Ti; - count = 0; - } - - // Update arc_target location - arc_target[X_AXIS] = center_axis0 + r_axis0; - arc_target[Y_AXIS] = center_axis1 + r_axis1; - //arc_target[axis_linear] += linear_per_segment; - arc_target[E_AXIS] += extruder_per_segment; - Printer::moveToReal(arc_target[X_AXIS],arc_target[Y_AXIS],IGNORE_COORDINATE,arc_target[E_AXIS],IGNORE_COORDINATE); - } - // Ensure last segment arrives at target location. - Printer::moveToReal(target[X_AXIS],target[Y_AXIS],IGNORE_COORDINATE,target[E_AXIS],IGNORE_COORDINATE); -} -#endif - - - -/** - Moves the stepper motors one step. If the last step is reached, the next movement is started. - The function must be called from a timer loop. It returns the time for the next call. - This is a modified version that implements a bresenham 'multi-step' algorithm where the dominant - cartesian axis steps may be less than the changing dominant delta axis. -*/ -#if NONLINEAR_SYSTEM -int lastblk =- 1; -int32_t cur_errupd; -//#define DEBUG_DELTA_TIMER -// Current delta segment -DeltaSegment *curd; -// Current delta segment primary error increment -int32_t curd_errupd, stepsPerSegRemaining; -int32_t PrintLine::bresenhamStep() // Version for delta printer -{ -#if CPU_ARCH == ARCH_ARM - if(!PrintLine::nlFlag) -#else - if(cur == NULL) -#endif - { - setCurrentLine(); - if(cur->isBlocked()) // This step is in computation - shouldn't happen - { - if(lastblk != (int)cur) - { - HAL::allowInterrupts(); - lastblk = (int)cur; - Com::printFLN(Com::tBLK, (int32_t)linesCount); - } - cur = NULL; -#if CPU_ARCH == ARCH_ARM - PrintLine::nlFlag = false; -#endif - return 2000; - } - HAL::allowInterrupts(); - lastblk = -1; -#if INCLUDE_DEBUG_NO_MOVE - if(Printer::debugNoMoves()) // simulate a move, but do nothing in reality - { - //HAL::forbidInterrupts(); - //deltaSegmentCount -= cur->numDeltaSegments; // should always be zero - removeCurrentLineForbidInterrupt(); - if(linesCount == 0) UI_STATUS(UI_TEXT_IDLE); - return 1000; - } -#endif - if(cur->isWarmUp()) - { - // This is a warmup move to initalize the path planner correctly. Just waste - // a bit of time to get the planning up to date. - if(linesCount <= cur->getWaitForXLinesFilled()) - { - cur = NULL; -#if CPU_ARCH==ARCH_ARM - PrintLine::nlFlag = false; -#endif - return 2000; - } - long wait = cur->getWaitTicks(); - removeCurrentLineForbidInterrupt(); - return(wait); // waste some time for path optimization to fill up - } // End if WARMUP -#if FEATURE_Z_PROBE - // z move may consist of mroe then 1 z line segment, so we better ignore them - // if the probe was already hit. - if(Printer::isZProbingActive() && Printer::stepsRemainingAtZHit >= 0) - { - removeCurrentLineForbidInterrupt(); - if(linesCount == 0) UI_STATUS(UI_TEXT_IDLE); - return 1000; - } -#endif - - if(cur->isEMove()) Extruder::enable(); - cur->fixStartAndEndSpeed(); - // Set up delta segments - if (cur->numDeltaSegments) - { - - // If there are delta segments point to them here - curd = &cur->segments[--cur->numDeltaSegments]; - // Enable axis - All axis are enabled since they will most probably all be involved in a move - // Since segments could involve different axis this reduces load when switching segments and - // makes disabling easier. - Printer::enableXStepper(); - Printer::enableYStepper(); - Printer::enableZStepper(); - - // Copy across movement into main direction flags so that endstops function correctly - cur->dir |= curd->dir; - // Initialize bresenham for the first segment - cur->error[X_AXIS] = cur->error[Y_AXIS] = cur->error[Z_AXIS] = cur->numPrimaryStepPerSegment >> 1; - curd_errupd = cur->numPrimaryStepPerSegment; - stepsPerSegRemaining = cur->numPrimaryStepPerSegment; - } - else curd = NULL; - cur_errupd = cur->stepsRemaining; - - if(!cur->areParameterUpToDate()) // should never happen, but with bad timings??? - { - cur->updateStepsParameter(); - } - Printer::vMaxReached = cur->vStart; - Printer::stepNumber = 0; - Printer::timer = 0; - HAL::forbidInterrupts(); - //Determine direction of movement - if (curd) - { - Printer::setXDirection(curd->isXPositiveMove()); - Printer::setYDirection(curd->isYPositiveMove()); - Printer::setZDirection(curd->isZPositiveMove()); - } -#if USE_ADVANCE - if(!Printer::isAdvanceActivated()) // Set direction if no advance enabled -#endif - Extruder::setDirection(cur->isEPositiveMove()); -#if defined(DIRECTION_DELAY) && DIRECTION_DELAY > 0 - HAL::delayMicroseconds(DIRECTION_DELAY); -#endif -#if USE_ADVANCE -#if ENABLE_QUADRATIC_ADVANCE - Printer::advanceExecuted = cur->advanceStart; -#endif - cur->updateAdvanceSteps(cur->vStart, 0, false); -#endif - return Printer::interval; // Wait an other 50% from last step to make the 100% full - } // End cur=0 - HAL::allowInterrupts(); - - if(curd != NULL) - { - Endstops::update(); - curd->checkEndstops(cur,(cur->isCheckEndstops())); - } - int maxLoops = (Printer::stepsPerTimerCall <= cur->stepsRemaining ? Printer::stepsPerTimerCall : cur->stepsRemaining); - HAL::forbidInterrupts(); - for(int loop = 0; loop < maxLoops; loop++) - { -#if STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY - if(loop > 0) - HAL::delayMicroseconds(STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY); -#endif - if((cur->error[E_AXIS] -= cur->delta[E_AXIS]) < 0) - { -#if USE_ADVANCE - if(Printer::isAdvanceActivated()) // Use interrupt for movement - { - if(cur->isEPositiveMove()) - Printer::extruderStepsNeeded++; - else - Printer::extruderStepsNeeded--; - } - else -#endif - Extruder::step(); - cur->error[E_AXIS] += cur_errupd; - } - if (curd) - { - // Take delta steps - if(curd->isXMove()) - if((cur->error[X_AXIS] -= curd->deltaSteps[A_TOWER]) < 0) - { - cur->startXStep(); - cur->error[X_AXIS] += curd_errupd; -#ifdef DEBUG_REAL_POSITION - Printer::realDeltaPositionSteps[A_TOWER] += curd->isXPositiveMove() ? 1 : -1; -#endif -#ifdef DEBUG_STEPCOUNT - cur->totalStepsRemaining--; -#endif - } - - if(curd->isYMove()) - if((cur->error[Y_AXIS] -= curd->deltaSteps[B_TOWER]) < 0) - { - cur->startYStep(); - cur->error[Y_AXIS] += curd_errupd; -#ifdef DEBUG_REAL_POSITION - Printer::realDeltaPositionSteps[B_TOWER] += curd->isYPositiveMove() ? 1 : -1; -#endif -#ifdef DEBUG_STEPCOUNT - cur->totalStepsRemaining--; -#endif - } - - if(curd->isZMove()) - if((cur->error[Z_AXIS] -= curd->deltaSteps[C_TOWER]) < 0) - { - cur->startZStep(); - cur->error[Z_AXIS] += curd_errupd; - Printer::realDeltaPositionSteps[C_TOWER] += curd->isZPositiveMove() ? 1 : -1; -#ifdef DEBUG_STEPCOUNT - cur->totalStepsRemaining--; -#endif - } - stepsPerSegRemaining--; - if (!stepsPerSegRemaining) - { - if (cur->numDeltaSegments) - { - // Get the next delta segment - curd = &cur->segments[--cur->numDeltaSegments]; - - // Initialize bresenham for this segment (numPrimaryStepPerSegment is already correct for the half step setting) - cur->error[X_AXIS] = cur->error[Y_AXIS] = cur->error[Z_AXIS] = cur->numPrimaryStepPerSegment >> 1; - - // Reset the counter of the primary steps. This is initialized in the line - // generation so don't have to do this the first time. - stepsPerSegRemaining = cur->numPrimaryStepPerSegment; - - // Change direction if necessary - Printer::setXDirection(curd->dir & X_DIRPOS); - Printer::setYDirection(curd->dir & Y_DIRPOS); - Printer::setZDirection(curd->dir & Z_DIRPOS); -#if defined(DIRECTION_DELAY) && DIRECTION_DELAY > 0 - HAL::delayMicroseconds(DIRECTION_DELAY); -#endif - - if(FEATURE_BABYSTEPPING && Printer::zBabystepsMissing && curd - && (curd->dir & XYZ_STEP) == XYZ_STEP) - { - // execute a extra babystep - Printer::insertStepperHighDelay(); - Printer::endXYZSteps(); - HAL::delayMicroseconds(STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY + 1); - - if(Printer::zBabystepsMissing > 0) - { - if(curd->dir & X_DIRPOS) - cur->startXStep(); - else - cur->error[X_AXIS] += curd_errupd; - if(curd->dir & Y_DIRPOS) - cur->startYStep(); - else - cur->error[Y_AXIS] += curd_errupd; - if(curd->dir & Z_DIRPOS) - cur->startZStep(); - else - cur->error[Z_AXIS] += curd_errupd; - Printer::zBabystepsMissing--; - } - else - { - if(curd->dir & X_DIRPOS) - cur->error[X_AXIS] += curd_errupd; - else - cur->startXStep(); - if(curd->dir & Y_DIRPOS) - cur->error[Y_AXIS] += curd_errupd; - else - cur->startYStep(); - if(curd->dir & Z_DIRPOS) - cur->error[Z_AXIS] += curd_errupd; - else - cur->startZStep(); - Printer::zBabystepsMissing++; - } - HAL::delayMicroseconds(1); - } - } - else - curd = 0;// Release the last segment - //deltaSegmentCount--; - } - } -#if CPU_ARCH != ARCH_AVR - if(loop < maxLoops - 1) - { -#endif - Printer::insertStepperHighDelay(); - Printer::endXYZSteps(); -#if USE_ADVANCE - if(!Printer::isAdvanceActivated()) // Use interrupt for movement -#endif - Extruder::unstep(); -#if CPU_ARCH != ARCH_AVR - } -#endif - } // for loop - - HAL::allowInterrupts(); // Allow interrupts for other types, timer1 is still disabled -#if RAMP_ACCELERATION -//If acceleration is enabled on this move and we are in the acceleration segment, calculate the current interval - if (cur->moveAccelerating()) - { - Printer::vMaxReached = HAL::ComputeV(Printer::timer, cur->fAcceleration) + cur->vStart; - if(Printer::vMaxReached > cur->vMax) Printer::vMaxReached = cur->vMax; - speed_t v = Printer::updateStepsPerTimerCall(Printer::vMaxReached); - Printer::interval = HAL::CPUDivU2(v); - Printer::timer += Printer::interval; - cur->updateAdvanceSteps(Printer::vMaxReached, maxLoops, true); - Printer::stepNumber += maxLoops; // is only used by moveAccelerating - } - else if (cur->moveDecelerating()) // time to slow down - { - speed_t v = HAL::ComputeV(Printer::timer, cur->fAcceleration); - if (v > Printer::vMaxReached) // if deceleration goes too far it can become too large - v = cur->vEnd; - else - { - v = Printer::vMaxReached - v; - if (v < cur->vEnd) v = cur->vEnd; // extra steps at the end of desceleration due to rounding erros - } - cur->updateAdvanceSteps(v, maxLoops, false); - v = Printer::updateStepsPerTimerCall(v); - Printer::interval = HAL::CPUDivU2(v); - Printer::timer += Printer::interval; - } - else - { - // If we had acceleration, we need to use the latest vMaxReached and interval - // If we started full speed, we need to use cur->fullInterval and vMax - cur->updateAdvanceSteps((!cur->accelSteps ? cur->vMax : Printer::vMaxReached), 0, true); - if(!cur->accelSteps) - { - if(cur->vMax > STEP_DOUBLER_FREQUENCY) - { -#if ALLOW_QUADSTEPPING - if(cur->vMax > STEP_DOUBLER_FREQUENCY * 2) - { - Printer::stepsPerTimerCall = 4; - Printer::interval = cur->fullInterval << 2; - } - else - { - Printer::stepsPerTimerCall = 2; - Printer::interval = cur->fullInterval << 1; - } -#else - Printer::stepsPerTimerCall = 2; - Printer::interval = cur->fullInterval << 1; -#endif - } - else - { - Printer::stepsPerTimerCall = 1; - Printer::interval = cur->fullInterval; - } - } - } -#else - Printer::interval = cur->fullInterval; // without RAMPS always use full speed -#endif - PrintLine::cur->stepsRemaining -= maxLoops; - - if(cur->stepsRemaining <= 0 || cur->isNoMove()) // line finished - { - // Release remaining delta segments -#ifdef DEBUG_STEPCOUNT - if(cur->totalStepsRemaining || cur->numDeltaSegments) - { - Com::printFLN(PSTR("Missed steps:"), cur->totalStepsRemaining); - Com::printFLN(PSTR("Step/seg r:"), stepsPerSegRemaining); - Com::printFLN(PSTR("NDS:"), (int) cur->numDeltaSegments); - } -#endif - //HAL::forbidInterrupts(); - //deltaSegmentCount -= cur->numDeltaSegments; // should always be zero - removeCurrentLineForbidInterrupt(); - Printer::disableAllowedStepper(); - if(linesCount == 0) UI_STATUS(UI_TEXT_IDLE); - Printer::interval >>= 1; // 50% of time to next call to do cur=0 - DEBUG_MEMORY; - } // Do even -#if CPU_ARCH != ARCH_AVR - Printer::insertStepperHighDelay(); - Printer::endXYZSteps(); -#if USE_ADVANCE - if(!Printer::isAdvanceActivated()) // Use interrupt for movement -#endif - Extruder::unstep(); -#endif - return Printer::interval; -} -#else -/** - Moves the stepper motors one step. If the last step is reached, the next movement is started. - The function must be called from a timer loop. It returns the time for the next call. - - Normal non delta algorithm -*/ -int lastblk = -1; -int32_t cur_errupd; -int32_t PrintLine::bresenhamStep() // version for cartesian printer -{ -#if CPU_ARCH == ARCH_ARM - if(!PrintLine::nlFlag) -#else - if(cur == NULL) -#endif - { - ANALYZER_ON(ANALYZER_CH0); - setCurrentLine(); - if(cur->isBlocked()) // This step is in computation - shouldn't happen - { - /*if(lastblk!=(int)cur) // can cause output errors! - { - HAL::allowInterrupts(); - lastblk = (int)cur; - Com::printFLN(Com::tBLK,lines_count); - }*/ - cur = NULL; -#if CPU_ARCH==ARCH_ARM - PrintLine::nlFlag = false; -#endif - return 2000; - } - HAL::allowInterrupts(); - lastblk = -1; -#if INCLUDE_DEBUG_NO_MOVE - if(Printer::debugNoMoves()) // simulate a move, but do nothing in reality - { - removeCurrentLineForbidInterrupt(); - return 1000; - } -#endif - ANALYZER_OFF(ANALYZER_CH0); - if(cur->isWarmUp()) - { - // This is a warmup move to initalize the path planner correctly. Just waste - // a bit of time to get the planning up to date. - if(linesCount<=cur->getWaitForXLinesFilled()) - { - cur = NULL; -#if CPU_ARCH == ARCH_ARM - PrintLine::nlFlag = false; -#endif - return 2000; - } - long wait = cur->getWaitTicks(); - removeCurrentLineForbidInterrupt(); - return(wait); // waste some time for path optimization to fill up - } // End if WARMUP - //Only enable axis that are moving. If the axis doesn't need to move then it can stay disabled depending on configuration. -#if GANTRY -#if DRIVE_SYSTEM == XY_GANTRY || DRIVE_SYSTEM == YX_GANTRY - if(cur->isXOrYMove()) - { - Printer::enableXStepper(); - Printer::enableYStepper(); - } - if(cur->isZMove()) Printer::enableZStepper(); -#else // XZ / ZX Gantry - if(cur->isXOrZMove()) - { - Printer::enableXStepper(); - Printer::enableZStepper(); - } - if(cur->isYMove()) Printer::enableYStepper(); -#endif -#else - if(cur->isXMove()) Printer::enableXStepper(); - if(cur->isYMove()) Printer::enableYStepper(); - if(cur->isZMove()) Printer::enableZStepper(); -#endif - if(cur->isEMove()) Extruder::enable(); - cur->fixStartAndEndSpeed(); - HAL::allowInterrupts(); - cur_errupd = cur->delta[cur->primaryAxis]; - if(!cur->areParameterUpToDate()) // should never happen, but with bad timings??? - { - cur->updateStepsParameter(); - } - Printer::vMaxReached = cur->vStart; - Printer::stepNumber=0; - Printer::timer = 0; - HAL::forbidInterrupts(); - //Determine direction of movement,check if endstop was hit -#if !(GANTRY) - Printer::setXDirection(cur->isXPositiveMove()); - Printer::setYDirection(cur->isYPositiveMove()); - Printer::setZDirection(cur->isZPositiveMove()); -#else // Any gantry type - long gdx = (cur->dir & X_DIRPOS ? cur->delta[X_AXIS] : -cur->delta[X_AXIS]); // Compute signed difference in steps -#if DRIVE_SYSTEM == XY_GANTRY || DRIVE_SYSTEM == YX_GANTRY - Printer::setZDirection(cur->isZPositiveMove()); - long gdy = (cur->dir & Y_DIRPOS ? cur->delta[Y_AXIS] : -cur->delta[Y_AXIS]); - Printer::setXDirection(gdx + gdy >= 0); -#if DRIVE_SYSTEM == XY_GANTRY - Printer::setYDirection(gdx > gdy); -#else - Printer::setYDirection(gdx <= gdy); -#endif -#else // XZ or ZX core - Printer::setYDirection(cur->isYPositiveMove()); - long gdz = (cur->dir & Z_DIRPOS ? cur->delta[Z_AXIS] : -cur->delta[Z_AXIS]); - Printer::setXDirection(gdx + gdz >= 0); -#if DRIVE_SYSTEM == XZ_GANTRY - Printer::setZDirection(gdx > gdz); -#else - Printer::setZDirection(gdx <= gdz); -#endif -#endif // YZ or ZY Gantry -#endif // GANTRY -#if USE_ADVANCE - if(!Printer::isAdvanceActivated()) // Set direction if no advance/OPS enabled -#endif - Extruder::setDirection(cur->isEPositiveMove()); -#if defined(DIRECTION_DELAY) && DIRECTION_DELAY > 0 - HAL::delayMicroseconds(DIRECTION_DELAY); -#endif -#if USE_ADVANCE -#if ENABLE_QUADRATIC_ADVANCE - Printer::advanceExecuted = cur->advanceStart; -#endif - cur->updateAdvanceSteps(cur->vStart, 0, false); -#endif - return Printer::interval; // Wait an other 50% from last step to make the 100% full - } // End cur=0 - Endstops::update(); - cur->checkEndstops(); - fast8_t max_loops = RMath::min((int32_t)Printer::stepsPerTimerCall,cur->stepsRemaining); - for(fast8_t loop = 0; loop < max_loops; loop++) - { -#if STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY > 0 - if(loop > 0) - HAL::delayMicroseconds(STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY); -#endif - if((cur->error[E_AXIS] -= cur->delta[E_AXIS]) < 0) - { -#if USE_ADVANCE - if(Printer::isAdvanceActivated()) // Use interrupt for movement - { - if(cur->isEPositiveMove()) - Printer::extruderStepsNeeded++; - else - Printer::extruderStepsNeeded--; - } - else -#endif - Extruder::step(); - cur->error[E_AXIS] += cur_errupd; - } - if(cur->isXMove()) - if((cur->error[X_AXIS] -= cur->delta[X_AXIS]) < 0) - { - cur->startXStep(); - cur->error[X_AXIS] += cur_errupd; - } - if(cur->isYMove()) - if((cur->error[Y_AXIS] -= cur->delta[Y_AXIS]) < 0) - { - cur->startYStep(); - cur->error[Y_AXIS] += cur_errupd; - } - if(cur->isZMove()) - if((cur->error[Z_AXIS] -= cur->delta[Z_AXIS]) < 0) - { - cur->startZStep(); - cur->error[Z_AXIS] += cur_errupd; -#ifdef DEBUG_STEPCOUNT - cur->totalStepsRemaining--; -#endif - } -#if (GANTRY) -#if DRIVE_SYSTEM == XY_GANTRY || DRIVE_SYSTEM == YX_GANTRY - Printer::executeXYGantrySteps(); -#else - Printer::executeXZGantrySteps(); -#endif -#endif - Printer::insertStepperHighDelay(); -#if USE_ADVANCE - if(!Printer::isAdvanceActivated()) // Use interrupt for movement -#endif - Extruder::unstep(); - Printer::endXYZSteps(); - } // for loop - HAL::allowInterrupts(); // Allow interrupts for other types, timer1 is still disabled -#if RAMP_ACCELERATION - //If acceleration is enabled on this move and we are in the acceleration segment, calculate the current interval - if (cur->moveAccelerating()) // we are accelerating - { - Printer::vMaxReached = HAL::ComputeV(Printer::timer,cur->fAcceleration) + cur->vStart; - if(Printer::vMaxReached > cur->vMax) Printer::vMaxReached = cur->vMax; - unsigned int v = Printer::updateStepsPerTimerCall(Printer::vMaxReached); - Printer::interval = HAL::CPUDivU2(v); - Printer::timer += Printer::interval; - cur->updateAdvanceSteps(Printer::vMaxReached, max_loops, true); - Printer::stepNumber += max_loops; // only used for moveAccelerating - } - else if (cur->moveDecelerating()) // time to slow down - { - unsigned int v = HAL::ComputeV(Printer::timer,cur->fAcceleration); - if (v > Printer::vMaxReached) // if deceleration goes too far it can become too large - v = cur->vEnd; - else - { - v = Printer::vMaxReached - v; - if (vvEnd) v = cur->vEnd; // extra steps at the end of desceleration due to rounding erros - } - cur->updateAdvanceSteps(v,max_loops,false); // needs original v - v = Printer::updateStepsPerTimerCall(v); - Printer::interval = HAL::CPUDivU2(v); - Printer::timer += Printer::interval; - } - else // full speed reached - { - cur->updateAdvanceSteps((!cur->accelSteps ? cur->vMax : Printer::vMaxReached), 0, true); - // constant speed reached - if(cur->vMax > STEP_DOUBLER_FREQUENCY) - { -#if ALLOW_QUADSTEPPING - if(cur->vMax > STEP_DOUBLER_FREQUENCY * 2) - { - Printer::stepsPerTimerCall = 4; - Printer::interval = cur->fullInterval << 2; - } - else - { - Printer::stepsPerTimerCall = 2; - Printer::interval = cur->fullInterval << 1; - } -#else - Printer::stepsPerTimerCall = 2; - Printer::interval = cur->fullInterval << 1; -#endif - } - else - { - Printer::stepsPerTimerCall = 1; - Printer::interval = cur->fullInterval; - } - } -#else - Printer::stepsPerTimerCall = 1; - Printer::interval = cur->fullInterval; // without RAMPS always use full speed -#endif // RAMP_ACCELERATION - cur->stepsRemaining -= max_loops; - long interval = Printer::interval; - if(cur->stepsRemaining <= 0 || cur->isNoMove()) // line finished - { -#ifdef DEBUG_STEPCOUNT - if(cur->totalStepsRemaining) - { - Com::printF(Com::tDBGMissedSteps, cur->totalStepsRemaining); - Com::printFLN(Com::tComma, cur->stepsRemaining); - } -#endif - removeCurrentLineForbidInterrupt(); - Printer::disableAllowedStepper(); - if(linesCount == 0) UI_STATUS(UI_TEXT_IDLE); - interval = Printer::interval = interval >> 1; // 50% of time to next call to do cur=0 - DEBUG_MEMORY; - } // Do even - if(FEATURE_BABYSTEPPING && Printer::zBabystepsMissing) - { - Printer::zBabystep(); - } - return interval; -} -#endif - - +/* + 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 . + + 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 "Repetier.h" + +// ================ Sanity checks ================ +#ifndef STEP_DOUBLER_FREQUENCY +#error Please add new parameter STEP_DOUBLER_FREQUENCY to your configuration. +#else +#if STEP_DOUBLER_FREQUENCY < 10000 || STEP_DOUBLER_FREQUENCY > 20000 +#if CPU_ARCH==ARCH_AVR +#error STEP_DOUBLER_FREQUENCY should be in range 10000-16000. +#endif +#endif +#endif +#ifdef EXTRUDER_SPEED +#error EXTRUDER_SPEED is not used any more. Values are now taken from extruder definition. +#endif +#ifdef ENDSTOPPULLUPS +#error ENDSTOPPULLUPS is now replaced by individual pullup configuration! +#endif +#ifdef EXT0_PID_PGAIN +#error The PID system has changed. Please use the new float number options! +#endif +// #################################################################################### +// # No configuration below this line - just some errorchecking # +// #################################################################################### +#ifdef SUPPORT_MAX6675 +#if !defined SCK_PIN || !defined MOSI_PIN || !defined MISO_PIN +#error For MAX6675 support, you need to define SCK_PIN, MISO_PIN and MOSI_PIN in pins.h +#endif +#endif +#if X_STEP_PIN<0 || Y_STEP_PIN<0 || Z_STEP_PIN<0 +#error One of the following pins is not assigned: X_STEP_PIN,Y_STEP_PIN,Z_STEP_PIN +#endif +#if EXT0_STEP_PIN<0 && NUM_EXTRUDER>0 +#error EXT0_STEP_PIN not set to a pin number. +#endif +#if EXT0_DIR_PIN<0 && NUM_EXTRUDER>0 +#error EXT0_DIR_PIN not set to a pin number. +#endif +#if PRINTLINE_CACHE_SIZE<4 +#error PRINTLINE_CACHE_SIZE must be at least 5 +#endif + +//Inactivity shutdown variables +millis_t previousMillisCmd = 0; +millis_t maxInactiveTime = MAX_INACTIVE_TIME * 1000L; +millis_t stepperInactiveTime = STEPPER_INACTIVE_TIME * 1000L; +long baudrate = BAUDRATE; ///< Communication speed rate. +#if USE_ADVANCE +#if ENABLE_QUADRATIC_ADVANCE +int maxadv = 0; +#endif +int maxadv2 = 0; +float maxadvspeed = 0; +#endif +uint8_t pwm_pos[NUM_PWM]; // 0-NUM_EXTRUDER = Heater 0-NUM_EXTRUDER of extruder, NUM_EXTRUDER = Heated bed, NUM_EXTRUDER+1 Board fan, NUM_EXTRUDER+2 = Fan +volatile int waitRelax = 0; // Delay filament relax at the end of print, could be a simple timeout + +PrintLine PrintLine::lines[PRINTLINE_CACHE_SIZE]; ///< Cache for print moves. +PrintLine *PrintLine::cur = NULL; ///< Current printing line +#if CPU_ARCH == ARCH_ARM +volatile bool PrintLine::nlFlag = false; +#endif +ufast8_t PrintLine::linesWritePos = 0; ///< Position where we write the next cached line move. +volatile ufast8_t PrintLine::linesCount = 0; ///< Number of lines cached 0 = nothing to do. +ufast8_t PrintLine::linesPos = 0; ///< Position for executing line movement. + +/** +Move printer the given number of steps. Puts the move into the queue. Used by e.g. homing commands. +*/ +void PrintLine::moveRelativeDistanceInSteps(int32_t x, int32_t y, int32_t z, int32_t e, float feedrate, bool waitEnd, bool checkEndstop,bool pathOptimize) +{ +#if NUM_EXTRUDER > 0 + if(Printer::debugDryrun() || (MIN_EXTRUDER_TEMP > 30 && Extruder::current->tempControl.currentTemperatureC < MIN_EXTRUDER_TEMP && !Printer::isColdExtrusionAllowed())) + e = 0; // should not be allowed for current temperature +#endif + float savedFeedrate = Printer::feedrate; + Printer::destinationSteps[X_AXIS] = Printer::currentPositionSteps[X_AXIS] + x; + Printer::destinationSteps[Y_AXIS] = Printer::currentPositionSteps[Y_AXIS] + y; + Printer::destinationSteps[Z_AXIS] = Printer::currentPositionSteps[Z_AXIS] + z; + Printer::destinationSteps[E_AXIS] = Printer::currentPositionSteps[E_AXIS] + e; + Printer::feedrate = feedrate; +#if NONLINEAR_SYSTEM + if (!queueDeltaMove(checkEndstop, pathOptimize, false)) + { + Com::printWarningFLN(PSTR("moveRelativeDistanceInSteps / queueDeltaMove returns error")); + } +#else + queueCartesianMove(checkEndstop, pathOptimize); +#endif + Printer::feedrate = savedFeedrate; + Printer::updateCurrentPosition(false); + if(waitEnd) + Commands::waitUntilEndOfAllMoves(); + previousMillisCmd = HAL::timeInMilliseconds(); +} + +void PrintLine::moveRelativeDistanceInStepsReal(int32_t x, int32_t y, int32_t z, int32_t e, float feedrate, bool waitEnd,bool pathOptimize) +{ + Printer::lastCmdPos[X_AXIS] += x * Printer::invAxisStepsPerMM[X_AXIS]; + Printer::lastCmdPos[Y_AXIS] += y * Printer::invAxisStepsPerMM[Y_AXIS]; + Printer::lastCmdPos[Z_AXIS] += z * Printer::invAxisStepsPerMM[Z_AXIS]; + if(!Printer::isPositionAllowed( Printer::lastCmdPos[X_AXIS], Printer::lastCmdPos[Y_AXIS], Printer::lastCmdPos[Z_AXIS])) + { + return; // ignore move + } +#if NUM_EXTRUDER > 0 + if(Printer::debugDryrun() || (MIN_EXTRUDER_TEMP > 30 && Extruder::current->tempControl.currentTemperatureC < MIN_EXTRUDER_TEMP && !Printer::isColdExtrusionAllowed())) + e = 0; // should not be allowed for current temperature +#endif + Printer::moveToReal(Printer::lastCmdPos[X_AXIS], Printer::lastCmdPos[Y_AXIS], Printer::lastCmdPos[Z_AXIS], + (Printer::currentPositionSteps[E_AXIS] + e) * Printer::invAxisStepsPerMM[E_AXIS],feedrate,pathOptimize); + Printer::updateCurrentPosition(); + if(waitEnd) + Commands::waitUntilEndOfAllMoves(); + previousMillisCmd = HAL::timeInMilliseconds(); +} + +#if !NONLINEAR_SYSTEM +#if DISTORTION_CORRECTION + /* Special version which adds distortion correction to z. Gets called from queueCartesianMove if needed. */ + void PrintLine::queueCartesianSegmentTo(uint8_t check_endstops, uint8_t pathOptimize) { + + // Correct the bumps + Printer::zCorrectionStepsIncluded = Printer::distortion.correct(Printer::destinationSteps[X_AXIS],Printer::destinationSteps[Y_AXIS],Printer::destinationSteps[Z_AXIS]); + Printer::destinationSteps[Z_AXIS] += Printer::zCorrectionStepsIncluded; +#if DEBUG_DISTORTION + Com::printF(PSTR("zCorr:"),Printer::zCorrectionStepsIncluded*Printer::invAxisStepsPerMM[Z_AXIS],3); + Com::printF(PSTR(" atX:"),Printer::destinationSteps[0]*Printer::invAxisStepsPerMM[X_AXIS]); + Com::printFLN(PSTR(" atY:"),Printer::destinationSteps[1]*Printer::invAxisStepsPerMM[Y_AXIS]); +#endif + PrintLine::waitForXFreeLines(1); + uint8_t newPath = PrintLine::insertWaitMovesIfNeeded(pathOptimize, 0); + PrintLine *p = PrintLine::getNextWriteLine(); + + float axis_diff[E_AXIS_ARRAY]; // Axis movement in mm + p->flags = (check_endstops ? FLAG_CHECK_ENDSTOPS : 0); + #if MIXING_EXTRUDER + if(Printer::isAllEMotors()) { + p->flags |= FLAG_ALL_E_MOTORS; + } + #endif + p->joinFlags = 0; + if(!pathOptimize) p->setEndSpeedFixed(true); + p->dir = 0; + Printer::constrainDestinationCoords(); + //Find direction + Printer::zCorrectionStepsIncluded = 0; + for(uint8_t axis = 0; axis < 4; axis++) + { + p->delta[axis] = Printer::destinationSteps[axis] - Printer::currentPositionSteps[axis]; + p->secondSpeed = Printer::fanSpeed; + if(axis == E_AXIS) + { + if(Printer::mode == PRINTER_MODE_FFF) + { + Printer::extrudeMultiplyError += (static_cast(p->delta[E_AXIS]) * Printer::extrusionFactor); + p->delta[E_AXIS] = static_cast(Printer::extrudeMultiplyError); + Printer::extrudeMultiplyError -= p->delta[E_AXIS]; + Printer::filamentPrinted += p->delta[E_AXIS] * Printer::invAxisStepsPerMM[axis]; + } + #if defined(SUPPORT_LASER) && SUPPORT_LASER + else if(Printer::mode == PRINTER_MODE_LASER) + { + p->secondSpeed = ((p->delta[X_AXIS] != 0 || p->delta[Y_AXIS] != 0) && (LaserDriver::laserOn || p->delta[E_AXIS] != 0) ? LaserDriver::intensity : 0); + p->delta[E_AXIS] = 0; + } + #endif + } + if(p->delta[axis] >= 0) + p->setPositiveDirectionForAxis(axis); + else + p->delta[axis] = -p->delta[axis]; + axis_diff[axis] = p->delta[axis] * Printer::invAxisStepsPerMM[axis]; + if(p->delta[axis]) p->setMoveOfAxis(axis); + Printer::currentPositionSteps[axis] = Printer::destinationSteps[axis]; + } + if(p->isNoMove()) + { + if(newPath) // need to delete dummy elements, otherwise commands can get locked. + PrintLine::resetPathPlanner(); + return; // No steps included + } + float xydist2; + #if ENABLE_BACKLASH_COMPENSATION + if((p->isXYZMove()) && ((p->dir & XYZ_DIRPOS)^(Printer::backlashDir & XYZ_DIRPOS)) & (Printer::backlashDir >> 3)) // We need to compensate backlash, add a move + { + PrintLine::waitForXFreeLines(2); + uint8_t wpos2 = PrintLine::linesWritePos + 1; + if(wpos2 >= PRINTLINE_CACHE_SIZE) wpos2 = 0; + PrintLine *p2 = &PrintLine::lines[wpos2]; + memcpy(p2,p,sizeof(PrintLine)); // Move current data to p2 + uint8_t changed = (p->dir & XYZ_DIRPOS)^(Printer::backlashDir & XYZ_DIRPOS); + float back_diff[4]; // Axis movement in mm + back_diff[E_AXIS] = 0; + back_diff[X_AXIS] = (changed & 1 ? (p->isXPositiveMove() ? Printer::backlashX : -Printer::backlashX) : 0); + back_diff[Y_AXIS] = (changed & 2 ? (p->isYPositiveMove() ? Printer::backlashY : -Printer::backlashY) : 0); + back_diff[Z_AXIS] = (changed & 4 ? (p->isZPositiveMove() ? Printer::backlashZ : -Printer::backlashZ) : 0); + p->dir &= XYZ_DIRPOS; // x,y and z are already correct + for(uint8_t i = 0; i < 4; i++) + { + float f = back_diff[i]*Printer::axisStepsPerMM[i]; + p->delta[i] = abs((long)f); + if(p->delta[i]) p->dir |= XSTEP << i; + } + //Define variables that are needed for the Bresenham algorithm. Please note that Z is not currently included in the Bresenham algorithm. + if(p->delta[Y_AXIS] > p->delta[X_AXIS] && p->delta[Y_AXIS] > p->delta[Z_AXIS]) p->primaryAxis = Y_AXIS; + else if (p->delta[X_AXIS] > p->delta[Z_AXIS] ) p->primaryAxis = X_AXIS; + else p->primaryAxis = Z_AXIS; + p->stepsRemaining = p->delta[p->primaryAxis]; + //Feedrate calc based on XYZ travel distance + xydist2 = back_diff[X_AXIS] * back_diff[X_AXIS] + back_diff[Y_AXIS] * back_diff[Y_AXIS]; + if(p->isZMove()) + p->distance = sqrt(xydist2 + back_diff[Z_AXIS] * back_diff[Z_AXIS]); + else + p->distance = sqrt(xydist2); + // 56 seems to be xstep|ystep|e_posdir which just seems odd + Printer::backlashDir = (Printer::backlashDir & 56) | (p2->dir & XYZ_DIRPOS); + p->calculateMove(back_diff,pathOptimize); + p = p2; // use saved instance for the real move + } + #endif + + //Define variables that are needed for the Bresenham algorithm. Please note that Z is not currently included in the Bresenham algorithm. + if(p->delta[Y_AXIS] > p->delta[X_AXIS] && p->delta[Y_AXIS] > p->delta[Z_AXIS] && p->delta[Y_AXIS] > p->delta[E_AXIS]) p->primaryAxis = Y_AXIS; + else if (p->delta[X_AXIS] > p->delta[Z_AXIS] && p->delta[X_AXIS] > p->delta[E_AXIS]) p->primaryAxis = X_AXIS; + else if (p->delta[Z_AXIS] > p->delta[E_AXIS]) p->primaryAxis = Z_AXIS; + else p->primaryAxis = E_AXIS; + p->stepsRemaining = p->delta[p->primaryAxis]; + if(p->isXYZMove()) + { + xydist2 = axis_diff[X_AXIS] * axis_diff[X_AXIS] + axis_diff[Y_AXIS] * axis_diff[Y_AXIS]; + if(p->isZMove()) + p->distance = RMath::max((float)sqrt(xydist2 + axis_diff[Z_AXIS] * axis_diff[Z_AXIS]),fabs(axis_diff[E_AXIS])); + else + p->distance = RMath::max((float)sqrt(xydist2),fabs(axis_diff[E_AXIS])); + } + else + p->distance = fabs(axis_diff[E_AXIS]); + p->calculateMove(axis_diff,pathOptimize); + + } +#endif +/** + Put a move to the current destination coordinates into the movement cache. + If the cache is full, the method will wait, until a place gets free. During + wait communication and temperature control is enabled. + @param check_endstops Read endstop during move. +*/ +void PrintLine::queueCartesianMove(uint8_t check_endstops, uint8_t pathOptimize) +{ + Printer::unsetAllSteppersDisabled(); +#if DISTORTION_CORRECTION + if(Printer::distortion.isEnabled() && Printer::destinationSteps[Z_AXIS] < Printer::distortion.zMaxSteps() && Printer::isZProbingActive() == false && !Printer::isHoming()) { + // we are inside correction height so we split all moves in lines of max. 10 mm and add them + // including a z correction + int32_t deltas[E_AXIS_ARRAY],start[E_AXIS_ARRAY]; + for(fast8_t i = 0;i < E_AXIS_ARRAY;i++) { + deltas[i] = Printer::destinationSteps[i] - Printer::currentPositionSteps[i]; + start[i] = Printer::currentPositionSteps[i]; + } + float dx = Printer::invAxisStepsPerMM[X_AXIS] * deltas[X_AXIS]; + float dy = Printer::invAxisStepsPerMM[Y_AXIS] * deltas[Y_AXIS]; + float len = dx * dx + dy * dy; + if(len < 100) { // no splitting required + queueCartesianSegmentTo(check_endstops, pathOptimize); + return; + } + // we need to split longer lines to follow bed curvature + len = sqrt(len); + int segments = (static_cast(len) + 9) / 10; +#if DEBUG_DISTORTION + Com::printF(PSTR("Split line len:"),len);Com::printFLN(PSTR(" segments:"),segments); +#endif + for(int i = 1; i <= segments; i++) { + for(fast8_t j = 0; j < E_AXIS_ARRAY; j++) { + Printer::destinationSteps[j] = start[j] + (i * deltas[j]) / segments; + } + queueCartesianSegmentTo(check_endstops, pathOptimize); + } + return; + } +#endif + waitForXFreeLines(1); + uint8_t newPath = insertWaitMovesIfNeeded(pathOptimize, 0); + PrintLine *p = getNextWriteLine(); + + float axis_diff[E_AXIS_ARRAY]; // Axis movement in mm + p->flags = (check_endstops ? FLAG_CHECK_ENDSTOPS : 0); +#if MIXING_EXTRUDER + if(Printer::isAllEMotors()) { + p->flags |= FLAG_ALL_E_MOTORS; + } +#endif + p->joinFlags = 0; + if(!pathOptimize) p->setEndSpeedFixed(true); + p->dir = 0; + Printer::constrainDestinationCoords(); + //Find direction + Printer::zCorrectionStepsIncluded = 0; + for(uint8_t axis = 0; axis < 4; axis++) + { + p->delta[axis] = Printer::destinationSteps[axis] - Printer::currentPositionSteps[axis]; + p->secondSpeed = Printer::fanSpeed; + if(axis == E_AXIS) + { + if(Printer::mode == PRINTER_MODE_FFF) + { + Printer::extrudeMultiplyError += (static_cast(p->delta[E_AXIS]) * Printer::extrusionFactor); + p->delta[E_AXIS] = static_cast(Printer::extrudeMultiplyError); + Printer::extrudeMultiplyError -= p->delta[E_AXIS]; + Printer::filamentPrinted += p->delta[E_AXIS] * Printer::invAxisStepsPerMM[axis]; + } +#if defined(SUPPORT_LASER) && SUPPORT_LASER + else if(Printer::mode == PRINTER_MODE_LASER) + { + p->secondSpeed = ((p->delta[X_AXIS] != 0 || p->delta[Y_AXIS] != 0) && (LaserDriver::laserOn || p->delta[E_AXIS] != 0) ? LaserDriver::intensity : 0); + p->delta[E_AXIS] = 0; + } +#endif + } + if(p->delta[axis] >= 0) + p->setPositiveDirectionForAxis(axis); + else + p->delta[axis] = -p->delta[axis]; + axis_diff[axis] = p->delta[axis] * Printer::invAxisStepsPerMM[axis]; + if(p->delta[axis]) p->setMoveOfAxis(axis); + Printer::currentPositionSteps[axis] = Printer::destinationSteps[axis]; + } + if(p->isNoMove()) + { + if(newPath) // need to delete dummy elements, otherwise commands can get locked. + resetPathPlanner(); + return; // No steps included + } + float xydist2; +#if ENABLE_BACKLASH_COMPENSATION + if((p->isXYZMove()) && ((p->dir & XYZ_DIRPOS)^(Printer::backlashDir & XYZ_DIRPOS)) & (Printer::backlashDir >> 3)) // We need to compensate backlash, add a move + { + waitForXFreeLines(2); + uint8_t wpos2 = linesWritePos + 1; + if(wpos2 >= PRINTLINE_CACHE_SIZE) wpos2 = 0; + PrintLine *p2 = &lines[wpos2]; + memcpy(p2,p,sizeof(PrintLine)); // Move current data to p2 + uint8_t changed = (p->dir & XYZ_DIRPOS)^(Printer::backlashDir & XYZ_DIRPOS); + float back_diff[4]; // Axis movement in mm + back_diff[E_AXIS] = 0; + back_diff[X_AXIS] = (changed & 1 ? (p->isXPositiveMove() ? Printer::backlashX : -Printer::backlashX) : 0); + back_diff[Y_AXIS] = (changed & 2 ? (p->isYPositiveMove() ? Printer::backlashY : -Printer::backlashY) : 0); + back_diff[Z_AXIS] = (changed & 4 ? (p->isZPositiveMove() ? Printer::backlashZ : -Printer::backlashZ) : 0); + p->dir &= XYZ_DIRPOS; // x,y and z are already correct + for(uint8_t i = 0; i < 4; i++) + { + float f = back_diff[i]*Printer::axisStepsPerMM[i]; + p->delta[i] = abs((long)f); + if(p->delta[i]) p->dir |= XSTEP << i; + } + //Define variables that are needed for the Bresenham algorithm. Please note that Z is not currently included in the Bresenham algorithm. + if(p->delta[Y_AXIS] > p->delta[X_AXIS] && p->delta[Y_AXIS] > p->delta[Z_AXIS]) p->primaryAxis = Y_AXIS; + else if (p->delta[X_AXIS] > p->delta[Z_AXIS] ) p->primaryAxis = X_AXIS; + else p->primaryAxis = Z_AXIS; + p->stepsRemaining = p->delta[p->primaryAxis]; + //Feedrate calc based on XYZ travel distance + xydist2 = back_diff[X_AXIS] * back_diff[X_AXIS] + back_diff[Y_AXIS] * back_diff[Y_AXIS]; + if(p->isZMove()) + p->distance = sqrt(xydist2 + back_diff[Z_AXIS] * back_diff[Z_AXIS]); + else + p->distance = sqrt(xydist2); + // 56 seems to be xstep|ystep|e_posdir which just seems odd + Printer::backlashDir = (Printer::backlashDir & 56) | (p2->dir & XYZ_DIRPOS); + p->calculateMove(back_diff,pathOptimize); + p = p2; // use saved instance for the real move + } +#endif + + //Define variables that are needed for the Bresenham algorithm. Please note that Z is not currently included in the Bresenham algorithm. + if(p->delta[Y_AXIS] > p->delta[X_AXIS] && p->delta[Y_AXIS] > p->delta[Z_AXIS] && p->delta[Y_AXIS] > p->delta[E_AXIS]) p->primaryAxis = Y_AXIS; + else if (p->delta[X_AXIS] > p->delta[Z_AXIS] && p->delta[X_AXIS] > p->delta[E_AXIS]) p->primaryAxis = X_AXIS; + else if (p->delta[Z_AXIS] > p->delta[E_AXIS]) p->primaryAxis = Z_AXIS; + else p->primaryAxis = E_AXIS; + p->stepsRemaining = p->delta[p->primaryAxis]; + if(p->isXYZMove()) + { + xydist2 = axis_diff[X_AXIS] * axis_diff[X_AXIS] + axis_diff[Y_AXIS] * axis_diff[Y_AXIS]; + if(p->isZMove()) + p->distance = RMath::max((float)sqrt(xydist2 + axis_diff[Z_AXIS] * axis_diff[Z_AXIS]),fabs(axis_diff[E_AXIS])); + else + p->distance = RMath::max((float)sqrt(xydist2),fabs(axis_diff[E_AXIS])); + } + else + p->distance = fabs(axis_diff[E_AXIS]); + p->calculateMove(axis_diff,pathOptimize); +} +#endif + +void PrintLine::calculateMove(float axis_diff[], uint8_t pathOptimize) +{ +#if NONLINEAR_SYSTEM + long axisInterval[VIRTUAL_AXIS_ARRAY]; // shortest interval possible for that axis +#else + long axisInterval[E_AXIS_ARRAY]; +#endif + float timeForMove = (float)(F_CPU)*distance / (isXOrYMove() ? RMath::max(Printer::minimumSpeed, Printer::feedrate) : Printer::feedrate); // time is in ticks + //bool critical = Printer::isZProbingActive(); + if(linesCount < MOVE_CACHE_LOW && timeForMove < LOW_TICKS_PER_MOVE) // Limit speed to keep cache full. + { + //Com::printF(PSTR("L:"),(int)linesCount); + //Com::printF(PSTR(" Old "),timeForMove); + timeForMove += (3 * (LOW_TICKS_PER_MOVE - timeForMove)) / (linesCount + 1); // Increase time if queue gets empty. Add more time if queue gets smaller. + //Com::printFLN(PSTR("Slow "),timeForMove); + //critical = true; + } + timeInTicks = timeForMove; + UI_MEDIUM; // do check encoder + // Compute the slowest allowed interval (ticks/step), so maximum feedrate is not violated + long limitInterval = timeForMove / stepsRemaining; // until not violated by other constraints it is your target speed + if(isXMove()) + { + axisInterval[X_AXIS] = fabs(axis_diff[X_AXIS]) * F_CPU / (Printer::maxFeedrate[X_AXIS] * stepsRemaining); // mm*ticks/s/(mm/s*steps) = ticks/step +#if !NONLINEAR_SYSTEM + limitInterval = RMath::max(axisInterval[X_AXIS], limitInterval); +#endif + } + else axisInterval[X_AXIS] = 0; + if(isYMove()) + { + axisInterval[Y_AXIS] = fabs(axis_diff[Y_AXIS]) * F_CPU / (Printer::maxFeedrate[Y_AXIS] * stepsRemaining); +#if !NONLINEAR_SYSTEM + limitInterval = RMath::max(axisInterval[Y_AXIS], limitInterval); +#endif + } + else axisInterval[Y_AXIS] = 0; + if(isZMove()) // normally no move in z direction + { + axisInterval[Z_AXIS] = fabs(axis_diff[Z_AXIS]) * (float)F_CPU / (float)(Printer::maxFeedrate[Z_AXIS] * stepsRemaining); // must prevent overflow! +#if !NONLINEAR_SYSTEM + limitInterval = RMath::max(axisInterval[Z_AXIS], limitInterval); +#endif + } + else axisInterval[Z_AXIS] = 0; + if(isEMove()) + { + axisInterval[E_AXIS] = fabs(axis_diff[E_AXIS]) * F_CPU / (Printer::maxFeedrate[E_AXIS] * stepsRemaining); +#if !NONLINEAR_SYSTEM + limitInterval = RMath::max(axisInterval[E_AXIS], limitInterval); +#endif + } + else axisInterval[E_AXIS] = 0; +#if NONLINEAR_SYSTEM + if(axis_diff[VIRTUAL_AXIS] >= 0) + axisInterval[VIRTUAL_AXIS] = fabs(axis_diff[VIRTUAL_AXIS]) * F_CPU / (Printer::maxFeedrate[Z_AXIS] * stepsRemaining); + else + axisInterval[VIRTUAL_AXIS] = fabs(axis_diff[VIRTUAL_AXIS]) * F_CPU / (Printer::maxFeedrate[E_AXIS] * stepsRemaining); + limitInterval = RMath::max(axisInterval[VIRTUAL_AXIS], limitInterval); +#endif + + fullInterval = limitInterval = limitInterval > LIMIT_INTERVAL ? limitInterval : LIMIT_INTERVAL; // This is our target speed + // new time at full speed = limitInterval*p->stepsRemaining [ticks] + timeForMove = (float)limitInterval * (float)stepsRemaining; // for large z-distance this overflows with long computation + float inv_time_s = (float)F_CPU / timeForMove; + if(isXMove()) + { + axisInterval[X_AXIS] = timeForMove / delta[X_AXIS]; + speedX = axis_diff[X_AXIS] * inv_time_s; + if(isXNegativeMove()) speedX = -speedX; + } + else speedX = 0; + if(isYMove()) + { + axisInterval[Y_AXIS] = timeForMove / delta[Y_AXIS]; + speedY = axis_diff[Y_AXIS] * inv_time_s; + if(isYNegativeMove()) speedY = -speedY; + } + else speedY = 0; + if(isZMove()) + { + axisInterval[Z_AXIS] = timeForMove / delta[Z_AXIS]; + speedZ = axis_diff[Z_AXIS] * inv_time_s; + if(isZNegativeMove()) speedZ = -speedZ; + } + else speedZ = 0; + if(isEMove()) + { + axisInterval[E_AXIS] = timeForMove / delta[E_AXIS]; + speedE = axis_diff[E_AXIS] * inv_time_s; + if(isENegativeMove()) speedE = -speedE; + } +#if NONLINEAR_SYSTEM + axisInterval[VIRTUAL_AXIS] = limitInterval; //timeForMove/stepsRemaining; +#endif + fullSpeed = distance * inv_time_s; + //long interval = axis_interval[primary_axis]; // time for every step in ticks with full speed + //If acceleration is enabled, do some Bresenham calculations depending on which axis will lead it. +#if RAMP_ACCELERATION + // slowest time to accelerate from v0 to limitInterval determines used acceleration + // t = (v_end-v_start)/a + float slowest_axis_plateau_time_repro = 1e15; // repro to reduce division Unit: 1/s + uint32_t *accel = (isEPositiveMove() ? Printer::maxPrintAccelerationStepsPerSquareSecond : Printer::maxTravelAccelerationStepsPerSquareSecond); +#if defined(INTERPOLATE_ACCELERATION_WITH_Z) && INTERPOLATE_ACCELERATION_WITH_Z != 0 + uint32_t newAccel[4]; + float accelFac = 100.0 + (EEPROM::accelarationFactorTop() - 100.0) * Printer::currentPosition[Z_AXIS] / Printer::zLength; +#if INTERPOLATE_ACCELERATION_WITH_Z == 1 || INTERPOLATE_ACCELERATION_WITH_Z == 3 + newAccel[X_AXIS] = static_cast(accel[X_AXIS] * accelFac) / 100; + newAccel[Y_AXIS] = static_cast(accel[Y_AXIS] * accelFac) / 100; +#else + newAccel[X_AXIS] = accel[X_AXIS]; + newAccel[Y_AXIS] = accel[Y_AXIS]; +#endif +#if INTERPOLATE_ACCELERATION_WITH_Z == 2 || INTERPOLATE_ACCELERATION_WITH_Z == 3 + newAccel[Z_AXIS] = static_cast(accel[Z_AXIS] * accelFac) / 100; +#else + newAccel[Z_AXIS] = accel[Z_AXIS]; +#endif + newAccel[E_AXIS] = accel[E_AXIS]; + accel = newAccel; +#endif + for(uint8_t i = 0; i < 4 ; i++) + { + if(isMoveOfAxis(i)) + // v = a * t => t = v/a = F_CPU/(c*a) => 1/t = c*a/F_CPU + slowest_axis_plateau_time_repro = RMath::min(slowest_axis_plateau_time_repro, (float)axisInterval[i] * (float)accel[i]); // steps/s^2 * step/tick Ticks/s^2 + } + + // Errors for delta move are initialized in timer (except extruder) +#if !NONLINEAR_SYSTEM + error[X_AXIS] = error[Y_AXIS] = error[Z_AXIS] = delta[primaryAxis] >> 1; +#endif +#if NONLINEAR_SYSTEM + error[E_AXIS] = stepsRemaining >> 1; +#endif + invFullSpeed = 1.0 / fullSpeed; + accelerationPrim = slowest_axis_plateau_time_repro / axisInterval[primaryAxis]; // a = v/t = F_CPU/(c*t): Steps/s^2 + //Now we can calculate the new primary axis acceleration, so that the slowest axis max acceleration is not violated + fAcceleration = 262144.0 * (float)accelerationPrim / F_CPU; // will overflow without float! + accelerationDistance2 = 2.0 * distance * slowest_axis_plateau_time_repro * fullSpeed/((float)F_CPU); // mm^2/s^2 + startSpeed = endSpeed = minSpeed = safeSpeed(); + // Can accelerate to full speed within the line + if (startSpeed * startSpeed + accelerationDistance2 >= fullSpeed * fullSpeed) + setNominalMove(); + + vMax = F_CPU / fullInterval; // maximum steps per second, we can reach + // if(p->vMax>46000) // gets overflow in N computation + // p->vMax = 46000; + //p->plateauN = (p->vMax*p->vMax/p->accelerationPrim)>>1; +#if USE_ADVANCE + if(!isXYZMove() || !isEMove()) + { +#if ENABLE_QUADRATIC_ADVANCE + advanceRate = 0; // No head move or E move only or sucking filament back + advanceFull = 0; +#endif + advanceL = 0; + } + else + { + float advlin = fabs(speedE) * Extruder::current->advanceL * 0.001 * Printer::axisStepsPerMM[E_AXIS]; + advanceL = (uint16_t)((65536L * advlin)/vMax); //advanceLscaled = (65536*vE*k2)/vMax +#if ENABLE_QUADRATIC_ADVANCE + advanceFull = 65536*Extruder::current->advanceK * speedE * speedE; // Steps*65536 at full speed + long steps = (HAL::U16SquaredToU32(vMax)) / (accelerationPrim << 1); // v^2/(2*a) = steps needed to accelerate from 0-vMax + advanceRate = advanceFull / steps; + if((advanceFull >> 16) > maxadv) + { + maxadv = (advanceFull >> 16); + maxadvspeed = fabs(speedE); + } +#endif + if(advlin > maxadv2) + { + maxadv2 = advlin; + maxadvspeed = fabs(speedE); + } + } +#endif + UI_MEDIUM; // do check encoder + updateTrapezoids(); + // how much steps on primary axis do we need to reach target feedrate + //p->plateauSteps = (long) (((float)p->acceleration *0.5f / slowest_axis_plateau_time_repro + p->vMin) *1.01f/slowest_axis_plateau_time_repro); +#else +#if USE_ADVANCE +#if ENABLE_QUADRATIC_ADVANCE + advanceRate = 0; // No advance for constant speeds + advanceFull = 0; +#endif +#endif +#endif + +#ifdef DEBUG_STEPCOUNT +// Set in delta move calculation +#if !NONLINEAR_SYSTEM + totalStepsRemaining = delta[X_AXIS] + delta[Y_AXIS] + delta[Z_AXIS]; +#endif +#endif +#ifdef DEBUG_QUEUE_MOVE + if(Printer::debugEcho()) + { + logLine(); + Com::printFLN(Com::tDBGLimitInterval, limitInterval); + Com::printFLN(Com::tDBGMoveDistance, distance); + Com::printFLN(Com::tDBGCommandedFeedrate, Printer::feedrate); + Com::printFLN(Com::tDBGConstFullSpeedMoveTime, timeForMove); + } +#endif + // Make result permanent + if (pathOptimize) waitRelax = 70; + pushLine(); + DEBUG_MEMORY; +} + +/** +This is the path planner. + +It goes from the last entry and tries to increase the end speed of previous moves in a fashion that the maximum jerk +is never exceeded. If a segment with reached maximum speed is met, the planner stops. Everything left from this +is already optimal from previous updates. +The first 2 entries in the queue are not checked. The first is the one that is already in print and the following will likely to become active. + +The method is called before lines_count is increased! +*/ +void PrintLine::updateTrapezoids() +{ + ufast8_t first = linesWritePos; + PrintLine *firstLine; + PrintLine *act = &lines[linesWritePos]; + InterruptProtectedBlock noInts; + + // First we find out how far back we could go with optimization. + + ufast8_t maxfirst = linesPos; // first non fixed segment we might change + if(maxfirst != linesWritePos) + nextPlannerIndex(maxfirst); // don't touch the line printing + // Now ignore enough segments to gain enough time for path planning + millis_t timeleft = 0; + // Skip as many stored moves as needed to gain enough time for computation +#if PRINTLINE_CACHE_SIZE < 10 +#define minTime 4500L * PRINTLINE_CACHE_SIZE +#else +#define minTime 45000L +#endif + while(timeleft < minTime && maxfirst != linesWritePos) + { + timeleft += lines[maxfirst].timeInTicks; + nextPlannerIndex(maxfirst); + } + // Search last fixed element + while(first != maxfirst && !lines[first].isEndSpeedFixed()) + previousPlannerIndex(first); + if(first != linesWritePos && lines[first].isEndSpeedFixed()) + nextPlannerIndex(first); + // now first points to last segment before the end speed is fixed + // so start speed is also fixed. + + if(first == linesWritePos) // Nothing to plan, only new element present + { + act->block(); // Prevent steppe rinterrupt from using this + noInts.unprotect(); + act->setStartSpeedFixed(true); + act->updateStepsParameter(); + act->unblock(); + return; + } + // now we have at least one additional move for optimization + // that is not a wait move + // First is now the new element or the first element with non fixed end speed. + // anyhow, the start speed of first is fixed + firstLine = &lines[first]; + firstLine->block(); // don't let printer touch this or following segments during update + noInts.unprotect(); + ufast8_t previousIndex = linesWritePos; + previousPlannerIndex(previousIndex); + PrintLine *previous = &lines[previousIndex]; // segment before the one we are inserting +#if DRIVE_SYSTEM != DELTA + // filters z-move<->not z-move + if((previous->primaryAxis == Z_AXIS && act->primaryAxis != Z_AXIS) || (previous->primaryAxis != Z_AXIS && act->primaryAxis == Z_AXIS)) + { + previous->setEndSpeedFixed(true); + act->setStartSpeedFixed(true); + act->updateStepsParameter(); + firstLine->unblock(); + return; + } +#endif // DRIVE_SYSTEM + + if(previous->isEOnlyMove() != act->isEOnlyMove()) + { + previous->maxJunctionSpeed = previous->endSpeed; + previous->setEndSpeedFixed(true); + act->setStartSpeedFixed(true); + act->updateStepsParameter(); + firstLine->unblock(); + return; + } + else + { + computeMaxJunctionSpeed(previous, act); // Set maximum junction speed if we have a real move before + } + // Increase speed if possible neglecting current speed + backwardPlanner(linesWritePos,first); + // Reduce speed to reachable speeds + forwardPlanner(first); + + // Update precomputed data + do + { + lines[first].updateStepsParameter(); + //noInts.protect(); + lines[first].unblock(); // start with first block to release next used segment as early as possible + nextPlannerIndex(first); + lines[first].block(); + //noInts.unprotect(); + } + while(first != linesWritePos); + act->updateStepsParameter(); + act->unblock(); +} + +/* Computes the maximum junction speed of the newly added segment under +optimal conditions. There is no guarantee that the previous move will be able to reach the +speed at all, but if it could exceed it will never exceed this theoretical limit. + +if you define ALTERNATIVE_JERK teh new jerk computations are used. These +use the cosine of the angle and the maximum speed +Jerk = (1-cos(alpha))*min(v1,v2) +This sets jerk to 0 on zero angle change. + + Old New +0°: 0 0 +30°: 51,8 13.4 +45°: 76.53 29.3 +90°: 141 100 +180°: 200 200 + + +von 100 auf 200 + Old New(min) New(max) +0°: 100 0 0 +30°: 123,9 13.4 26.8 +45°: 147.3 29.3 58.6 +90°: 223 100 200 +180°: 300 200 400 + +*/ +inline void PrintLine::computeMaxJunctionSpeed(PrintLine *previous, PrintLine *current) +{ +#if NONLINEAR_SYSTEM + if (previous->moveID == current->moveID) // Avoid computing junction speed for split delta lines + { + if(previous->fullSpeed > current->fullSpeed) + previous->maxJunctionSpeed = current->fullSpeed; + else + previous->maxJunctionSpeed = previous->fullSpeed; + return; + } +#endif +#if USE_ADVANCE + if(Printer::isAdvanceActivated()) + { + // if we start/stop extrusion we need to do so with lowest possible end speed + // or advance would leave a drolling extruder and can not adjust fast enough. + if(previous->isEMove() != current->isEMove()) + { + previous->setEndSpeedFixed(true); + current->setStartSpeedFixed(true); + previous->endSpeed = current->startSpeed = previous->maxJunctionSpeed = RMath::min(previous->endSpeed, current->startSpeed); + previous->invalidateParameter(); + current->invalidateParameter(); + return; + } + } +#endif // USE_ADVANCE + // if we are here we have to identical move types + // either pure extrusion -> pure extrusion or + // move -> move (with or without extrusion) + // First we compute the normalized jerk for speed 1 + float factor = 1.0; + float maxJoinSpeed = RMath::min(current->fullSpeed,previous->fullSpeed); +#if (DRIVE_SYSTEM == DELTA) // No point computing Z Jerk separately for delta moves +#ifdef ALTERNATIVE_JERK + float jerk = maxJoinSpeed * (1.0 - (current->speedX * previous->speedX + current->speedY * previous->speedY + current->speedZ * previous->speedZ) / (current->fullSpeed * previous->fullSpeed)); +#else + float dx = current->speedX - previous->speedX; + float dy = current->speedY - previous->speedY; + float dz = current->speedZ - previous->speedZ; + float jerk = sqrt(dx * dx + dy * dy + dz * dz); +#endif // ALTERNATIVE_JERK +#else // DELTA +#ifdef ALTERNATIVE_JERK + float jerk = maxJoinSpeed * (1.0 - (current->speedX * previous->speedX + current->speedY * previous->speedY + current->speedZ * previous->speedZ) / (current->fullSpeed * previous->fullSpeed)); +#else + float dx = current->speedX - previous->speedX; + float dy = current->speedY - previous->speedY; + float jerk = sqrt(dx * dx + dy * dy); +#endif // ALTERNATIVE_JERK +#endif // DELTA + if(jerk > Printer::maxJerk) + factor = Printer::maxJerk / jerk; // always < 1.0! +#if DRIVE_SYSTEM != DELTA + if((previous->dir | current->dir) & ZSTEP) + { + float dz = fabs(current->speedZ - previous->speedZ); + if(dz > Printer::maxZJerk) + factor = RMath::min(factor, Printer::maxZJerk / dz); + } +#endif + float eJerk = fabs(current->speedE - previous->speedE); + if(eJerk > Extruder::current->maxStartFeedrate) + factor = RMath::min(factor, Extruder::current->maxStartFeedrate / eJerk); + + previous->maxJunctionSpeed = maxJoinSpeed * factor; // set speed limit +#ifdef DEBUG_QUEUE_MOVE + if(Printer::debugEcho()) + { + Com::printF(PSTR("ID:"), (int)previous); + Com::printFLN(PSTR(" MJ:"), previous->maxJunctionSpeed); + } +#endif // DEBUG_QUEUE_MOVE +} + +/** Update parameter used by updateTrapezoids + +Computes the acceleration/decelleration steps and advanced parameter associated. +*/ +void PrintLine::updateStepsParameter() +{ + if(areParameterUpToDate() || isWarmUp()) return; + float startFactor = startSpeed * invFullSpeed; + float endFactor = endSpeed * invFullSpeed; + vStart = vMax * startFactor; //starting speed + vEnd = vMax * endFactor; +#if CPU_ARCH == ARCH_AVR + uint32_t vmax2 = HAL::U16SquaredToU32(vMax); + accelSteps = ((vmax2 - HAL::U16SquaredToU32(vStart)) / (accelerationPrim << 1)) + 1; // Always add 1 for missing precision + decelSteps = ((vmax2 - HAL::U16SquaredToU32(vEnd)) /(accelerationPrim << 1)) + 1; +#else + uint64_t vmax2 = static_cast(vMax) * static_cast(vMax); + accelSteps = ((vmax2 - static_cast(vStart) * static_cast(vStart)) / (accelerationPrim << 1)) + 1; // Always add 1 for missing precision + decelSteps = ((vmax2 - static_cast(vEnd) * static_cast(vEnd)) / (accelerationPrim << 1)) + 1; +#endif + +#if USE_ADVANCE +#if ENABLE_QUADRATIC_ADVANCE + advanceStart = (float)advanceFull * startFactor * startFactor; + advanceEnd = (float)advanceFull * endFactor * endFactor; +#endif +#endif + if(accelSteps + decelSteps >= stepsRemaining) // can't reach limit speed + { + uint16_t red = (accelSteps + decelSteps + 2 - stepsRemaining) >> 1; + accelSteps = accelSteps - RMath::min(accelSteps, red); + decelSteps = decelSteps - RMath::min(decelSteps, red); + } + setParameterUpToDate(); +#ifdef DEBUG_QUEUE_MOVE + if(Printer::debugEcho()) + { + Com::printFLN(Com::tDBGId,(int)this); + Com::printF(Com::tDBGVStartEnd,(long)vStart); + Com::printFLN(Com::tSlash,(long)vEnd); + Com::printF(Com::tDBAccelSteps,(long)accelSteps); + Com::printF(Com::tSlash,(long)decelSteps); + Com::printFLN(Com::tSlash,(long)stepsRemaining); + Com::printF(Com::tDBGStartEndSpeed,startSpeed,1); + Com::printFLN(Com::tSlash,endSpeed,1); + Com::printFLN(Com::tDBGFlags,(uint32_t)flags); + Com::printFLN(Com::tDBGJoinFlags,(uint32_t)joinFlags); + } +#endif +} + +/** +Compute the maximum speed from the last entered move. +The backwards planner traverses the moves from last to first looking at deceleration. The RHS of the accelerate/decelerate ramp. + +start = last line inserted +last = last element until we check +*/ +inline void PrintLine::backwardPlanner(ufast8_t start,ufast8_t last) +{ + PrintLine *act = &lines[start], *previous; + float lastJunctionSpeed = act->endSpeed; // Start always with safe speed + + //PREVIOUS_PLANNER_INDEX(last); // Last element is already fixed in start speed + while(start != last) + { + previousPlannerIndex(start); + previous = &lines[start]; + previous->block(); + // Avoid speed calc once crusing in split delta move +#if NONLINEAR_SYSTEM + if (previous->moveID == act->moveID && lastJunctionSpeed == previous->maxJunctionSpeed) + { + act->startSpeed = RMath::max(act->minSpeed, previous->endSpeed = lastJunctionSpeed); + previous->invalidateParameter(); + act->invalidateParameter(); + } +#endif + + /* if(prev->isEndSpeedFixed()) // Nothing to update from here on, happens when path optimize disabled + { + act->setStartSpeedFixed(true); + return; + }*/ + + // Avoid speed calcs if we know we can accelerate within the line + lastJunctionSpeed = (act->isNominalMove() ? act->fullSpeed : sqrt(lastJunctionSpeed * lastJunctionSpeed + act->accelerationDistance2)); // acceleration is acceleration*distance*2! What can be reached if we try? + // If that speed is more that the maximum junction speed allowed then ... + if(lastJunctionSpeed >= previous->maxJunctionSpeed) // Limit is reached + { + // If the previous line's end speed has not been updated to maximum speed then do it now + if(previous->endSpeed != previous->maxJunctionSpeed) + { + previous->invalidateParameter(); // Needs recomputation + previous->endSpeed = RMath::max(previous->minSpeed, previous->maxJunctionSpeed); // possibly unneeded??? + } + // If actual line start speed has not been updated to maximum speed then do it now + if(act->startSpeed != previous->maxJunctionSpeed) + { + act->startSpeed = RMath::max(act->minSpeed, previous->maxJunctionSpeed); // possibly unneeded??? + act->invalidateParameter(); + } + lastJunctionSpeed = previous->endSpeed; + } + else + { + // Block prev end and act start as calculated speed and recalculate plateau speeds (which could move the speed higher again) + act->startSpeed = RMath::max(act->minSpeed, lastJunctionSpeed); + lastJunctionSpeed = previous->endSpeed = RMath::max(lastJunctionSpeed, previous->minSpeed); + previous->invalidateParameter(); + act->invalidateParameter(); + } + act = previous; + } // while loop +} + +void PrintLine::forwardPlanner(ufast8_t first) +{ + PrintLine *act; + PrintLine *next = &lines[first]; + float vmaxRight; + float leftSpeed = next->startSpeed; + while(first != linesWritePos) // All except last segment, which has fixed end speed + { + act = next; + nextPlannerIndex(first); + next = &lines[first]; + /* if(act->isEndSpeedFixed()) + { + leftSpeed = act->endSpeed; + continue; // Nothing to do here + }*/ + // Avoid speed calc once crusing in split delta move +#if NONLINEAR_SYSTEM + if (act->moveID == next->moveID && act->endSpeed == act->maxJunctionSpeed) + { + act->startSpeed = leftSpeed; + leftSpeed = act->endSpeed; + act->setEndSpeedFixed(true); + next->setStartSpeedFixed(true); + continue; + } +#endif + // Avoid speed calcs if we know we can accelerate within the line. + vmaxRight = (act->isNominalMove() ? act->fullSpeed : sqrt(leftSpeed * leftSpeed + act->accelerationDistance2)); + if(vmaxRight > act->endSpeed) // Could be higher next run? + { + if(leftSpeed < act->minSpeed) + { + leftSpeed = act->minSpeed; + act->endSpeed = sqrt(leftSpeed * leftSpeed + act->accelerationDistance2); + } + act->startSpeed = leftSpeed; + next->startSpeed = leftSpeed = RMath::max(RMath::min(act->endSpeed, act->maxJunctionSpeed), next->minSpeed); + if(act->endSpeed == act->maxJunctionSpeed) // Full speed reached, don't compute again! + { + act->setEndSpeedFixed(true); + next->setStartSpeedFixed(true); + } + act->invalidateParameter(); + } + else // We can accelerate full speed without reaching limit, which is as fast as possible. Fix it! + { + act->fixStartAndEndSpeed(); + act->invalidateParameter(); + if(act->minSpeed > leftSpeed) + { + leftSpeed = act->minSpeed; + vmaxRight = sqrt(leftSpeed * leftSpeed + act->accelerationDistance2); + } + act->startSpeed = leftSpeed; + act->endSpeed = RMath::max(act->minSpeed,vmaxRight); + next->startSpeed = leftSpeed = RMath::max(RMath::min(act->endSpeed, act->maxJunctionSpeed), next->minSpeed); + next->setStartSpeedFixed(true); + } + } // While + next->startSpeed = RMath::max(next->minSpeed, leftSpeed); // This is the new segment, which is updated anyway, no extra flag needed. +} + + +inline float PrintLine::safeSpeed() +{ + float safe(Printer::maxJerk * 0.5); +#if DRIVE_SYSTEM != DELTA + if(isZMove()) + { + float mz = Printer::maxZJerk * 0.5; + if(isXOrYMove()) + { + if(fabs(speedZ) > mz) + safe = RMath::min(safe,mz * fullSpeed / fabs(speedZ)); + } + else + { + safe = mz; + } + } +#endif + if(isEMove()) + { + if(isXYZMove()) + safe = RMath::min(safe, 0.5 * Extruder::current->maxStartFeedrate * fullSpeed / fabs(speedE)); + else + safe = 0.5 * Extruder::current->maxStartFeedrate; // This is a retraction move + } + if(DRIVE_SYSTEM == DELTA || primaryAxis == X_AXIS || primaryAxis == Y_AXIS) // enforce minimum speed for numerical stability of explicit speed integration + safe = RMath::max(Printer::minimumSpeed, safe); + else if(primaryAxis == Z_AXIS) + { + safe = RMath::max(Printer::minimumZSpeed, safe); + } + return RMath::min(safe, fullSpeed); +} + + +/** Check if move is new. If it is insert some dummy moves to allow the path optimizer to work since it does +not act on the first two moves in the queue. The stepper timer will spot these moves and leave some time for +processing. +*/ +uint8_t PrintLine::insertWaitMovesIfNeeded(uint8_t pathOptimize, uint8_t waitExtraLines) +{ + if(linesCount == 0 && waitRelax == 0 && pathOptimize) // First line after some time - warm up needed + { + //return 0; +#if NONLINEAR_SYSTEM + uint8_t w = 3; +#else + uint8_t w = 4; +#endif + while(w--) + { + PrintLine *p = getNextWriteLine(); + p->flags = FLAG_WARMUP; + p->joinFlags = FLAG_JOIN_STEPPARAMS_COMPUTED | FLAG_JOIN_END_FIXED | FLAG_JOIN_START_FIXED; + p->dir = 0; + p->setWaitForXLinesFilled(w + waitExtraLines); +#if NONLINEAR_SYSTEM + p->setWaitTicks(300000); +#else + p->setWaitTicks(100000); +#endif // NONLINEAR_SYSTEM + pushLine(); + } + //Com::printFLN(PSTR("InsertWait")); + return 1; + } + return 0; +} + +void PrintLine::logLine() +{ +#ifdef DEBUG_QUEUE_MOVE + Com::printFLN(Com::tDBGId,(int)this); + Com::printArrayFLN(Com::tDBGDelta,delta); + Com::printFLN(Com::tDBGDir,(uint32_t)dir); + Com::printFLN(Com::tDBGFlags,(uint32_t)flags); + Com::printFLN(Com::tDBGFullSpeed,fullSpeed); + Com::printFLN(Com::tDBGVMax,(int32_t)vMax); + Com::printFLN(Com::tDBGAcceleration,accelerationDistance2); + Com::printFLN(Com::tDBGAccelerationPrim,(int32_t)accelerationPrim); + Com::printFLN(Com::tDBGRemainingSteps,stepsRemaining); +#if USE_ADVANCE +#if ENABLE_QUADRATIC_ADVANCE + Com::printFLN(Com::tDBGAdvanceFull,advanceFull >> 16); + Com::printFLN(Com::tDBGAdvanceRate,advanceRate); +#endif +#endif +#endif // DEBUG_QUEUE_MOVE +} + +void PrintLine::waitForXFreeLines(uint8_t b, bool allowMoves) +{ + while(getLinesCount() + b > PRINTLINE_CACHE_SIZE) // wait for a free entry in movement cache + { + GCode::readFromSerial(); + Commands::checkForPeriodicalActions(allowMoves); + } +} + + +#if DRIVE_SYSTEM == DELTA +// pick one for verbose the other silent +#define RETURN_0(s) { Com::printErrorFLN(PSTR(s)); return 0; } +/*#define RETURN_0(s) { Com::print(s " "); SHOWS(temp); SHOWS(opt);\ + SHOWS(cartesianPosSteps[Z_AXIS]);\ + SHOWS(towerAMinSteps); ;\ + SHOWS(deltaPosSteps[A_TOWER]); \ + SHOWS(Printer::deltaAPosYSteps);\ + SHOWS(cartesianPosSteps[Y_AXIS]); \ + SHOW(Printer::deltaDiagonalStepsSquaredA.l); return 0; } + */ +/** + Calculate the delta tower position from a cartesian position + @param cartesianPosSteps Array containing cartesian coordinates. + @param deltaPosSteps Result array with tower coordinates. + @returns 1 if cartesian coordinates have a valid delta tower position 0 if not. +*/ +uint8_t transformCartesianStepsToDeltaSteps(int32_t cartesianPosSteps[], int32_t deltaPosSteps[]) +{ + int32_t zSteps = cartesianPosSteps[Z_AXIS]; +#if DISTORTION_CORRECTION + static int cnt = 0; + static int32_t lastZSteps = 9999999; + static int32_t lastZCorrection = 0; + cnt++; + if(cnt >= DISTORTION_UPDATE_FREQUENCY || lastZSteps != zSteps) + { + cnt = 0; + lastZSteps = zSteps; + lastZCorrection = Printer::distortion.correct(cartesianPosSteps[X_AXIS], cartesianPosSteps[Y_AXIS], cartesianPosSteps[Z_AXIS]); + } + zSteps += lastZCorrection; +#endif + //SHOWA("motion.c transformCart... cartesian ",cartesianPosSteps, 3); + if(Printer::isLargeMachine()) + { +#ifdef SUPPORT_64_BIT_MATH + // 64 bit is better for precision, so we use that if available. + // A TOWER height + uint64_t temp = RMath::absLong(Printer::deltaAPosYSteps - cartesianPosSteps[Y_AXIS]); + uint64_t opt = Printer::deltaDiagonalStepsSquaredA.L; + + temp *= temp; + if (opt < temp) + RETURN_0("Apos y square "); + opt -= temp; + + temp = RMath::absLong(Printer::deltaAPosXSteps - cartesianPosSteps[X_AXIS]); + temp *= temp; + if (opt < temp) + RETURN_0("Apos x square "); + + deltaPosSteps[A_TOWER] = HAL::integer64Sqrt(opt - temp) + zSteps; + if (deltaPosSteps[A_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) + RETURN_0("A hit floor"); + + // B TOWER height + temp = RMath::absLong(Printer::deltaBPosYSteps - cartesianPosSteps[Y_AXIS]); + opt = Printer::deltaDiagonalStepsSquaredB.L; + temp *= temp; + if (opt < temp) + RETURN_0("Bpos y square "); + opt -= temp; + + temp = RMath::absLong(Printer::deltaBPosXSteps - cartesianPosSteps[X_AXIS]); + temp *= temp; + if (opt < temp) + RETURN_0("Bpos x square "); + + deltaPosSteps[B_TOWER] = HAL::integer64Sqrt(opt - temp) + zSteps ; + if (deltaPosSteps[B_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) + RETURN_0("B hit floor"); + + // C TOWER height + temp = RMath::absLong(Printer::deltaCPosYSteps - cartesianPosSteps[Y_AXIS]); + opt = Printer::deltaDiagonalStepsSquaredC.L ; + + temp = temp * temp; + if ( opt < temp ) + RETURN_0("Cpos y square "); + opt -= temp; + + temp = RMath::absLong(Printer::deltaCPosXSteps - cartesianPosSteps[X_AXIS]); + temp = temp * temp; + if ( opt < temp ) + RETURN_0("Cpos x square "); + + deltaPosSteps[C_TOWER] = HAL::integer64Sqrt(opt - temp) + zSteps; + if (deltaPosSteps[C_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) + RETURN_0("C hit floor"); +#else + float temp = Printer::deltaAPosYSteps - cartesianPosSteps[Y_AXIS]; + float opt = Printer::deltaDiagonalStepsSquaredA.f - temp * temp; + float temp2 = Printer::deltaAPosXSteps - cartesianPosSteps[X_AXIS]; + if ((temp = opt - temp2 * temp2) >= 0) + deltaPosSteps[A_TOWER] = floor(0.5 + sqrt(temp) + + zSteps); + else + return 0; + if (deltaPosSteps[A_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) return 0; + + temp = Printer::deltaBPosYSteps - cartesianPosSteps[Y_AXIS]; + opt = Printer::deltaDiagonalStepsSquaredB.f - temp * temp; + temp2 = Printer::deltaBPosXSteps - cartesianPosSteps[X_AXIS]; + if ((temp = opt - temp2 * temp2) >= 0) + deltaPosSteps[B_TOWER] = floor(0.5 + sqrt(temp) + + zSteps); + else + return 0; + if (deltaPosSteps[B_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) return 0; + + temp = Printer::deltaCPosYSteps - cartesianPosSteps[Y_AXIS]; + opt = Printer::deltaDiagonalStepsSquaredC.f - temp * temp; + temp2 = Printer::deltaCPosXSteps - cartesianPosSteps[X_AXIS]; + if ((temp = opt - temp2*temp2) >= 0) + deltaPosSteps[C_TOWER] = floor(0.5 + sqrt(temp) + + zSteps); + else + return 0; + if (deltaPosSteps[C_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) return 0; + + return 1; +#endif + } + else + { + // As we are right on the edge of many printers arm lengths, this is rewrittent to use unsigned long + // This allows 52% longer arms to be used without performance penalty + // the code is a bit longer, because we cannot use negative to test for invalid conditions + // Also, previous code did not check for overflow of squared result + // Overflow is also detected as a fault condition + + const uint32_t LIMIT = 65534; // Largest squarable int without overflow; + + // A TOWER height + uint32_t temp = RMath::absLong(Printer::deltaAPosYSteps - cartesianPosSteps[Y_AXIS]); + uint32_t opt = Printer::deltaDiagonalStepsSquaredA.l; + + if (temp > LIMIT) + RETURN_0("Apos y steps "); + temp *= temp; + if (opt < temp) + RETURN_0("Apos y square "); + opt -= temp; + + temp = RMath::absLong(Printer::deltaAPosXSteps - cartesianPosSteps[X_AXIS]); + if (temp > LIMIT) + RETURN_0("Apos x steps "); + temp *= temp; + if (opt < temp) + RETURN_0("Apos x square "); + + deltaPosSteps[A_TOWER] = SQRT(opt-temp) + zSteps; + if (deltaPosSteps[A_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) + RETURN_0("A hit floor"); + + // B TOWER height + temp = RMath::absLong(Printer::deltaBPosYSteps - cartesianPosSteps[Y_AXIS]); + opt = Printer::deltaDiagonalStepsSquaredB.l; + + if (temp > LIMIT) + RETURN_0("Bpos y steps "); + temp *= temp; + if (opt < temp) + RETURN_0("Bpos y square "); + opt -= temp; + + temp = RMath::absLong(Printer::deltaBPosXSteps - cartesianPosSteps[X_AXIS]); + if (temp > LIMIT ) + RETURN_0("Bpos x steps "); + temp *= temp; + if (opt < temp) + RETURN_0("Bpos x square "); + + deltaPosSteps[B_TOWER] = SQRT(opt-temp) + zSteps ; + if (deltaPosSteps[B_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) + RETURN_0("B hit floor"); + + // C TOWER height + temp = RMath::absLong(Printer::deltaCPosYSteps - cartesianPosSteps[Y_AXIS]); + opt = Printer::deltaDiagonalStepsSquaredC.l ; + + if (temp > LIMIT) + RETURN_0("Cpos y steps "); + temp = temp * temp; + if ( opt < temp ) + RETURN_0("Cpos y square "); + opt -= temp; + + temp = RMath::absLong(Printer::deltaCPosXSteps - cartesianPosSteps[X_AXIS]); + if (temp > LIMIT) + RETURN_0("Cpos x steps "); + temp = temp * temp; + if ( opt < temp ) + RETURN_0("Cpos x square "); + + deltaPosSteps[C_TOWER] = SQRT(opt - temp) + zSteps; + if (deltaPosSteps[C_TOWER] < Printer::deltaFloorSafetyMarginSteps && !Printer::isZProbingActive()) + RETURN_0("C hit floor"); + /* + long temp = Printer::deltaAPosYSteps - cartesianPosSteps[Y_AXIS]; + long opt = Printer::deltaDiagonalStepsSquaredA.l - temp * temp; + long temp2 = Printer::deltaAPosXSteps - cartesianPosSteps[X_AXIS]; + if ((temp = opt - temp2 * temp2) >= 0) + #ifdef FAST_INTEGER_SQRT + deltaPosSteps[A_TOWER] = HAL::integerSqrt(temp) + cartesianPosSteps[Z_AXIS]; + #else + deltaPosSteps[A_TOWER] = sqrt(temp) + cartesianPosSteps[Z_AXIS]; + #endif + else + return 0; + + temp = Printer::deltaBPosYSteps - cartesianPosSteps[Y_AXIS]; + opt = Printer::deltaDiagonalStepsSquaredB.l - temp * temp; + temp2 = Printer::deltaBPosXSteps - cartesianPosSteps[X_AXIS]; + if ((temp = opt - temp2*temp2) >= 0) + #ifdef FAST_INTEGER_SQRT + deltaPosSteps[B_TOWER] = HAL::integerSqrt(temp) + cartesianPosSteps[Z_AXIS]; + #else + deltaPosSteps[B_TOWER] = sqrt(temp) + cartesianPosSteps[Z_AXIS]; + #endif + else + return 0; + + temp = Printer::deltaCPosYSteps - cartesianPosSteps[Y_AXIS]; + opt = Printer::deltaDiagonalStepsSquaredC.l - temp * temp; + temp2 = Printer::deltaCPosXSteps - cartesianPosSteps[X_AXIS]; + if ((temp = opt - temp2*temp2) >= 0) + #ifdef FAST_INTEGER_SQRT + deltaPosSteps[C_TOWER] = HAL::integerSqrt(temp) + cartesianPosSteps[Z_AXIS]; + #else + deltaPosSteps[C_TOWER] = sqrt(temp) + cartesianPosSteps[Z_AXIS]; + #endif + else + return 0;*/ + } + return 1; +} +#endif + +#if DRIVE_SYSTEM==TUGA + +/** + Calculate the delta tower position from a cartesian position + @param cartesianPosSteps Array containing cartesian coordinates. + @param deltaPosSteps Result array with tower coordinates. + @returns 1 if cartesian coordinates have a valid delta tower position 0 if not. + + X Y + * * + \ / + \ / + \ / + \/ + / + / + / + / + * Extruder + + +*/ +uint8_t transformCartesianStepsToDeltaSteps(int32_t cartesianPosSteps[], int32_t tugaPosSteps[]) +{ + tugaPosSteps[0] = cartesianPosSteps[0]; + tugaPosSteps[2] = cartesianPosSteps[2]; + int32_t y2 = Printer::deltaBPosXSteps-cartesianPosSteps[1]; + if(Printer::isLargeMachine()) + { + float y2f = (float)y2 * (float)y2; + float temp = Printer::deltaDiagonalStepsSquaredF - y2f; + if(temp < 0) return 0; + tugaPosSteps[1] = tugaPosSteps[0] + sqrt(temp); + } + else + { + y2 = y2*y2; + int32_t temp = Printer::deltaDiagonalStepsSquared - y2; + if(temp < 0) return 0; + tugaPosSteps[1] = tugaPosSteps[0] + HAL::integerSqrt(temp); + } + return 1; +} +#endif + + +#if NONLINEAR_SYSTEM + +void DeltaSegment::checkEndstops(PrintLine *cur,bool checkall) +{ + if(Printer::isZProbingActive()) + { + Endstops::update(); +#if FEATURE_Z_PROBE + if(isZNegativeMove() && Endstops::zProbe()) + { + cur->setXMoveFinished(); + cur->setYMoveFinished(); + cur->setZMoveFinished(); + dir = 0; + Printer::stepsRemainingAtZHit = cur->stepsRemaining; + cur->stepsRemaining = 0; + return; + } +#endif +#if DRIVE_SYSTEM == DELTA + if(isZPositiveMove() && isXPositiveMove() && isYPositiveMove() && Endstops::anyXYZMax()) +#else + if(isZPositiveMove() && Endstops::zMax()) +#endif + { + cur->setXMoveFinished(); + cur->setYMoveFinished(); + cur->setZMoveFinished(); + dir = 0; + Printer::stepsRemainingAtZHit = cur->stepsRemaining; + return; + } + } + if(checkall) + { + if(!Printer::isZProbingActive()) + Endstops::update(); // do not test twice + if(isXPositiveMove() && Endstops::xMax()) + { +#if DRIVE_SYSTEM == DELTA + if(Printer::stepsRemainingAtXHit < 0) + Printer::stepsRemainingAtXHit = cur->stepsRemaining; +#endif + setXMoveFinished(); + cur->setXMoveFinished(); + } + if(isYPositiveMove() && Endstops::yMax()) + { +#if DRIVE_SYSTEM == DELTA + if(Printer::stepsRemainingAtYHit < 0) + Printer::stepsRemainingAtYHit = cur->stepsRemaining; +#endif + setYMoveFinished(); + cur->setYMoveFinished(); + } +#if DRIVE_SYSTEM != DELTA + if(isXNegativeMove() && Endstops::xMin()) + { + setXMoveFinished(); + cur->setXMoveFinished(); + } + if(isYNegativeMove() && Endstops::yMin()) + { + setYMoveFinished(); + cur->setYMoveFinished(); + } +#endif + if(isZPositiveMove() && Endstops::zMax()) + { +#if MAX_HARDWARE_ENDSTOP_Z + if(Printer::stepsRemainingAtZHit) + Printer::stepsRemainingAtZHit = cur->stepsRemaining; +#endif + setZMoveFinished(); + cur->setZMoveFinished(); + } + } + if(isZNegativeMove() && Endstops::zMin()) + { + setZMoveFinished(); + cur->setZMoveFinished(); + } + +} + +void PrintLine::calculateDirectionAndDelta(int32_t difference[], ufast8_t *dir, int32_t delta[]) +{ + *dir = 0; + //Find direction + for(uint8_t i = 0; i < 4; i++) + { + if(difference[i] >= 0) + { + delta[i] = difference[i]; + *dir |= X_DIRPOS << i; + } + else + { + delta[i] = -difference[i]; + } + if(delta[i]) *dir |= XSTEP << i; + } +} +/** + Calculate and cache the delta robot positions of the cartesian move in a line. + @return The largest delta axis move in a single segment + @param p The line to examine. +*/ +inline uint16_t PrintLine::calculateDeltaSubSegments(uint8_t softEndstop) +{ + uint8_t i; + int32_t delta,diff; + int32_t destinationSteps[Z_AXIS_ARRAY], destinationDeltaSteps[TOWER_ARRAY]; + // Save current position +#if (CPU_ARCH == ARCH_AVR) && !EXACT_DELTA_MOVES + for(uint8_t i = 0; i < Z_AXIS_ARRAY; i++) + destinationSteps[i] = Printer::currentPositionSteps[i]; +#else + float dx[Z_AXIS_ARRAY]; + for(int i = 0; i < Z_AXIS_ARRAY; i++) + dx[i] = static_cast(Printer::destinationSteps[i] - Printer::currentPositionSteps[i]) / static_cast(numDeltaSegments); +#endif +// out.println_byte_P(PSTR("Calculate delta segments:"), p->numDeltaSegments); +#ifdef DEBUG_STEPCOUNT + totalStepsRemaining = 0; +#endif + + uint16_t maxAxisMove = 0; + for (int s = numDeltaSegments; s > 0; s--) + { + DeltaSegment *d = &segments[s - 1]; + +#if (CPU_ARCH == ARCH_AVR) && !EXACT_DELTA_MOVES + for(i = 0; i < Z_AXIS_ARRAY; i++) + { + // End of segment in cartesian steps + + // This method generates small waves which get larger with increasing number of delta segments. smaller?? + diff = Printer::destinationSteps[i] - destinationSteps[i]; + if(s == 1) + destinationSteps[i] += diff; + else if(s == 2) + destinationSteps[i] += (diff >> 1); + else if(s == 4) + destinationSteps[i] += (diff >> 2); + else if(diff<0) + destinationSteps[i] -= HAL::Div4U2U(-diff, s); + else + destinationSteps[i] += HAL::Div4U2U(diff, s); + } +#else + float segment = static_cast(numDeltaSegments - s + 1); + for(i = 0; i < Z_AXIS_ARRAY; i++) // End of segment in cartesian steps + // Perfect approximation, but slower, so we limit it to faster processors like arm + destinationSteps[i] = static_cast(floor(0.5 + dx[i] * segment)) + Printer::currentPositionSteps[i]; +#endif + // Verify that delta calc has a solution + if (transformCartesianStepsToDeltaSteps(destinationSteps, destinationDeltaSteps)) + { + d->dir = 0; + if (softEndstop) + { + destinationDeltaSteps[A_TOWER] = RMath::min(destinationDeltaSteps[A_TOWER], Printer::maxDeltaPositionSteps); + destinationDeltaSteps[B_TOWER] = RMath::min(destinationDeltaSteps[B_TOWER], Printer::maxDeltaPositionSteps); + destinationDeltaSteps[C_TOWER] = RMath::min(destinationDeltaSteps[C_TOWER], Printer::maxDeltaPositionSteps); + } + + for(i = 0; i < TOWER_ARRAY; i++) + { + delta = destinationDeltaSteps[i] - Printer::currentDeltaPositionSteps[i]; + if (delta > 0) + { + d->setPositiveMoveOfAxis(i); +#ifdef DEBUG_DELTA_OVERFLOW + if (delta > 65535) + Com::printFLN(Com::tDBGDeltaOverflow, delta); +#endif + d->deltaSteps[i] = static_cast(delta); + } + else + { + d->setMoveOfAxis(i); +#ifdef DEBUG_DELTA_OVERFLOW + if (-delta > 65535) + Com::printFLN(Com::tDBGDeltaOverflow, delta); +#endif + d->deltaSteps[i] = static_cast(-delta); + } +#ifdef DEBUG_STEPCOUNT + totalStepsRemaining += d->deltaSteps[i]; +#endif + maxAxisMove = RMath::max(maxAxisMove,d->deltaSteps[i]); + Printer::currentDeltaPositionSteps[i] = destinationDeltaSteps[i]; + } + } + else + { + // Illegal position - ignore move + Com::printWarningF(Com::tInvalidDeltaCoordinate); + Com::printF(PSTR(" x:"), destinationSteps[X_AXIS]); + Com::printF(PSTR(" y:"), destinationSteps[Y_AXIS]); + Com::printFLN(PSTR(" z:"), destinationSteps[Z_AXIS]); + d->dir = 0; + d->deltaSteps[A_TOWER] = d->deltaSteps[B_TOWER] = d->deltaSteps[C_TOWER] = 0; + return 65535; // flag error + } + } +#ifdef DEBUG_STEPCOUNT +// out.println_long_P(PSTR("initial StepsRemaining:"), p->totalStepsRemaining); +#endif + return maxAxisMove; +} + +uint8_t PrintLine::calculateDistance(float axisDiff[], uint8_t dir, float *distance) +{ + // Calculate distance depending on direction + if(dir & XYZ_STEP) + { + if(dir & XSTEP) + *distance = axisDiff[X_AXIS] * axisDiff[X_AXIS]; + else + *distance = 0; + if(dir & YSTEP) + *distance += axisDiff[Y_AXIS] * axisDiff[Y_AXIS]; + if(dir & ZSTEP) + *distance += axisDiff[Z_AXIS] * axisDiff[Z_AXIS]; + *distance = RMath::max((float)sqrt(*distance),fabs(axisDiff[E_AXIS])); + return 1; + } + else + { + if(dir & ESTEP) + { + *distance = fabs(axisDiff[E_AXIS]); + return 1; + } + *distance = 0; + return 0; + } +} + +#if SOFTWARE_LEVELING +void PrintLine::calculatePlane(int32_t factors[], int32_t p1[], int32_t p2[], int32_t p3[]) +{ + factors[0] = p1[1] * (p2[2] - p3[2]) + p2[1] * (p3[2] - p1[2]) + p3[1] * (p1[2] - p2[2]); + factors[1] = p1[2] * (p2[0] - p3[0]) + p2[2] * (p3[0] - p1[0]) + p3[2] * (p1[0] - p2[0]); + factors[2] = p1[0] * (p2[1] - p3[1]) + p2[0] * (p3[1] - p1[1]) + p3[0] * (p1[1] - p2[1]); + factors[3] = p1[0] * ((p2[1] * p3[2]) - (p3[1] * p2[2])) + p2[0] * ((p3[1] * p1[2]) - (p1[1] * p3[2])) + p3[0] * ((p1[1] * p2[2]) - (p2[1] * p1[2])); +} + +float PrintLine::calcZOffset(int32_t factors[], int32_t pointX, int32_t pointY) +{ + return (factors[3] - factors[X_AXIS] * pointX - factors[Y_AXIS] * pointY) / (float) factors[2]; +} +#endif + +inline void PrintLine::queueEMove(int32_t extrudeDiff,uint8_t check_endstops,uint8_t pathOptimize) +{ + Printer::unsetAllSteppersDisabled(); + waitForXFreeLines(1); + uint8_t newPath = insertWaitMovesIfNeeded(pathOptimize, 1); + PrintLine *p = getNextWriteLine(); + float axisDiff[5]; // Axis movement in mm + if(check_endstops) p->flags = FLAG_CHECK_ENDSTOPS; + else p->flags = 0; +#if MIXING_EXTRUDER + if(Printer::isAllEMotors()) { + p->flags |= FLAG_ALL_E_MOTORS; + } +#endif + p->joinFlags = 0; + if(!pathOptimize) p->setEndSpeedFixed(true); + //Find direction + for(uint8_t i = 0; i < 3; i++) + { + p->delta[i] = 0; + axisDiff[i] = 0; + } + if (extrudeDiff >= 0) + { + p->delta[E_AXIS] = extrudeDiff; + p->dir = E_STEP_DIRPOS; + } + else + { + p->delta[E_AXIS] = -extrudeDiff; + p->dir = ESTEP; + } + Printer::currentPositionSteps[E_AXIS] = Printer::destinationSteps[E_AXIS]; + + p->numDeltaSegments = 0; + //Define variables that are needed for the Bresenham algorithm. Please note that Z is not currently included in the Bresenham algorithm. + p->primaryAxis = E_AXIS; + p->stepsRemaining = p->delta[E_AXIS]; + axisDiff[E_AXIS] = p->distance = p->delta[E_AXIS] * Printer::invAxisStepsPerMM[E_AXIS]; + axisDiff[VIRTUAL_AXIS] = -p->distance; + p->moveID = lastMoveID++; + p->calculateMove(axisDiff,pathOptimize); +} + +/** + Split a line up into a series of lines with at most DELTASEGMENTS_PER_PRINTLINE delta segments. + @param check_endstops Check endstops during the move. + @param pathOptimize Run the path optimizer. + @param delta_step_rate delta step rate in segments per second for the move. +*/ +uint8_t PrintLine::queueDeltaMove(uint8_t check_endstops,uint8_t pathOptimize, uint8_t softEndstop) +{ + //if (softEndstop && Printer::destinationSteps[Z_AXIS] < 0) Printer::destinationSteps[Z_AXIS] = 0; // now constrained at entry level including cylinder test + int32_t difference[E_AXIS_ARRAY]; + float axis_diff[VIRTUAL_AXIS_ARRAY]; // Axis movement in mm. Virtual axis in 4; + uint8_t secondSpeed = Printer::fanSpeed; + for(fast8_t axis = 0; axis < E_AXIS_ARRAY; axis++) + { + difference[axis] = Printer::destinationSteps[axis] - Printer::currentPositionSteps[axis]; + if(axis == E_AXIS) + { + if(Printer::mode == PRINTER_MODE_FFF) + { + Printer::extrudeMultiplyError += (static_cast(difference[E_AXIS]) * Printer::extrusionFactor); + difference[E_AXIS] = static_cast(Printer::extrudeMultiplyError); + Printer::extrudeMultiplyError -= difference[E_AXIS]; + axis_diff[E_AXIS] = difference[E_AXIS] * Printer::invAxisStepsPerMM[E_AXIS]; + Printer::filamentPrinted += axis_diff[E_AXIS]; + axis_diff[E_AXIS] = fabs(axis_diff[E_AXIS]); + } +#if defined(SUPPORT_LASER) && SUPPORT_LASER + else if(Printer::mode == PRINTER_MODE_LASER) + { + secondSpeed = ((axis_diff[X_AXIS] != 0 || axis_diff[Y_AXIS] != 0) && (LaserDriver::laserOn || axis_diff[E_AXIS] != 0) ? LaserDriver::intensity : 0); + axis_diff[E_AXIS] = 0; + } +#endif + } + else + axis_diff[axis] = fabs(difference[axis] * Printer::invAxisStepsPerMM[axis]); + } + + float cartesianDistance; + ufast8_t cartesianDir; + int32_t cartesianDeltaSteps[E_AXIS_ARRAY]; + calculateDirectionAndDelta(difference, &cartesianDir, cartesianDeltaSteps); + if (!calculateDistance(axis_diff, cartesianDir, &cartesianDistance)) + { + // Appears the intent is to do nothing if no distance is detected. + // This apparently is not an error condition, just early exit. + return true; + } + + if (!(cartesianDir & XYZ_STEP)) + { + queueEMove(difference[E_AXIS], check_endstops,pathOptimize); + return true; + } + + int16_t segmentCount; + float feedrate = RMath::min(Printer::feedrate, Printer::maxFeedrate[Z_AXIS]); + if (cartesianDir & XY_STEP) + { + // Compute number of seconds for move and hence number of segments needed + //float seconds = 100 * cartesianDistance / (Printer::feedrate * Printer::feedrateMultiply); multiply in feedrate included + float seconds = cartesianDistance / feedrate; +#ifdef DEBUG_SPLIT + Com::printFLN(Com::tDBGDeltaSeconds, seconds); +#endif + float sps = static_cast((cartesianDir & E_STEP_DIRPOS) == E_STEP_DIRPOS ? Printer::printMovesPerSecond : Printer::travelMovesPerSecond); + segmentCount = RMath::max(1, static_cast(sps * seconds)); +#ifdef DEBUG_SEGMENT_LENGTH + float segDist = cartesianDistance/(float)segmentCount; + if(segDist > Printer::maxRealSegmentLength) + { + Printer::maxRealSegmentLength = segDist; + Com::printFLN("StepsPerSecond:",sps); + Com::printFLN(PSTR("New max. segment length:"),segDist); + } +#endif + //Com::printFLN(PSTR("Segments:"),segmentCount); + } + else + { + // Optimize pure Z axis move. Since a pure Z axis move is linear all we have to watch out for is unsigned integer overuns in + // the queued moves; +#ifdef DEBUG_SPLIT + Com::printFLN(Com::tDBGDeltaZDelta, cartesianDeltaSteps[Z_AXIS]); +#endif + segmentCount = (cartesianDeltaSteps[Z_AXIS] + (uint32_t)65534) / (uint32_t)65535; + } + // Now compute the number of lines needed + int numLines = (segmentCount + DELTASEGMENTS_PER_PRINTLINE - 1) / DELTASEGMENTS_PER_PRINTLINE; + // There could be some error here but it doesn't matter since the number of segments will just be reduced slightly + int segmentsPerLine = segmentCount / numLines; + + int32_t startPosition[E_AXIS_ARRAY], fractionalSteps[E_AXIS_ARRAY]; + if(numLines > 1) + { + for (fast8_t i = 0; i < Z_AXIS_ARRAY; i++) + startPosition[i] = Printer::currentPositionSteps[i]; + startPosition[E_AXIS] = 0; + cartesianDistance /= numLines; + } + +#ifdef DEBUG_SPLIT + Com::printFLN(Com::tDBGDeltaSegments, segmentCount); + Com::printFLN(Com::tDBGDeltaNumLines, numLines); + Com::printFLN(Com::tDBGDeltaSegmentsPerLine, segmentsPerLine); +#endif + Printer::unsetAllSteppersDisabled(); // Motor is enabled now + waitForXFreeLines(1); + + // Insert dummy moves if necessary + // Need to leave at least one slot open for the first split move + insertWaitMovesIfNeeded(pathOptimize, RMath::min(PRINTLINE_CACHE_SIZE - 4, numLines)); + uint32_t oldEDestination = Printer::destinationSteps[E_AXIS]; // flow and volumetric extrusion changed virtual target + Printer::currentPositionSteps[E_AXIS] = 0; + + for (int lineNumber = 1; lineNumber < numLines + 1; lineNumber++) + { + waitForXFreeLines(1); + PrintLine *p = getNextWriteLine(); + // Downside a comparison per loop. Upside one less distance calculation and simpler code. + if (numLines == 1) + { + // p->numDeltaSegments = segmentCount; // not neede, gets overwritten further down + p->dir = cartesianDir; + for (fast8_t i = 0; i < E_AXIS_ARRAY; i++) + { + p->delta[i] = cartesianDeltaSteps[i]; + fractionalSteps[i] = difference[i]; + } + p->distance = cartesianDistance; + } + else + { + for (fast8_t i = 0; i < E_AXIS_ARRAY; i++) + { + Printer::destinationSteps[i] = startPosition[i] + (difference[i] * lineNumber) / numLines; + fractionalSteps[i] = Printer::destinationSteps[i] - Printer::currentPositionSteps[i]; + axis_diff[i] = fabs(fractionalSteps[i] * Printer::invAxisStepsPerMM[i]); + } + calculateDirectionAndDelta(fractionalSteps, &p->dir, p->delta); + p->distance = cartesianDistance; + } + + p->joinFlags = 0; + p->secondSpeed = secondSpeed; + p->moveID = lastMoveID; + + // Only set fixed on last segment + if (lineNumber == numLines && !pathOptimize) + p->setEndSpeedFixed(true); + + p->flags = (check_endstops ? FLAG_CHECK_ENDSTOPS : 0); +#if MIXING_EXTRUDER + if(Printer::isAllEMotors()) { + p->flags |= FLAG_ALL_E_MOTORS; + } +#endif + p->numDeltaSegments = segmentsPerLine; + + uint16_t maxDeltaStep = p->calculateDeltaSubSegments(softEndstop); + if (maxDeltaStep == 65535) + { + Com::printWarningFLN(PSTR("in queueDeltaMove to calculateDeltaSubSegments returns error.")); + return false; + } + +#ifdef DEBUG_SPLIT + Com::printFLN(Com::tDBGDeltaMaxDS, (int32_t)maxDeltaStep); +#endif + int32_t virtual_axis_move = (int32_t)maxDeltaStep * segmentsPerLine; + if (virtual_axis_move == 0 && p->delta[E_AXIS] == 0) + { + if (numLines != 1) + { + Com::printErrorFLN(Com::tDBGDeltaNoMoveinDSegment); + return false; // Line too short in low precision area + } + } + p->primaryAxis = VIRTUAL_AXIS; // Virtual axis will lead bresenham step either way + if (virtual_axis_move > p->delta[E_AXIS]) // Is delta move or E axis leading + { + p->stepsRemaining = virtual_axis_move; + axis_diff[VIRTUAL_AXIS] = p->distance; //virtual_axis_move * Printer::invAxisStepsPerMM[Z_AXIS]; // Steps/unit same as all the towers + // Virtual axis steps per segment + p->numPrimaryStepPerSegment = maxDeltaStep; + } + else + { + // Round up the E move to get something divisible by segment count which is greater than E move + p->numPrimaryStepPerSegment = (p->delta[E_AXIS] + segmentsPerLine - 1) / segmentsPerLine; + p->stepsRemaining = p->numPrimaryStepPerSegment * segmentsPerLine; + axis_diff[VIRTUAL_AXIS] = -p->distance; //p->stepsRemaining * Printer::invAxisStepsPerMM[Z_AXIS]; + } +#ifdef DEBUG_SPLIT + Com::printFLN(Com::tDBGDeltaStepsPerSegment, p->numPrimaryStepPerSegment); + Com::printFLN(Com::tDBGDeltaVirtualAxisSteps, p->stepsRemaining); +#endif + p->calculateMove(axis_diff, pathOptimize); + for (uint8_t i = 0; i < E_AXIS_ARRAY; i++) + { + Printer::currentPositionSteps[i] += fractionalSteps[i]; + } + } + Printer::currentPositionSteps[E_AXIS] = Printer::destinationSteps[E_AXIS] = oldEDestination; + lastMoveID++; // Will wrap at 255 + + return true; // flag success +} + +#endif + +#if ARC_SUPPORT +// Arc function taken from grbl +// The arc is approximated by generating a huge number of tiny, linear segments. The length of each +// segment is configured in settings.mm_per_arc_segment. +void PrintLine::arc(float *position, float *target, float *offset, float radius, uint8_t isclockwise) +{ + // int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled(); + // plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc + float center_axis0 = position[X_AXIS] + offset[X_AXIS]; + float center_axis1 = position[Y_AXIS] + offset[Y_AXIS]; + //float linear_travel = 0; //target[axis_linear] - position[axis_linear]; + float extruder_travel = (Printer::destinationSteps[E_AXIS] - Printer::currentPositionSteps[E_AXIS]) * Printer::invAxisStepsPerMM[E_AXIS]; + float r_axis0 = -offset[0]; // Radius vector from center to current location + float r_axis1 = -offset[1]; + float rt_axis0 = target[0] - center_axis0; + float rt_axis1 = target[1] - center_axis1; + /*long xtarget = Printer::destinationSteps[X_AXIS]; + long ytarget = Printer::destinationSteps[Y_AXIS]; + long ztarget = Printer::destinationSteps[Z_AXIS]; + long etarget = Printer::destinationSteps[E_AXIS]; + */ + // CCW angle between position and target from circle center. Only one atan2() trig computation required. + float angular_travel = atan2(r_axis0 * rt_axis1 - r_axis1 * rt_axis0, r_axis0 * rt_axis0 + r_axis1 * rt_axis1); + if ((!isclockwise && angular_travel <= 0.00001) || (isclockwise && angular_travel < -0.000001)) + { + angular_travel += 2.0f * M_PI; + } + if (isclockwise) + { + angular_travel -= 2.0f * M_PI; + } + + float millimeters_of_travel = fabs(angular_travel)*radius; //hypot(angular_travel*radius, fabs(linear_travel)); + if (millimeters_of_travel < 0.001f) + { + return;// treat as succes because there is nothing to do; + } + //uint16_t segments = (radius>=BIG_ARC_RADIUS ? floor(millimeters_of_travel/MM_PER_ARC_SEGMENT_BIG) : floor(millimeters_of_travel/MM_PER_ARC_SEGMENT)); + // Increase segment size if printing faster then computation speed allows + uint16_t segments = (Printer::feedrate > 60.0f ? floor(millimeters_of_travel / RMath::min(static_cast(MM_PER_ARC_SEGMENT_BIG), Printer::feedrate * 0.01666f * static_cast(MM_PER_ARC_SEGMENT))) : floor(millimeters_of_travel / static_cast(MM_PER_ARC_SEGMENT))); + if(segments == 0) segments = 1; + /* + // Multiply inverse feed_rate to compensate for the fact that this movement is approximated + // by a number of discrete segments. The inverse feed_rate should be correct for the sum of + // all segments. + if (invert_feed_rate) { feed_rate *= segments; } + */ + float theta_per_segment = angular_travel / segments; + //float linear_per_segment = linear_travel/segments; + float extruder_per_segment = extruder_travel / segments; + + /* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, + and phi is the angle of rotation. Based on the solution approach by Jens Geisler. + r_T = [cos(phi) -sin(phi); + sin(phi) cos(phi] * r ; + + For arc generation, the center of the circle is the axis of rotation and the radius vector is + defined from the circle center to the initial position. Each line segment is formed by successive + vector rotations. This requires only two cos() and sin() computations to form the rotation + matrix for the duration of the entire arc. Error may accumulate from numerical round-off, since + all double numbers are single precision on the Arduino. (True double precision will not have + round off issues for CNC applications.) Single precision error can accumulate to be greater than + tool precision in some cases. Therefore, arc path correction is implemented. + + Small angle approximation may be used to reduce computation overhead further. This approximation + holds for everything, but very small circles and large mm_per_arc_segment values. In other words, + theta_per_segment would need to be greater than 0.1 rad and N_ARC_CORRECTION would need to be large + to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for + numerical drift error. N_ARC_CORRECTION may be on the order a hundred(s) before error becomes an + issue for CNC machines with the single precision Arduino calculations. + + This approximation also allows mc_arc to immediately insert a line segment into the planner + without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied + a correction, the planner should have caught up to the lag caused by the initial mc_arc overhead. + This is important when there are successive arc motions. + */ + // Vector rotation matrix values + float cos_T = 1 - 0.5 * theta_per_segment * theta_per_segment; // Small angle approximation + float sin_T = theta_per_segment; + + float arc_target[4]; + float sin_Ti; + float cos_Ti; + float r_axisi; + uint16_t i; + int8_t count = 0; + + // Initialize the linear axis + //arc_target[axis_linear] = position[axis_linear]; + + // Initialize the extruder axis + arc_target[E_AXIS] = Printer::currentPositionSteps[E_AXIS] * Printer::invAxisStepsPerMM[E_AXIS]; + + for (i = 1; i < segments; i++) + { + // Increment (segments-1) + + if((count & 3) == 0) + { + GCode::readFromSerial(); + Commands::checkForPeriodicalActions(false); + UI_MEDIUM; // do check encoder + } + + if (count < N_ARC_CORRECTION) //25 pieces + { + // Apply vector rotation matrix + r_axisi = r_axis0 * sin_T + r_axis1 * cos_T; + r_axis0 = r_axis0 * cos_T - r_axis1 * sin_T; + r_axis1 = r_axisi; + count++; + } + else + { + // Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. + // Compute exact location by applying transformation matrix from initial radius vector(=-offset). + cos_Ti = cos(i * theta_per_segment); + sin_Ti = sin(i * theta_per_segment); + r_axis0 = -offset[0] * cos_Ti + offset[1] * sin_Ti; + r_axis1 = -offset[0] * sin_Ti - offset[1] * cos_Ti; + count = 0; + } + + // Update arc_target location + arc_target[X_AXIS] = center_axis0 + r_axis0; + arc_target[Y_AXIS] = center_axis1 + r_axis1; + //arc_target[axis_linear] += linear_per_segment; + arc_target[E_AXIS] += extruder_per_segment; + Printer::moveToReal(arc_target[X_AXIS],arc_target[Y_AXIS],IGNORE_COORDINATE,arc_target[E_AXIS],IGNORE_COORDINATE); + } + // Ensure last segment arrives at target location. + Printer::moveToReal(target[X_AXIS],target[Y_AXIS],IGNORE_COORDINATE,target[E_AXIS],IGNORE_COORDINATE); +} +#endif + + + +/** + Moves the stepper motors one step. If the last step is reached, the next movement is started. + The function must be called from a timer loop. It returns the time for the next call. + This is a modified version that implements a bresenham 'multi-step' algorithm where the dominant + cartesian axis steps may be less than the changing dominant delta axis. +*/ +#if NONLINEAR_SYSTEM +int lastblk =- 1; +int32_t cur_errupd; +//#define DEBUG_DELTA_TIMER +// Current delta segment +DeltaSegment *curd; +// Current delta segment primary error increment +int32_t curd_errupd, stepsPerSegRemaining; +int32_t PrintLine::bresenhamStep() // Version for delta printer +{ +#if CPU_ARCH == ARCH_ARM + if(!PrintLine::nlFlag) +#else + if(cur == NULL) +#endif + { + setCurrentLine(); + if(cur->isBlocked()) // This step is in computation - shouldn't happen + { + if(lastblk != (int)cur) + { + HAL::allowInterrupts(); + lastblk = (int)cur; + Com::printFLN(Com::tBLK, (int32_t)linesCount); + } + cur = NULL; +#if CPU_ARCH == ARCH_ARM + PrintLine::nlFlag = false; +#endif + return 2000; + } + HAL::allowInterrupts(); + lastblk = -1; +#if INCLUDE_DEBUG_NO_MOVE + if(Printer::debugNoMoves()) // simulate a move, but do nothing in reality + { + //HAL::forbidInterrupts(); + //deltaSegmentCount -= cur->numDeltaSegments; // should always be zero + removeCurrentLineForbidInterrupt(); + if(linesCount == 0) UI_STATUS_F(Com::translatedF(UI_TEXT_IDLE_ID)); + return 1000; + } +#endif + if(cur->isWarmUp()) + { + // This is a warmup move to initalize the path planner correctly. Just waste + // a bit of time to get the planning up to date. + if(linesCount <= cur->getWaitForXLinesFilled()) + { + cur = NULL; +#if CPU_ARCH==ARCH_ARM + PrintLine::nlFlag = false; +#endif + return 2000; + } + long wait = cur->getWaitTicks(); + removeCurrentLineForbidInterrupt(); + return(wait); // waste some time for path optimization to fill up + } // End if WARMUP +#if FEATURE_Z_PROBE + // z move may consist of mroe then 1 z line segment, so we better ignore them + // if the probe was already hit. + if(Printer::isZProbingActive() && Printer::stepsRemainingAtZHit >= 0) + { + removeCurrentLineForbidInterrupt(); + if(linesCount == 0) UI_STATUS_F(Com::translatedF(UI_TEXT_IDLE_ID)); + return 1000; + } +#endif + + if(cur->isEMove()) Extruder::enable(); + cur->fixStartAndEndSpeed(); + // Set up delta segments + if (cur->numDeltaSegments) + { + + // If there are delta segments point to them here + curd = &cur->segments[--cur->numDeltaSegments]; + // Enable axis - All axis are enabled since they will most probably all be involved in a move + // Since segments could involve different axis this reduces load when switching segments and + // makes disabling easier. + Printer::enableXStepper(); + Printer::enableYStepper(); + Printer::enableZStepper(); + + // Copy across movement into main direction flags so that endstops function correctly + cur->dir |= curd->dir; + // Initialize bresenham for the first segment + cur->error[X_AXIS] = cur->error[Y_AXIS] = cur->error[Z_AXIS] = cur->numPrimaryStepPerSegment >> 1; + curd_errupd = cur->numPrimaryStepPerSegment; + stepsPerSegRemaining = cur->numPrimaryStepPerSegment; + } + else curd = NULL; + cur_errupd = cur->stepsRemaining; + + if(!cur->areParameterUpToDate()) // should never happen, but with bad timings??? + { + cur->updateStepsParameter(); + } + Printer::vMaxReached = cur->vStart; + Printer::stepNumber = 0; + Printer::timer = 0; + HAL::forbidInterrupts(); + //Determine direction of movement + if (curd) + { + Printer::setXDirection(curd->isXPositiveMove()); + Printer::setYDirection(curd->isYPositiveMove()); + Printer::setZDirection(curd->isZPositiveMove()); + } +#if USE_ADVANCE + if(!Printer::isAdvanceActivated()) // Set direction if no advance enabled +#endif + Extruder::setDirection(cur->isEPositiveMove()); +#if defined(DIRECTION_DELAY) && DIRECTION_DELAY > 0 + HAL::delayMicroseconds(DIRECTION_DELAY); +#endif +#if USE_ADVANCE +#if ENABLE_QUADRATIC_ADVANCE + Printer::advanceExecuted = cur->advanceStart; +#endif + cur->updateAdvanceSteps(cur->vStart, 0, false); +#endif + if(Printer::mode == PRINTER_MODE_FFF) { + Printer::setFanSpeedDirectly(cur->secondSpeed); + } +#if defined(SUPPORT_LASER) && SUPPORT_LASER + else if(Printer::mode == PRINTER_MODE_LASER) + { + LaserDriver::changeIntensity(cur->secondSpeed); + } +#endif + return Printer::interval; // Wait an other 50% from last step to make the 100% full + } // End cur=0 + HAL::allowInterrupts(); + + if(curd != NULL) + { + curd->checkEndstops(cur,(cur->isCheckEndstops())); + } + int maxLoops = (Printer::stepsPerTimerCall <= cur->stepsRemaining ? Printer::stepsPerTimerCall : cur->stepsRemaining); + HAL::forbidInterrupts(); + for(int loop = 0; loop < maxLoops; loop++) + { +#if STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY + if(loop > 0) + HAL::delayMicroseconds(STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY); +#endif + if((cur->error[E_AXIS] -= cur->delta[E_AXIS]) < 0) + { +#if USE_ADVANCE + if(Printer::isAdvanceActivated()) // Use interrupt for movement + { + if(cur->isEPositiveMove()) + Printer::extruderStepsNeeded++; + else + Printer::extruderStepsNeeded--; + } + else +#endif + Extruder::step(); + cur->error[E_AXIS] += cur_errupd; + } + if (curd) + { + // Take delta steps + if(curd->isXMove()) + if((cur->error[X_AXIS] -= curd->deltaSteps[A_TOWER]) < 0) + { + cur->startXStep(); + cur->error[X_AXIS] += curd_errupd; +#ifdef DEBUG_REAL_POSITION + Printer::realDeltaPositionSteps[A_TOWER] += curd->isXPositiveMove() ? 1 : -1; +#endif +#ifdef DEBUG_STEPCOUNT + cur->totalStepsRemaining--; +#endif + } + + if(curd->isYMove()) + if((cur->error[Y_AXIS] -= curd->deltaSteps[B_TOWER]) < 0) + { + cur->startYStep(); + cur->error[Y_AXIS] += curd_errupd; +#ifdef DEBUG_REAL_POSITION + Printer::realDeltaPositionSteps[B_TOWER] += curd->isYPositiveMove() ? 1 : -1; +#endif +#ifdef DEBUG_STEPCOUNT + cur->totalStepsRemaining--; +#endif + } + + if(curd->isZMove()) + if((cur->error[Z_AXIS] -= curd->deltaSteps[C_TOWER]) < 0) + { + cur->startZStep(); + cur->error[Z_AXIS] += curd_errupd; + Printer::realDeltaPositionSteps[C_TOWER] += curd->isZPositiveMove() ? 1 : -1; +#ifdef DEBUG_STEPCOUNT + cur->totalStepsRemaining--; +#endif + } + stepsPerSegRemaining--; + if (!stepsPerSegRemaining) + { + if (cur->numDeltaSegments) + { + if(FEATURE_BABYSTEPPING && Printer::zBabystepsMissing/* && curd + && (curd->dir & XYZ_STEP) == XYZ_STEP*/) + { + // execute a extra babystep + //Printer::insertStepperHighDelay(); + //Printer::endXYZSteps(); + //HAL::delayMicroseconds(STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY + 1); + Printer::zBabystep(); + } + // Get the next delta segment + curd = &cur->segments[--cur->numDeltaSegments]; + + // Initialize bresenham for this segment (numPrimaryStepPerSegment is already correct for the half step setting) + cur->error[X_AXIS] = cur->error[Y_AXIS] = cur->error[Z_AXIS] = cur->numPrimaryStepPerSegment >> 1; + + // Reset the counter of the primary steps. This is initialized in the line + // generation so don't have to do this the first time. + stepsPerSegRemaining = cur->numPrimaryStepPerSegment; + + // Change direction if necessary + Printer::setXDirection(curd->dir & X_DIRPOS); + Printer::setYDirection(curd->dir & Y_DIRPOS); + Printer::setZDirection(curd->dir & Z_DIRPOS); +#if defined(DIRECTION_DELAY) && DIRECTION_DELAY > 0 + HAL::delayMicroseconds(DIRECTION_DELAY); +#endif + + } + else + curd = 0;// Release the last segment + //deltaSegmentCount--; + } + } +#if CPU_ARCH != ARCH_AVR + if(loop < maxLoops - 1) + { +#endif + Printer::insertStepperHighDelay(); + Printer::endXYZSteps(); +#if USE_ADVANCE + if(!Printer::isAdvanceActivated()) // Use interrupt for movement +#endif + Extruder::unstep(); +#if CPU_ARCH != ARCH_AVR + } +#endif + } // for loop + + HAL::allowInterrupts(); // Allow interrupts for other types, timer1 is still disabled +#if RAMP_ACCELERATION +//If acceleration is enabled on this move and we are in the acceleration segment, calculate the current interval + if (cur->moveAccelerating()) + { + Printer::vMaxReached = HAL::ComputeV(Printer::timer, cur->fAcceleration) + cur->vStart; + if(Printer::vMaxReached > cur->vMax) Printer::vMaxReached = cur->vMax; + speed_t v = Printer::updateStepsPerTimerCall(Printer::vMaxReached); + Printer::interval = HAL::CPUDivU2(v); + Printer::timer += Printer::interval; + cur->updateAdvanceSteps(Printer::vMaxReached, maxLoops, true); + Printer::stepNumber += maxLoops; // is only used by moveAccelerating + } + else if (cur->moveDecelerating()) // time to slow down + { + speed_t v = HAL::ComputeV(Printer::timer, cur->fAcceleration); + if (v > Printer::vMaxReached) // if deceleration goes too far it can become too large + v = cur->vEnd; + else + { + v = Printer::vMaxReached - v; + if (v < cur->vEnd) v = cur->vEnd; // extra steps at the end of desceleration due to rounding erros + } + cur->updateAdvanceSteps(v, maxLoops, false); + v = Printer::updateStepsPerTimerCall(v); + Printer::interval = HAL::CPUDivU2(v); + Printer::timer += Printer::interval; + } + else + { + // If we had acceleration, we need to use the latest vMaxReached and interval + // If we started full speed, we need to use cur->fullInterval and vMax + cur->updateAdvanceSteps((!cur->accelSteps ? cur->vMax : Printer::vMaxReached), 0, true); + if(!cur->accelSteps) + { + if(cur->vMax > STEP_DOUBLER_FREQUENCY) + { +#if ALLOW_QUADSTEPPING + if(cur->vMax > STEP_DOUBLER_FREQUENCY * 2) + { + Printer::stepsPerTimerCall = 4; + Printer::interval = cur->fullInterval << 2; + } + else + { + Printer::stepsPerTimerCall = 2; + Printer::interval = cur->fullInterval << 1; + } +#else + Printer::stepsPerTimerCall = 2; + Printer::interval = cur->fullInterval << 1; +#endif + } + else + { + Printer::stepsPerTimerCall = 1; + Printer::interval = cur->fullInterval; + } + } + } +#else + Printer::interval = cur->fullInterval; // without RAMPS always use full speed +#endif + PrintLine::cur->stepsRemaining -= maxLoops; + + if(cur->stepsRemaining <= 0 || cur->isNoMove()) // line finished + { + // Release remaining delta segments +#ifdef DEBUG_STEPCOUNT + if(cur->totalStepsRemaining || cur->numDeltaSegments) + { + Com::printFLN(PSTR("Missed steps:"), cur->totalStepsRemaining); + Com::printFLN(PSTR("Step/seg r:"), stepsPerSegRemaining); + Com::printFLN(PSTR("NDS:"), (int) cur->numDeltaSegments); + } +#endif + //HAL::forbidInterrupts(); + //deltaSegmentCount -= cur->numDeltaSegments; // should always be zero + removeCurrentLineForbidInterrupt(); + Printer::disableAllowedStepper(); + if(linesCount == 0) { + UI_STATUS_F(Com::translatedF(UI_TEXT_IDLE_ID)); + if(Printer::mode == PRINTER_MODE_FFF) { + Printer::setFanSpeedDirectly(Printer::fanSpeed); + } +#if defined(SUPPORT_LASER) && SUPPORT_LASER + else if(Printer::mode == PRINTER_MODE_LASER) // Last move disables laser for safety! + { + LaserDriver::changeIntensity(0); + } +#endif + } + Printer::interval >>= 1; // 50% of time to next call to do cur=0 + DEBUG_MEMORY; + } // Do even +#if CPU_ARCH != ARCH_AVR + Printer::insertStepperHighDelay(); + Printer::endXYZSteps(); +#if USE_ADVANCE + if(!Printer::isAdvanceActivated()) // Use interrupt for movement +#endif + Extruder::unstep(); +#endif + return Printer::interval; +} +#else +/** + Moves the stepper motors one step. If the last step is reached, the next movement is started. + The function must be called from a timer loop. It returns the time for the next call. + + Normal non delta algorithm +*/ +int lastblk = -1; +int32_t cur_errupd; +int32_t PrintLine::bresenhamStep() // version for cartesian printer +{ +#if CPU_ARCH == ARCH_ARM + if(!PrintLine::nlFlag) +#else + if(cur == NULL) +#endif + { + ANALYZER_ON(ANALYZER_CH0); + setCurrentLine(); + if(cur->isBlocked()) // This step is in computation - shouldn't happen + { + /*if(lastblk!=(int)cur) // can cause output errors! + { + HAL::allowInterrupts(); + lastblk = (int)cur; + Com::printFLN(Com::tBLK,lines_count); + }*/ + cur = NULL; +#if CPU_ARCH==ARCH_ARM + PrintLine::nlFlag = false; +#endif + return 2000; + } + HAL::allowInterrupts(); + lastblk = -1; +#if INCLUDE_DEBUG_NO_MOVE + if(Printer::debugNoMoves()) // simulate a move, but do nothing in reality + { + removeCurrentLineForbidInterrupt(); + return 1000; + } +#endif + ANALYZER_OFF(ANALYZER_CH0); + if(cur->isWarmUp()) + { + // This is a warmup move to initalize the path planner correctly. Just waste + // a bit of time to get the planning up to date. + if(linesCount<=cur->getWaitForXLinesFilled()) + { + cur = NULL; +#if CPU_ARCH == ARCH_ARM + PrintLine::nlFlag = false; +#endif + return 2000; + } + long wait = cur->getWaitTicks(); + removeCurrentLineForbidInterrupt(); + return(wait); // waste some time for path optimization to fill up + } // End if WARMUP + //Only enable axis that are moving. If the axis doesn't need to move then it can stay disabled depending on configuration. +#if GANTRY +#if DRIVE_SYSTEM == XY_GANTRY || DRIVE_SYSTEM == YX_GANTRY + if(cur->isXOrYMove()) + { + Printer::enableXStepper(); + Printer::enableYStepper(); + } + if(cur->isZMove()) Printer::enableZStepper(); +#else // XZ / ZX Gantry + if(cur->isXOrZMove()) + { + Printer::enableXStepper(); + Printer::enableZStepper(); + } + if(cur->isYMove()) Printer::enableYStepper(); +#endif +#else + if(cur->isXMove()) Printer::enableXStepper(); + if(cur->isYMove()) Printer::enableYStepper(); + if(cur->isZMove()) Printer::enableZStepper(); +#endif + if(cur->isEMove()) Extruder::enable(); + cur->fixStartAndEndSpeed(); + HAL::allowInterrupts(); + cur_errupd = cur->delta[cur->primaryAxis]; + if(!cur->areParameterUpToDate()) // should never happen, but with bad timings??? + { + cur->updateStepsParameter(); + } + Printer::vMaxReached = cur->vStart; + Printer::stepNumber=0; + Printer::timer = 0; + HAL::forbidInterrupts(); + //Determine direction of movement,check if endstop was hit +#if !(GANTRY) + Printer::setXDirection(cur->isXPositiveMove()); + Printer::setYDirection(cur->isYPositiveMove()); + Printer::setZDirection(cur->isZPositiveMove()); +#else // Any gantry type + long gdx = (cur->dir & X_DIRPOS ? cur->delta[X_AXIS] : -cur->delta[X_AXIS]); // Compute signed difference in steps +#if DRIVE_SYSTEM == XY_GANTRY || DRIVE_SYSTEM == YX_GANTRY + Printer::setZDirection(cur->isZPositiveMove()); + long gdy = (cur->dir & Y_DIRPOS ? cur->delta[Y_AXIS] : -cur->delta[Y_AXIS]); + Printer::setXDirection(gdx + gdy >= 0); +#if DRIVE_SYSTEM == XY_GANTRY + Printer::setYDirection(gdx > gdy); +#else + Printer::setYDirection(gdx <= gdy); +#endif +#else // XZ or ZX core + Printer::setYDirection(cur->isYPositiveMove()); + long gdz = (cur->dir & Z_DIRPOS ? cur->delta[Z_AXIS] : -cur->delta[Z_AXIS]); + Printer::setXDirection(gdx + gdz >= 0); +#if DRIVE_SYSTEM == XZ_GANTRY + Printer::setZDirection(gdx > gdz); +#else + Printer::setZDirection(gdx <= gdz); +#endif +#endif // YZ or ZY Gantry +#endif // GANTRY +#if USE_ADVANCE + if(!Printer::isAdvanceActivated()) // Set direction if no advance/OPS enabled +#endif + Extruder::setDirection(cur->isEPositiveMove()); +#if defined(DIRECTION_DELAY) && DIRECTION_DELAY > 0 + HAL::delayMicroseconds(DIRECTION_DELAY); +#endif +#if USE_ADVANCE +#if ENABLE_QUADRATIC_ADVANCE + Printer::advanceExecuted = cur->advanceStart; +#endif + cur->updateAdvanceSteps(cur->vStart, 0, false); +#endif + if(Printer::mode == PRINTER_MODE_FFF) { + Printer::setFanSpeedDirectly(cur->secondSpeed); + } +#if defined(SUPPORT_LASER) && SUPPORT_LASER + else if(Printer::mode == PRINTER_MODE_LASER) + { + LaserDriver::changeIntensity(cur->secondSpeed); + } +#endif + return Printer::interval; // Wait an other 50% from last step to make the 100% full + } // End cur=0 + cur->checkEndstops(); + fast8_t max_loops = Printer::stepsPerTimerCall; + if(cur->stepsRemaining < max_loops) + max_loops = cur->stepsRemaining; + for(fast8_t loop = 0; loop < max_loops; loop++) + { +#if STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY > 0 + if(loop) + HAL::delayMicroseconds(STEPPER_HIGH_DELAY + DOUBLE_STEP_DELAY); +#endif + if((cur->error[E_AXIS] -= cur->delta[E_AXIS]) < 0) + { +#if USE_ADVANCE + if(Printer::isAdvanceActivated()) // Use interrupt for movement + { + if(cur->isEPositiveMove()) + Printer::extruderStepsNeeded++; + else + Printer::extruderStepsNeeded--; + } + else +#endif + Extruder::step(); + cur->error[E_AXIS] += cur_errupd; + } +#if CPU_ARCH == ARCH_AVR + if(cur->isXMove()) +#endif + if((cur->error[X_AXIS] -= cur->delta[X_AXIS]) < 0) + { + cur->startXStep(); + cur->error[X_AXIS] += cur_errupd; + } +#if CPU_ARCH == ARCH_AVR + if(cur->isYMove()) +#endif + if((cur->error[Y_AXIS] -= cur->delta[Y_AXIS]) < 0) + { + cur->startYStep(); + cur->error[Y_AXIS] += cur_errupd; + } +#if CPU_ARCH == ARCH_AVR + if(cur->isZMove()) +#endif + if((cur->error[Z_AXIS] -= cur->delta[Z_AXIS]) < 0) + { + cur->startZStep(); + cur->error[Z_AXIS] += cur_errupd; +#ifdef DEBUG_STEPCOUNT + cur->totalStepsRemaining--; +#endif + } +#if (GANTRY) +#if DRIVE_SYSTEM == XY_GANTRY || DRIVE_SYSTEM == YX_GANTRY + Printer::executeXYGantrySteps(); +#else + Printer::executeXZGantrySteps(); +#endif +#endif + Printer::insertStepperHighDelay(); +#if USE_ADVANCE + if(!Printer::isAdvanceActivated()) // Use interrupt for movement +#endif + cur->stepsRemaining--; + Extruder::unstep(); + Printer::endXYZSteps(); + } // for loop + HAL::allowInterrupts(); // Allow interrupts for other types, timer1 is still disabled +#if RAMP_ACCELERATION + //If acceleration is enabled on this move and we are in the acceleration segment, calculate the current interval + if (cur->moveAccelerating()) // we are accelerating + { + Printer::vMaxReached = HAL::ComputeV(Printer::timer,cur->fAcceleration) + cur->vStart; + if(Printer::vMaxReached > cur->vMax) Printer::vMaxReached = cur->vMax; + unsigned int v = Printer::updateStepsPerTimerCall(Printer::vMaxReached); + Printer::interval = HAL::CPUDivU2(v); + Printer::timer += Printer::interval; + cur->updateAdvanceSteps(Printer::vMaxReached, max_loops, true); + Printer::stepNumber += max_loops; // only used for moveAccelerating + } + else if (cur->moveDecelerating()) // time to slow down + { + unsigned int v = HAL::ComputeV(Printer::timer,cur->fAcceleration); + if (v > Printer::vMaxReached) // if deceleration goes too far it can become too large + v = cur->vEnd; + else + { + v = Printer::vMaxReached - v; + if (vvEnd) v = cur->vEnd; // extra steps at the end of desceleration due to rounding erros + } + cur->updateAdvanceSteps(v,max_loops,false); // needs original v + v = Printer::updateStepsPerTimerCall(v); + Printer::interval = HAL::CPUDivU2(v); + Printer::timer += Printer::interval; + } + else // full speed reached + { + cur->updateAdvanceSteps((!cur->accelSteps ? cur->vMax : Printer::vMaxReached), 0, true); + // constant speed reached + if(cur->vMax > STEP_DOUBLER_FREQUENCY) + { +#if ALLOW_QUADSTEPPING + if(cur->vMax > STEP_DOUBLER_FREQUENCY * 2) + { + Printer::stepsPerTimerCall = 4; + Printer::interval = cur->fullInterval << 2; + } + else + { + Printer::stepsPerTimerCall = 2; + Printer::interval = cur->fullInterval << 1; + } +#else + Printer::stepsPerTimerCall = 2; + Printer::interval = cur->fullInterval << 1; +#endif + } + else + { + Printer::stepsPerTimerCall = 1; + Printer::interval = cur->fullInterval; + } + } +#else + Printer::stepsPerTimerCall = 1; + Printer::interval = cur->fullInterval; // without RAMPS always use full speed +#endif // RAMP_ACCELERATION + long interval = Printer::interval; + if(cur->stepsRemaining <= 0 || cur->isNoMove()) // line finished + { +#ifdef DEBUG_STEPCOUNT + if(cur->totalStepsRemaining) + { + Com::printF(Com::tDBGMissedSteps, cur->totalStepsRemaining); + Com::printFLN(Com::tComma, cur->stepsRemaining); + } +#endif + removeCurrentLineForbidInterrupt(); + Printer::disableAllowedStepper(); + if(linesCount == 0) + { + UI_STATUS_F(Com::translatedF(UI_TEXT_IDLE_ID)); + if(Printer::mode == PRINTER_MODE_FFF) { + Printer::setFanSpeedDirectly(Printer::fanSpeed); + } +#if defined(SUPPORT_LASER) && SUPPORT_LASER + else if(Printer::mode == PRINTER_MODE_LASER) // Last move disables laser for safety! + { + LaserDriver::changeIntensity(0); + } +#endif + } + interval = Printer::interval = interval >> 1; // 50% of time to next call to do cur=0 + DEBUG_MEMORY; + } // Do even + if(FEATURE_BABYSTEPPING && Printer::zBabystepsMissing) + { + HAL::forbidInterrupts(); + Printer::zBabystep(); + } + return interval; +} +#endif diff --git a/Repetier/motion.h b/Repetier/motion.h index 4d1ac26..bbeef81 100644 --- a/Repetier/motion.h +++ b/Repetier/motion.h @@ -1,710 +1,715 @@ -/* - 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 . - - 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. -*/ - -#ifndef MOTION_H_INCLUDED -#define MOTION_H_INCLUDED - -/** 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 NONLINEAR_SYSTEM -// Allow the delta cache to store segments for every line in line cache. Beware this gets big ... fast. -// DELTASEGMENTS_PER_PRINTLINE * -#define DELTA_CACHE_SIZE (DELTASEGMENTS_PER_PRINTLINE * PRINTLINE_CACHE_SIZE) - -class PrintLine; -typedef struct -{ - flag8_t dir; ///< Direction of delta movement. - uint16_t deltaSteps[TOWER_ARRAY]; ///< Number of steps in move. - inline void checkEndstops(PrintLine *cur,bool checkall); - inline void setXMoveFinished() - { - dir &= ~XSTEP; - } - inline void setYMoveFinished() - { - dir &= ~YSTEP; - } - inline void setZMoveFinished() - { - dir &= ~ZSTEP; - } - inline void setXYMoveFinished() - { - dir &= ~XY_STEP; - } - inline bool isXPositiveMove() - { - return (dir & X_STEP_DIRPOS) == X_STEP_DIRPOS; - } - inline bool isXNegativeMove() - { - return (dir & X_STEP_DIRPOS) == XSTEP; - } - inline bool isYPositiveMove() - { - return (dir & Y_STEP_DIRPOS) == Y_STEP_DIRPOS; - } - inline bool isYNegativeMove() - { - return (dir & Y_STEP_DIRPOS) == YSTEP; - } - inline bool isZPositiveMove() - { - return (dir & Z_STEP_DIRPOS) == Z_STEP_DIRPOS; - } - inline bool isZNegativeMove() - { - return (dir & Z_STEP_DIRPOS) == ZSTEP; - } - inline bool isEPositiveMove() - { - return (dir & E_STEP_DIRPOS) == E_STEP_DIRPOS; - } - inline bool isENegativeMove() - { - return (dir & E_STEP_DIRPOS) == ESTEP; - } - inline bool isXMove() - { - return (dir & XSTEP); - } - inline bool isYMove() - { - return (dir & YSTEP); - } - inline bool isXOrYMove() - { - return dir & XY_STEP; - } - inline bool isZMove() - { - return (dir & ZSTEP); - } - inline bool isEMove() - { - return (dir & ESTEP); - } - inline bool isEOnlyMove() - { - return (dir & XYZE_STEP)==ESTEP; - } - inline bool isNoMove() - { - return (dir & XYZE_STEP) == 0; - } - inline bool isXYZMove() - { - return dir & XYZ_STEP; - } - inline bool isMoveOfAxis(uint8_t axis) - { - return (dir & (XSTEP< inside interrupt handle - inline void updateAdvanceSteps(speed_t v, uint8_t max_loops, bool accelerate) - { -#if USE_ADVANCE - if(!Printer::isAdvanceActivated()) return; -#if ENABLE_QUADRATIC_ADVANCE - long advanceTarget = Printer::advanceExecuted; - if(accelerate) - { - for(uint8_t loop = 0; loop < max_loops; loop++) advanceTarget += advanceRate; - if(advanceTarget > advanceFull) - advanceTarget = advanceFull; - } - else - { - for(uint8_t loop = 0; loop < max_loops; loop++) advanceTarget -= advanceRate; - if(advanceTarget < advanceEnd) - advanceTarget = advanceEnd; - } - long h = HAL::mulu16xu16to32(v, advanceL); - int tred = ((advanceTarget + h) >> 16); - HAL::forbidInterrupts(); - Printer::extruderStepsNeeded += tred - Printer::advanceStepsSet; - if(tred > 0 && Printer::advanceStepsSet <= 0) - Printer::extruderStepsNeeded += Extruder::current->advanceBacklash; - else if(tred < 0 && Printer::advanceStepsSet >= 0) - Printer::extruderStepsNeeded -= Extruder::current->advanceBacklash; - Printer::advanceStepsSet = tred; - HAL::allowInterrupts(); - Printer::advanceExecuted = advanceTarget; -#else - int tred = HAL::mulu6xu16shift16(v, advanceL); - HAL::forbidInterrupts(); - Printer::extruderStepsNeeded += tred - Printer::advanceStepsSet; - if(tred > 0 && Printer::advanceStepsSet <= 0) - Printer::extruderStepsNeeded += (Extruder::current->advanceBacklash << 1); - else if(tred < 0 && Printer::advanceStepsSet >= 0) - Printer::extruderStepsNeeded -= (Extruder::current->advanceBacklash << 1); - Printer::advanceStepsSet = tred; - HAL::allowInterrupts(); -#endif -#endif - } - inline bool moveDecelerating() - { - if(stepsRemaining <= decelSteps) - { - if (!(flags & FLAG_DECELERATING)) - { - Printer::timer = 0; - flags |= FLAG_DECELERATING; - } - return true; - } - else return false; - } - inline bool moveAccelerating() - { - return Printer::stepNumber <= accelSteps; - } - inline void startXStep() - { -#if !(GANTRY) - WRITE(X_STEP_PIN,HIGH); -#if FEATURE_TWO_XSTEPPER - WRITE(X2_STEP_PIN,HIGH); -#endif -#else -#if DRIVE_SYSTEM == XY_GANTRY || DRIVE_SYSTEM == XZ_GANTRY - if(isXPositiveMove()) - { - Printer::motorX++; - Printer::motorYorZ++; - } - else - { - Printer::motorX--; - Printer::motorYorZ--; - } -#endif -#if DRIVE_SYSTEM == YX_GANTRY || DRIVE_SYSTEM == ZX_GANTRY - if(isXPositiveMove()) - { - Printer::motorX++; - Printer::motorYorZ--; - } - else - { - Printer::motorX--; - Printer::motorYorZ++; - } -#endif -#endif -#ifdef DEBUG_STEPCOUNT - totalStepsRemaining--; -#endif - - } - inline void startYStep() - { -#if !(GANTRY) || DRIVE_SYSTEM == ZX_GANTRY || DRIVE_SYSTEM == XZ_GANTRY - WRITE(Y_STEP_PIN,HIGH); -#if FEATURE_TWO_YSTEPPER - WRITE(Y2_STEP_PIN,HIGH); -#endif -#else -#if DRIVE_SYSTEM == XY_GANTRY - if(isYPositiveMove()) - { - Printer::motorX++; - Printer::motorYorZ--; - } - else - { - Printer::motorX--; - Printer::motorYorZ++; - } -#endif -#if DRIVE_SYSTEM == YX_GANTRY - if(isYPositiveMove()) - { - Printer::motorX++; - Printer::motorYorZ++; - } - else - { - Printer::motorX--; - Printer::motorYorZ--; - } -#endif -#endif // GANTRY -#ifdef DEBUG_STEPCOUNT - totalStepsRemaining--; -#endif - } - inline void startZStep() - { -#if !(GANTRY) || DRIVE_SYSTEM == YX_GANTRY || DRIVE_SYSTEM == XY_GANTRY - WRITE(Z_STEP_PIN,HIGH); -#if FEATURE_TWO_ZSTEPPER - WRITE(Z2_STEP_PIN,HIGH); -#endif -#else -#if DRIVE_SYSTEM == XZ_GANTRY - if(isYPositiveMove()) - { - Printer::motorX++; - Printer::motorYorZ--; - } - else - { - Printer::motorX--; - Printer::motorYorZ++; - } -#endif -#if DRIVE_SYSTEM == ZX_GANTRY - if(isYPositiveMove()) - { - Printer::motorX++; - Printer::motorYorZ++; - } - else - { - Printer::motorX--; - Printer::motorYorZ--; - } -#endif -#endif - } - void updateStepsParameter(); - inline float safeSpeed(); - void calculateMove(float axis_diff[],uint8_t pathOptimize); - void logLine(); - inline long getWaitTicks() - { - return timeInTicks; - } - inline void setWaitTicks(long wait) - { - timeInTicks = wait; - } - - static inline bool hasLines() - { - return linesCount; - } - static inline void setCurrentLine() - { - cur = &lines[linesPos]; -#if CPU_ARCH==ARCH_ARM - PrintLine::nlFlag = true; -#endif - } - // Only called from within interrupts - static inline void removeCurrentLineForbidInterrupt() - { - linesPos++; - if(linesPos >= PRINTLINE_CACHE_SIZE) linesPos = 0; - cur = NULL; -#if CPU_ARCH == ARCH_ARM - nlFlag = false; -#endif - HAL::forbidInterrupts(); - --linesCount; - if(!linesCount) - Printer::setMenuMode(MENU_MODE_PRINTING, false); - } - static inline void pushLine() - { - linesWritePos++; - if(linesWritePos >= PRINTLINE_CACHE_SIZE) linesWritePos = 0; - Printer::setMenuMode(MENU_MODE_PRINTING, true); - InterruptProtectedBlock noInts; - linesCount++; - } - static uint8_t getLinesCount() - { - InterruptProtectedBlock noInts; - return linesCount; - } - static PrintLine *getNextWriteLine() - { - return &lines[linesWritePos]; - } - static inline void computeMaxJunctionSpeed(PrintLine *previous,PrintLine *current); - static int32_t bresenhamStep(); - static void waitForXFreeLines(uint8_t b=1, bool allowMoves = false); - static inline void forwardPlanner(ufast8_t p); - static inline void backwardPlanner(ufast8_t p,ufast8_t last); - static void updateTrapezoids(); - static uint8_t insertWaitMovesIfNeeded(uint8_t pathOptimize, uint8_t waitExtraLines); - static void queueCartesianMove(uint8_t check_endstops,uint8_t pathOptimize); - static void moveRelativeDistanceInSteps(int32_t x,int32_t y,int32_t z,int32_t e,float feedrate,bool waitEnd,bool check_endstop); - static void moveRelativeDistanceInStepsReal(int32_t x,int32_t y,int32_t z,int32_t e,float feedrate,bool waitEnd); -#if ARC_SUPPORT - static void arc(float *position, float *target, float *offset, float radius, uint8_t isclockwise); -#endif - static inline void previousPlannerIndex(ufast8_t &p) - { - p = (p ? p - 1 : PRINTLINE_CACHE_SIZE - 1); - } - static inline void nextPlannerIndex(ufast8_t& p) - { - p = (p == PRINTLINE_CACHE_SIZE - 1 ? 0 : p + 1); - } -#if NONLINEAR_SYSTEM - static uint8_t queueDeltaMove(uint8_t check_endstops,uint8_t pathOptimize, uint8_t softEndstop); - static inline void queueEMove(int32_t e_diff,uint8_t check_endstops,uint8_t pathOptimize); - inline uint16_t calculateDeltaSubSegments(uint8_t softEndstop); - static inline void calculateDirectionAndDelta(int32_t difference[], ufast8_t *dir, int32_t delta[]); - static inline uint8_t calculateDistance(float axis_diff[], uint8_t dir, float *distance); -#if SOFTWARE_LEVELING && DRIVE_SYSTEM == DELTA - static void calculatePlane(int32_t factors[], int32_t p1[], int32_t p2[], int32_t p3[]); - static float calcZOffset(int32_t factors[], int32_t pointX, int32_t pointY); -#endif -#endif -}; - - - -#endif // MOTION_H_INCLUDED - - +/* + 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 . + + 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. +*/ + +#ifndef MOTION_H_INCLUDED +#define MOTION_H_INCLUDED + +/** 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 // unused +#define FLAG_CHECK_ENDSTOPS 16 +#define FLAG_ALL_E_MOTORS 32 // For mixed extruder move all motors instead of selected motor +#define FLAG_SKIP_DEACCELERATING 64 // unused +#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 NONLINEAR_SYSTEM +// Allow the delta cache to store segments for every line in line cache. Beware this gets big ... fast. +// DELTASEGMENTS_PER_PRINTLINE * +#define DELTA_CACHE_SIZE (DELTASEGMENTS_PER_PRINTLINE * PRINTLINE_CACHE_SIZE) + +class PrintLine; +typedef struct +{ + flag8_t dir; ///< Direction of delta movement. + uint16_t deltaSteps[TOWER_ARRAY]; ///< Number of steps in move. + inline void checkEndstops(PrintLine *cur,bool checkall); + inline void setXMoveFinished() + { + dir &= ~XSTEP; + } + inline void setYMoveFinished() + { + dir &= ~YSTEP; + } + inline void setZMoveFinished() + { + dir &= ~ZSTEP; + } + inline void setXYMoveFinished() + { + dir &= ~XY_STEP; + } + inline bool isXPositiveMove() + { + return (dir & X_STEP_DIRPOS) == X_STEP_DIRPOS; + } + inline bool isXNegativeMove() + { + return (dir & X_STEP_DIRPOS) == XSTEP; + } + inline bool isYPositiveMove() + { + return (dir & Y_STEP_DIRPOS) == Y_STEP_DIRPOS; + } + inline bool isYNegativeMove() + { + return (dir & Y_STEP_DIRPOS) == YSTEP; + } + inline bool isZPositiveMove() + { + return (dir & Z_STEP_DIRPOS) == Z_STEP_DIRPOS; + } + inline bool isZNegativeMove() + { + return (dir & Z_STEP_DIRPOS) == ZSTEP; + } + inline bool isEPositiveMove() + { + return (dir & E_STEP_DIRPOS) == E_STEP_DIRPOS; + } + inline bool isENegativeMove() + { + return (dir & E_STEP_DIRPOS) == ESTEP; + } + inline bool isXMove() + { + return (dir & XSTEP); + } + inline bool isYMove() + { + return (dir & YSTEP); + } + inline bool isXOrYMove() + { + return dir & XY_STEP; + } + inline bool isZMove() + { + return (dir & ZSTEP); + } + inline bool isEMove() + { + return (dir & ESTEP); + } + inline bool isEOnlyMove() + { + return (dir & XYZE_STEP)==ESTEP; + } + inline bool isNoMove() + { + return (dir & XYZE_STEP) == 0; + } + inline bool isXYZMove() + { + return dir & XYZ_STEP; + } + inline bool isMoveOfAxis(uint8_t axis) + { + return (dir & (XSTEP< inside interrupt handle + inline void updateAdvanceSteps(speed_t v, uint8_t max_loops, bool accelerate) + { +#if USE_ADVANCE + if(!Printer::isAdvanceActivated()) return; +#if ENABLE_QUADRATIC_ADVANCE + long advanceTarget = Printer::advanceExecuted; + if(accelerate) + { + for(uint8_t loop = 0; loop < max_loops; loop++) advanceTarget += advanceRate; + if(advanceTarget > advanceFull) + advanceTarget = advanceFull; + } + else + { + for(uint8_t loop = 0; loop < max_loops; loop++) advanceTarget -= advanceRate; + if(advanceTarget < advanceEnd) + advanceTarget = advanceEnd; + } + long h = HAL::mulu16xu16to32(v, advanceL); + int tred = ((advanceTarget + h) >> 16); + HAL::forbidInterrupts(); + Printer::extruderStepsNeeded += tred - Printer::advanceStepsSet; + if(tred > 0 && Printer::advanceStepsSet <= 0) + Printer::extruderStepsNeeded += Extruder::current->advanceBacklash; + else if(tred < 0 && Printer::advanceStepsSet >= 0) + Printer::extruderStepsNeeded -= Extruder::current->advanceBacklash; + Printer::advanceStepsSet = tred; + HAL::allowInterrupts(); + Printer::advanceExecuted = advanceTarget; +#else + int tred = HAL::mulu6xu16shift16(v, advanceL); + HAL::forbidInterrupts(); + Printer::extruderStepsNeeded += tred - Printer::advanceStepsSet; + if(tred > 0 && Printer::advanceStepsSet <= 0) + Printer::extruderStepsNeeded += (Extruder::current->advanceBacklash << 1); + else if(tred < 0 && Printer::advanceStepsSet >= 0) + Printer::extruderStepsNeeded -= (Extruder::current->advanceBacklash << 1); + Printer::advanceStepsSet = tred; + HAL::allowInterrupts(); +#endif +#endif + } + INLINE bool moveDecelerating() + { + if(stepsRemaining <= decelSteps) + { + if (!(flags & FLAG_DECELERATING)) + { + Printer::timer = 0; + flags |= FLAG_DECELERATING; + } + return true; + } + else return false; + } + INLINE bool moveAccelerating() + { + return Printer::stepNumber <= accelSteps; + } + INLINE void startXStep() + { +#if !(GANTRY) + Printer::startXStep(); +#else +#if DRIVE_SYSTEM == XY_GANTRY || DRIVE_SYSTEM == XZ_GANTRY + if(isXPositiveMove()) + { + Printer::motorX++; + Printer::motorYorZ++; + } + else + { + Printer::motorX--; + Printer::motorYorZ--; + } +#endif +#if DRIVE_SYSTEM == YX_GANTRY || DRIVE_SYSTEM == ZX_GANTRY + if(isXPositiveMove()) + { + Printer::motorX++; + Printer::motorYorZ--; + } + else + { + Printer::motorX--; + Printer::motorYorZ++; + } +#endif +#endif +#ifdef DEBUG_STEPCOUNT + totalStepsRemaining--; +#endif + } + INLINE void startYStep() + { +#if !(GANTRY) || DRIVE_SYSTEM == ZX_GANTRY || DRIVE_SYSTEM == XZ_GANTRY + Printer::startYStep(); +#else +#if DRIVE_SYSTEM == XY_GANTRY + if(isYPositiveMove()) + { + Printer::motorX++; + Printer::motorYorZ--; + } + else + { + Printer::motorX--; + Printer::motorYorZ++; + } +#endif +#if DRIVE_SYSTEM == YX_GANTRY + if(isYPositiveMove()) + { + Printer::motorX++; + Printer::motorYorZ++; + } + else + { + Printer::motorX--; + Printer::motorYorZ--; + } +#endif +#endif // GANTRY +#ifdef DEBUG_STEPCOUNT + totalStepsRemaining--; +#endif + + } + INLINE void startZStep() + { +#if !(GANTRY) || DRIVE_SYSTEM == YX_GANTRY || DRIVE_SYSTEM == XY_GANTRY + Printer::startZStep(); +#else +#if DRIVE_SYSTEM == XZ_GANTRY + if(isZPositiveMove()) + { + Printer::motorX++; + Printer::motorYorZ--; + } + else + { + Printer::motorX--; + Printer::motorYorZ++; + } +#endif +#if DRIVE_SYSTEM == ZX_GANTRY + if(isZPositiveMove()) + { + Printer::motorX++; + Printer::motorYorZ++; + } + else + { + Printer::motorX--; + Printer::motorYorZ--; + } +#endif +#endif +#ifdef DEBUG_STEPCOUNT + totalStepsRemaining--; +#endif + } + void updateStepsParameter(); + float safeSpeed(); + void calculateMove(float axis_diff[],uint8_t pathOptimize); + void logLine(); + INLINE long getWaitTicks() + { + return timeInTicks; + } + INLINE void setWaitTicks(long wait) + { + timeInTicks = wait; + } + + static INLINE bool hasLines() + { + return linesCount; + } + static INLINE void setCurrentLine() + { + cur = &lines[linesPos]; +#if CPU_ARCH==ARCH_ARM + PrintLine::nlFlag = true; +#endif + } + // Only called from within interrupts + static INLINE void removeCurrentLineForbidInterrupt() + { + linesPos++; + if(linesPos >= PRINTLINE_CACHE_SIZE) linesPos = 0; + cur = NULL; +#if CPU_ARCH == ARCH_ARM + nlFlag = false; +#endif + HAL::forbidInterrupts(); + --linesCount; + if(!linesCount) + Printer::setMenuMode(MENU_MODE_PRINTING, false); + } + static INLINE void pushLine() + { + linesWritePos++; + if(linesWritePos >= PRINTLINE_CACHE_SIZE) linesWritePos = 0; + Printer::setMenuMode(MENU_MODE_PRINTING, true); + InterruptProtectedBlock noInts; + linesCount++; + } + static uint8_t getLinesCount() + { + InterruptProtectedBlock noInts; + return linesCount; + } + static PrintLine *getNextWriteLine() + { + return &lines[linesWritePos]; + } + static inline void computeMaxJunctionSpeed(PrintLine *previous,PrintLine *current); + static int32_t bresenhamStep(); + static void waitForXFreeLines(uint8_t b=1, bool allowMoves = false); + static inline void forwardPlanner(ufast8_t p); + static inline void backwardPlanner(ufast8_t p,ufast8_t last); + static void updateTrapezoids(); + static uint8_t insertWaitMovesIfNeeded(uint8_t pathOptimize, uint8_t waitExtraLines); +#if NONLINEAR_SYSTEM == 0 + static void queueCartesianMove(uint8_t check_endstops,uint8_t pathOptimize); +#if DISTORTION_CORRECTION + static void queueCartesianSegmentTo(uint8_t check_endstops, uint8_t pathOptimize); +#endif +#endif + static void moveRelativeDistanceInSteps(int32_t x,int32_t y,int32_t z,int32_t e,float feedrate,bool waitEnd,bool check_endstop,bool pathOptimize = true); + static void moveRelativeDistanceInStepsReal(int32_t x,int32_t y,int32_t z,int32_t e,float feedrate,bool waitEnd,bool pathOptimize = true); +#if ARC_SUPPORT + static void arc(float *position, float *target, float *offset, float radius, uint8_t isclockwise); +#endif + static INLINE void previousPlannerIndex(ufast8_t &p) + { + p = (p ? p - 1 : PRINTLINE_CACHE_SIZE - 1); + } + static INLINE void nextPlannerIndex(ufast8_t& p) + { + p = (p == PRINTLINE_CACHE_SIZE - 1 ? 0 : p + 1); + } +#if NONLINEAR_SYSTEM + static uint8_t queueDeltaMove(uint8_t check_endstops,uint8_t pathOptimize, uint8_t softEndstop); + static inline void queueEMove(int32_t e_diff,uint8_t check_endstops,uint8_t pathOptimize); + inline uint16_t calculateDeltaSubSegments(uint8_t softEndstop); + static inline void calculateDirectionAndDelta(int32_t difference[], ufast8_t *dir, int32_t delta[]); + static inline uint8_t calculateDistance(float axis_diff[], uint8_t dir, float *distance); +#if SOFTWARE_LEVELING && DRIVE_SYSTEM == DELTA + static void calculatePlane(int32_t factors[], int32_t p1[], int32_t p2[], int32_t p3[]); + static float calcZOffset(int32_t factors[], int32_t pointX, int32_t pointY); +#endif +#endif +}; + + + +#endif // MOTION_H_INCLUDED diff --git a/Repetier/pins.h b/Repetier/pins.h index fa8bb2b..0455a3b 100644 --- a/Repetier/pins.h +++ b/Repetier/pins.h @@ -82,7 +82,8 @@ STEPPER_CURRENT_CONTROL #define ORIG_PS_ON_PIN 15 #define HEATER_0_PIN 6 -#define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +// MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +#define TEMP_0_PIN 0 #endif @@ -154,7 +155,8 @@ STEPPER_CURRENT_CONTROL #define ORIG_PS_ON_PIN -1 #define HEATER_0_PIN 14 -#define TEMP_0_PIN 4 //D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +//D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +#define TEMP_0_PIN 4 #define HEATER_1_PIN -1 #define TEMP_1_PIN -1 #define HEATER_2_PIN -1 @@ -273,7 +275,8 @@ STEPPER_CURRENT_CONTROL #define ORIG_FAN_PIN -1 #define HEATER_0_PIN -1 -#define TEMP_0_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +// MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +#define TEMP_0_PIN -1 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, @@ -319,8 +322,10 @@ STEPPER_CURRENT_CONTROL #define ORIG_E0_ENABLE_PIN 13 //heaters -#define HEATER_0_PIN 12 // hot end heater -#define HEATER_1_PIN 16 // heated bed heater +// hot end heater +#define HEATER_0_PIN 12 +// heated bed heater +#define HEATER_1_PIN 16 #define HEATER_2_PIN -1 #define TEMP_2_PIN -1 @@ -410,8 +415,9 @@ STEPPER_CURRENT_CONTROL #define HEATER_0_PIN 10 #define HEATER_1_PIN 8 #define HEATER_2_PIN 9 -#define TEMP_0_PIN 13 // ANALOG NUMBERING -#define TEMP_1_PIN 14 // ANALOG NUMBERING +// ANALOG NUMBERING +#define TEMP_0_PIN 13 +#define TEMP_1_PIN 14 #define TEMP_2_PIN 15 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, #define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN, @@ -453,18 +459,19 @@ STEPPER_CURRENT_CONTROL #ifdef RAMPS_V_1_0 // RAMPS_V_1_0 -#define HEATER_0_PIN 12 // RAMPS 1.0 -#define HEATER_1_PIN -1 // RAMPS 1.0 -#define ORIG_FAN_PIN 11 // RAMPS 1.0 +#define HEATER_0_PIN 12 +#define HEATER_1_PIN -1 +#define ORIG_FAN_PIN 11 #else // RAMPS_V_1_1 or RAMPS_V_1_2 -#define HEATER_0_PIN 10 // RAMPS 1.1 -#define HEATER_1_PIN 8 // RAMPS 1.1 -#define ORIG_FAN_PIN 9 // RAMPS 1.1 +#define HEATER_0_PIN 10 +#define HEATER_1_PIN 8 +#define ORIG_FAN_PIN 9 #endif -#define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! -#define TEMP_1_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +// MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +#define TEMP_0_PIN 2 +#define TEMP_1_PIN 1 #endif // SPI for Max6675 Thermocouple @@ -482,19 +489,23 @@ STEPPER_CURRENT_CONTROL #define ORIG_FAN_PIN 4 #define ORIG_FAN2_PIN 5 #define LIGHT_PIN 6 -#define BEEPER_PIN 33 // Activate beeper on extension shield +// Activate beeper on extension shield +#define BEEPER_PIN 33 #define BEEPER_TYPE 1 -#define ORIG_E2_STEP_PIN 27 // Only available with X3 shield -#define ORIG_E2_DIR_PIN 29 // Only available with X3 shield -#define ORIG_E2_ENABLE_PIN 41 // Only available with X3 shield -#define ORIG_E3_STEP_PIN 23 // Only available with X3 shield -#define ORIG_E3_DIR_PIN 25 // Only available with X3 shield -#define ORIG_E3_ENABLE_PIN 40 // Only available with X3 shield -#define HEATER_3_PIN 17 // Only available with X3 shield -#define TEMP_3_PIN 12 // Only available with X3 shield -#define HEATER_4_PIN 16 // Only available with X3 shield -#define TEMP_4_PIN 5 //11 // Only available with X3 shield +// Only available with X3 shield +#define ORIG_E2_STEP_PIN 27 +#define ORIG_E2_DIR_PIN 29 +#define ORIG_E2_ENABLE_PIN 41 +// Only available with X3 shield +#define ORIG_E3_STEP_PIN 23 +#define ORIG_E3_DIR_PIN 25 +#define ORIG_E3_ENABLE_PIN 40 +// Only available with X3 shield +#define HEATER_3_PIN 17 +#define TEMP_3_PIN 12 +#define HEATER_4_PIN 16 +#define TEMP_4_PIN 5 #define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN, @@ -508,10 +519,12 @@ STEPPER_CURRENT_CONTROL #define SDCARDDETECTINVERTED false #define ORIG_SDCARDDETECT 49 #define SDSS 53 +#undef ORIG_FAN_PIN #define ORIG_FAN_PIN 5 #define ORIG_FAN2_PIN 6 #define LIGHT_PIN 11 -#define BEEPER_PIN 33 // Activate beeper on extension shield +// Activate beeper on extension shield +#define BEEPER_PIN 33 #define BEEPER_TYPE 1 #define ORIG_E2_STEP_PIN 23 @@ -524,22 +537,26 @@ STEPPER_CURRENT_CONTROL #define ORIG_E4_DIR_PIN 37 #define ORIG_E4_ENABLE_PIN 42 #define HEATER_0_PIN 10 -#define HEATER_1_PIN 8 // bed +// bed +#define HEATER_1_PIN 8 #define HEATER_2_PIN 9 #define HEATER_3_PIN 16 #define HEATER_4_PIN 17 #define HEATER_5_PIN 4 -#define TEMP_0_PIN 13 // ANALOG NUMBERING -#define TEMP_1_PIN 14 // BED , ANALOG NUMBERING +// ANALOG NUMBERING +#define TEMP_0_PIN 13 +// BED , ANALOG NUMBERING +#define TEMP_1_PIN 14 #define TEMP_2_PIN 15 -#define TEMP_3_PIN 12 // ANALOG NUMBERING -#define TEMP_4_PIN 11 // ANALOG NUMBERING +#define TEMP_3_PIN 12 +#define TEMP_4_PIN 11 #define TEMP_5_PIN 10 -#define TEMP_6_PIN 4 // Thermocouple 1 -#define TEMP_7_PIN 5 // Thermocouple 2 -#define THERMOCOUPLE_0_PIN 4 // Thermocouple 1 -#define THERMOCOUPLE_1_PIN 5 // Thermocouple 2 +// Thermocouple 1 and 2 +#define TEMP_6_PIN 4 +#define TEMP_7_PIN 5 +#define THERMOCOUPLE_0_PIN 4 +#define THERMOCOUPLE_1_PIN 5 #define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN, @@ -577,11 +594,12 @@ STEPPER_CURRENT_CONTROL #define ORIG_Z_MAX_PIN 32 #define ORIG_Z_ENABLE_PIN 35 -#define HEATER_1_PIN 4 // bed + // bed +#define HEATER_1_PIN 4 #define TEMP_1_PIN 10 -#define HEATER_0_PIN 2 //pwm -#define TEMP_0_PIN 8 //analog +#define HEATER_0_PIN 2 +#define TEMP_0_PIN 8 #define HEATER_2_PIN 3 #define TEMP_2_PIN 9 @@ -605,13 +623,15 @@ STEPPER_CURRENT_CONTROL #define ORIG_FAN_PIN 7 #define ORIG_PS_ON_PIN 12 #define KILL_PIN -1 -#define SUICIDE_PIN 54 //PIN that has to be turned on right after start, to keep power flowing. +//PIN that has to be turned on right after start, to keep power flowing. +#define SUICIDE_PIN 54 #define SCK_PIN 52 #define MISO_PIN 50 #define MOSI_PIN 51 #define SDPOWER -1 #define SDSS 53 +#define ORIG_SDCARDDETECT 38 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, #define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN, @@ -633,7 +653,7 @@ STEPPER_CURRENT_CONTROL #define ORIG_X_DIR_PIN 16 #define ORIG_X_ENABLE_PIN 48 #define ORIG_X_MIN_PIN 37 -#define ORIG_X_MAX_PIN 36 //Max endstops default to disabled "-1" +#define ORIG_X_MAX_PIN 36 #define ORIG_Y_STEP_PIN 54 #define ORIG_Y_DIR_PIN 47 @@ -666,17 +686,22 @@ STEPPER_CURRENT_CONTROL #define ORIG_PS_ON_PIN 45 -#define HEATER_0_PIN 2 // EXTRUDER 1 -#define HEATER_2_PIN 3 // EXTRUDER 2 -#define HEATER_3_PIN 6 // EXTRUDER 3 + // EXTRUDER 1 +#define HEATER_0_PIN 2 +// EXTRUDER 2 +#define HEATER_2_PIN 3 +// EXTRUDER 3 +#define HEATER_3_PIN 6 //optional FAN1 can be used as 4th heater output: #define HEATER_4_PIN 8 // EXTRUDER 4 -#define HEATER_1_PIN 9 // BED + // BED +#define HEATER_1_PIN 9 -#define TEMP_0_PIN 15 // ANALOG NUMBERING -#define TEMP_2_PIN 14 // ANALOG NUMBERING -#define TEMP_3_PIN 13 // ANALOG NUMBERING +// ANALOG NUMBERING +#define TEMP_0_PIN 15 +#define TEMP_2_PIN 14 +#define TEMP_3_PIN 13 //optional for extruder 4 or chamber: #define TEMP_2_PIN 12 // ANALOG NUMBERING -#define TEMP_1_PIN 11 // ANALOG NUMBERING +#define TEMP_1_PIN 11 #define SDPOWER -1 #define SDSS 53 @@ -730,7 +755,8 @@ STEPPER_CURRENT_CONTROL #define ORIG_PS_ON_PIN -1 #define HEATER_0_PIN 6 -#define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +// MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +#define TEMP_0_PIN 0 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, #define E1_PINS @@ -770,27 +796,28 @@ STEPPER_CURRENT_CONTROL #define ORIG_Z_MAX_PIN -1 //extruder pins -#define ORIG_E0_STEP_PIN 4 //Edited @ EJE Electronics 20100715 -#define ORIG_E0_DIR_PIN 2 //Edited @ EJE Electronics 20100715 -#define ORIG_E0_ENABLE_PIN 3 //Added @ EJE Electronics 20100715 -#define TEMP_0_PIN 5 //changed @ rkoeppl 20110410 -#define HEATER_0_PIN 14 //changed @ rkoeppl 20110410 +#define ORIG_E0_STEP_PIN 4 +#define ORIG_E0_DIR_PIN 2 +#define ORIG_E0_ENABLE_PIN 3 +#define TEMP_0_PIN 5 +#define HEATER_0_PIN 14 #if MOTHERBOARD == 5 -#define HEATER_1_PIN -1 //changed @ rkoeppl 20110410 -#define TEMP_1_PIN -1 //changed @ rkoeppl 20110410 +#define HEATER_1_PIN -1 +#define TEMP_1_PIN -1 #else -#define HEATER_1_PIN 1 //changed @ rkoeppl 20110410 -#define TEMP_1_PIN 0 //changed @ rkoeppl 20110410 +#define HEATER_1_PIN 1 +#define TEMP_1_PIN 0 #endif #define HEATER_2_PIN -1 #define TEMP_2_PIN -1 #define SDPOWER -1 -#define SDSS 16 // SCL pin of I2C header -#define LED_PIN -1 //changed @ rkoeppl 20110410 -#define ORIG_FAN_PIN -1 //changed @ rkoeppl 20110410 -#define ORIG_PS_ON_PIN -1 //changed @ rkoeppl 20110410 +// SCL pin of I2C header +#define SDSS 16 +#define LED_PIN -1 +#define ORIG_FAN_PIN -1 +#define ORIG_PS_ON_PIN -1 //our pin for debugging. #define DEBUG_PIN 0 @@ -852,11 +879,13 @@ STEPPER_CURRENT_CONTROL #define ORIG_PS_ON_PIN -1 -#define HEATER_0_PIN 13 // (extruder) +// (extruder) +#define HEATER_0_PIN 13 #ifdef SANGUINOLOLU_V_1_2 -#define HEATER_1_PIN 12 // (bed) +// (bed) +#define HEATER_1_PIN 12 #define ORIG_X_ENABLE_PIN 14 #define ORIG_Y_ENABLE_PIN 14 #define ORIG_Z_ENABLE_PIN 26 @@ -872,8 +901,10 @@ STEPPER_CURRENT_CONTROL #endif -#define TEMP_0_PIN 7 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) -#define TEMP_1_PIN 6 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) +// MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) +#define TEMP_0_PIN 7 +// MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) +#define TEMP_1_PIN 6 #define SDPOWER -1 #define SDSS 31 #define SCK_PIN 7 @@ -927,7 +958,8 @@ STEPPER_CURRENT_CONTROL #define ORIG_E0_DIR_PIN 0 #define ORIG_E0_ENABLE_PIN 14 -#define PROBE_PIN -1 //29 on Melzi1284p A2 +//29 on Melzi1284p A2 +#define PROBE_PIN -1 #define LED_PIN 27 @@ -935,22 +967,24 @@ STEPPER_CURRENT_CONTROL #define ORIG_PS_ON_PIN -1 -#define HEATER_0_PIN 13 // (extruder) +// (extruder) +#define HEATER_0_PIN 13 #define HEATER_2_PIN -1 -#ifdef REPRAPPRO_HUXLEY -#define HEATER_1_PIN 10 // bed (change to 10 for gate pin of MOSFET on heated bed) -#else -#define HEATER_1_PIN 12 -#endif +// bed (change to 12 for breakout pin on header) +#define HEATER_1_PIN 10 + #define ORIG_X_ENABLE_PIN 14 #define ORIG_Y_ENABLE_PIN 14 #define ORIG_Z_ENABLE_PIN 26 -#define TEMP_0_PIN 7 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) -#define TEMP_1_PIN 6 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) +// MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) +#define TEMP_0_PIN 7 +// MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) +#define TEMP_1_PIN 6 #define TEMP_2_PIN -1 #define SDPOWER -1 -#define SDSS 31 // 31 http://reprap.org/wiki/Melzi#Melzi_Arduino_Pin_Numbers says 31, schamtic show pin 37 = PA0 which is arduino pin 31! +// 31 http://reprap.org/wiki/Melzi#Melzi_Arduino_Pin_Numbers says 31, schamtic show pin 37 = PA0 which is arduino pin 31! +#define SDSS 31 #define SCK_PIN 7 #define MISO_PIN 6 #define MOSI_PIN 5 @@ -962,6 +996,90 @@ STEPPER_CURRENT_CONTROL #endif +#if MOTHERBOARD == 66 +#define KNOWN_BOARD 1 + +#ifndef __AVR_ATmega2560__ +#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. +#endif + +// X/Y/Z Steppers and MIN endstops verified + +#define ORIG_X_STEP_PIN 54 +#define ORIG_X_DIR_PIN 55 +#define ORIG_X_ENABLE_PIN 38 +#define ORIG_X_MIN_PIN 3 +#define ORIG_X_MAX_PIN -1 + +#define ORIG_Y_STEP_PIN 60 +#define ORIG_Y_DIR_PIN 61 +#define ORIG_Y_ENABLE_PIN 56 +#define ORIG_Y_MIN_PIN 14 +#define ORIG_Y_MAX_PIN -1 + +#define ORIG_Z_STEP_PIN 46 +#define ORIG_Z_DIR_PIN 48 +#define ORIG_Z_ENABLE_PIN 63 +#define ORIG_Z_MIN_PIN 18 +#define ORIG_Z_MAX_PIN -1 + +#define ORIG_E0_STEP_PIN 26 +#define ORIG_E0_DIR_PIN 28 +#define ORIG_E0_ENABLE_PIN 24 + +#define ORIG_E1_STEP_PIN -1 +#define ORIG_E1_DIR_PIN -1 +#define ORIG_E1_ENABLE_PIN -1 + +#define SDPOWER -1 +#define SDSS 25 +#define ORIG_SDCARDDETECT -1 + +#define LED_PIN 13 +#define ORIG_FAN_PIN 8 +#define ORIG_PS_ON_PIN -1 + +// schematic: HEATER1 (Extruder) +#define HEATER_0_PIN 10 +// schematic: HEATER2 (Heated Bed) +#define HEATER_1_PIN 9 +#define HEATER_2_PIN -1 + +// ANALOG NUMBERING +// schematic: THERM1 (Extruder) +#define TEMP_0_PIN 13 +// schematic: THERM2 (Heated Bed) +#define TEMP_1_PIN 14 +#define TEMP_2_PIN -1 + +#define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, +#define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN, + +// following pins (LCD, ENCODER, SDCARD) reverse engineered from schematic diagram: + +#ifdef ULTRA_LCD +#ifdef NEWPANEL + +#define LCD_PINS_RS 27 +#define LCD_PINS_ENABLE 29 +#define LCD_PINS_D4 37 +#define LCD_PINS_D5 35 +#define LCD_PINS_D6 33 +#define LCD_PINS_D7 31 + +#define BTN_EN1 16 +#define BTN_EN2 17 +#define BTN_ENC 23 + +#endif +#endif //ULTRA_LCD + +#define SCK_PIN 52 +#define MISO_PIN 50 +#define MOSI_PIN 51 +#define MAX6675_SS 53 +#endif + /**************************************************************************************** * Gen7 1.1 and above pin assignment * @@ -1089,7 +1207,8 @@ STEPPER_CURRENT_CONTROL #define SDPOWER -1 #define SDSS -1 -#define SDSSORIG 4 // Needs to set this to output to enable SPI even if other SS is used! +// Needs to set this to output to enable SPI even if other SS is used! +#define SDSSORIG 4 #define SCK_PIN 7 #define MISO_PIN 6 @@ -1221,7 +1340,8 @@ STEPPER_CURRENT_CONTROL #define MISO_PIN 6 #define MOSI_PIN 5 -#define ORIG_FAN_PIN 21 //FAN and ATX Power Supply Control Pins +//FAN and ATX Power Supply Control Pins +#define ORIG_FAN_PIN 21 #define ORIG_PS_ON_PIN 15 #define LED_PIN -1 @@ -1247,8 +1367,8 @@ STEPPER_CURRENT_CONTROL #define ORIG_Y_STEP_PIN 30 #define ORIG_Y_DIR_PIN 31 -#define ORIG_Y_ENABLE_PIN 20 //26 -#define ORIG_Y_MIN_PIN 26 // 20 +#define ORIG_Y_ENABLE_PIN 20 +#define ORIG_Y_MIN_PIN 26 #define ORIG_Y_MAX_PIN -1 #define ORIG_Z_STEP_PIN 32 @@ -1261,10 +1381,14 @@ STEPPER_CURRENT_CONTROL #define ORIG_E0_DIR_PIN 35 #define ORIG_E0_ENABLE_PIN 13 -#define TEMP_0_PIN 7 // Extruder - ANALOG PIN NUMBER! -#define TEMP_1_PIN 6 // Bed - ANALOG PIN NUMBER! -#define HEATER_0_PIN 15 // Extruder -#define HEATER_1_PIN 14 // bed +// Extruder - ANALOG PIN NUMBER! +#define TEMP_0_PIN 7 +// Bed - ANALOG PIN NUMBER! +#define TEMP_1_PIN 6 +// Extruder +#define HEATER_0_PIN 15 +// bed +#define HEATER_1_PIN 14 #define HEATER_2_PIN -1 #define TEMP_2_PIN -1 @@ -1315,23 +1439,30 @@ STEPPER_CURRENT_CONTROL #define ORIG_E0_STEP_PIN 34 #define ORIG_E0_DIR_PIN 35 #define ORIG_E0_ENABLE_PIN 12 -#define HEATER_0_PIN 8 // Extruder -#define TEMP_0_PIN 5 // Extruder - ANALOG PIN NUMBER! +// Extruder +#define HEATER_0_PIN 8 +// Extruder - ANALOG PIN NUMBER! +#define TEMP_0_PIN 5 #define ORIG_E1_STEP_PIN 14 #define ORIG_E1_DIR_PIN 13 #define ORIG_E1_ENABLE_PIN 11 -#define HEATER_2_PIN 9 // Extruder -#define TEMP_2_PIN 6 // Extruder - ANALOG PIN NUMBER! +// Extruder +#define HEATER_2_PIN 9 +// Extruder - ANALOG PIN NUMBER! +#define TEMP_2_PIN 6 -#define HEATER_1_PIN 10 // bed -#define TEMP_1_PIN 7 // Bed - ANALOG PIN NUMBER! +// bed +#define HEATER_1_PIN 10 +// Bed - ANALOG PIN NUMBER! +#define TEMP_1_PIN 7 #define SDPOWER -1 #define SDSS 20 #define LED_PIN -1 -#define ORIG_FAN_PIN 16 // Fan +// Fan +#define ORIG_FAN_PIN 16 #define ORIG_PS_ON_PIN -1 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, @@ -1387,7 +1518,8 @@ STEPPER_CURRENT_CONTROL #define ORIG_Y_STEP_PIN 30 #define ORIG_Y_DIR_PIN 31 #define ORIG_Y_ENABLE_PIN 18 -#define ORIG_Y_MIN_PIN 24 // (Was Pin 20 on Rev B-E); Don't use this if you want to use SD card. Use 37 and put the endstop in the e-stop slot!!! +// (Was Pin 20 on Rev B-E); Don't use this if you want to use SD card. Use 37 and put the endstop in the e-stop slot!!! +#define ORIG_Y_MIN_PIN 24 #define ORIG_Y_MAX_PIN -1 #define ORIG_Z_STEP_PIN 32 @@ -1399,18 +1531,24 @@ STEPPER_CURRENT_CONTROL #define ORIG_E0_STEP_PIN 34 #define ORIG_E0_DIR_PIN 35 #define ORIG_E0_ENABLE_PIN 13 -#define TEMP_0_PIN 1 // Extruder - ANALOG PIN NUMBER! -#define TEMP_1_PIN 0 // Bed - ANALOG PIN NUMBER! -#define HEATER_0_PIN 15 // Extruder -#define HEATER_1_PIN 14 // bed +// Extruder - ANALOG PIN NUMBER! +#define TEMP_0_PIN 1 +// Bed - ANALOG PIN NUMBER! +#define TEMP_1_PIN 0 +// Extruder +#define HEATER_0_PIN 15 +// bed +#define HEATER_1_PIN 14 #define HEATER_2_PIN -1 #define TEMP_2_PIN -1 #define SDPOWER -1 -#define SDSS 20 // (Was Pin 26 on Rev. B-E); old value 2 +// (Was Pin 26 on Rev. B-E); old value 2 +#define SDSS 20 #define LED_PIN -1 -#define ORIG_FAN_PIN 16 // Fan +// Fan +#define ORIG_FAN_PIN 16 #define ORIG_PS_ON_PIN -1 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, @@ -1442,7 +1580,8 @@ STEPPER_CURRENT_CONTROL #define ORIG_Y_STEP_PIN 30 #define ORIG_Y_DIR_PIN 31 #define ORIG_Y_ENABLE_PIN 18 -#define ORIG_Y_MIN_PIN 20 // Don't use this if you want to use SD card. Use 37 and put the endstop in the e-stop slot!!! +// Don't use this if you want to use SD card. Use 37 and put the endstop in the e-stop slot!!! +#define ORIG_Y_MIN_PIN 20 #define ORIG_Y_MAX_PIN -1 #define ORIG_Z_STEP_PIN 32 @@ -1454,18 +1593,23 @@ STEPPER_CURRENT_CONTROL #define ORIG_E0_STEP_PIN 34 #define ORIG_E0_DIR_PIN 35 #define ORIG_E0_ENABLE_PIN 13 -#define TEMP_0_PIN 1 // Extruder - ANALOG PIN NUMBER! -#define TEMP_1_PIN 0 // Bed - ANALOG PIN NUMBER! -#define HEATER_0_PIN 15 // Extruder -#define HEATER_1_PIN 14 // bed +// Extruder - ANALOG PIN NUMBER! +#define TEMP_0_PIN 1 +// Bed - ANALOG PIN NUMBER! +#define TEMP_1_PIN 0 +// Extruder +#define HEATER_0_PIN 15 +// bed +#define HEATER_1_PIN 14 #define HEATER_2_PIN -1 #define TEMP_2_PIN -1 #define SDPOWER -1 -#define SDSS 26 // old value 2 +// old value 2 +#define SDSS 26 #define LED_PIN -1 -#define ORIG_FAN_PIN 16 // Fan +#define ORIG_FAN_PIN 16 #define ORIG_PS_ON_PIN -1 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, @@ -1505,56 +1649,89 @@ STEPPER_CURRENT_CONTROL #define ORIG_SDCARDDETECT -1 // digital pin mappings -#define ORIG_X_STEP_PIN 54 // PINF.0, 97, STP_DRV1 -#define ORIG_X_DIR_PIN 55 // PINF.1, 96, DIR_DRV1 -#define ORIG_X_ENABLE_PIN 38 // PIND.7, 50, ENA_DRV1 -#define ORIG_X_MIN_PIN 3 // PINE.5, 7, OPTO1 +// PINF.0, 97, STP_DRV1 +#define ORIG_X_STEP_PIN 54 +// PINF.1, 96, DIR_DRV1 +#define ORIG_X_DIR_PIN 55 +// PIND.7, 50, ENA_DRV1 +#define ORIG_X_ENABLE_PIN 38 +// PINE.5, 7, OPTO1 +#define ORIG_X_MIN_PIN 3 #define ORIG_X_MAX_PIN -1 // PINJ.0, 63, OPTO4 (would be "15", -1 = disabled) -#define ORIG_Y_STEP_PIN 60 // PINF.6, 91, STP_DRV2 -#define ORIG_Y_DIR_PIN 61 // PINF.7, 90, DIR_DRV2 -#define ORIG_Y_ENABLE_PIN 56 // PINF.2, 95, ENA_DRV2 -#define ORIG_Y_MIN_PIN 2 // PINE.4, 6, OPTO2 -#define ORIG_Y_MAX_PIN -1 // PIND.3, 46, OPTO5 (would be "18", -1 = disabled +// PINF.6, 91, STP_DRV2 +#define ORIG_Y_STEP_PIN 60 +// PINF.7, 90, DIR_DRV2 +#define ORIG_Y_DIR_PIN 61 +// PINF.2, 95, ENA_DRV2 +#define ORIG_Y_ENABLE_PIN 56 +// PINE.4, 6, OPTO2 +#define ORIG_Y_MIN_PIN 2 +// PIND.3, 46, OPTO5 (would be "18", -1 = disabled +#define ORIG_Y_MAX_PIN -1 -#define ORIG_Z_STEP_PIN 46 // PINL.3, 38, STP_DRV3 -#define ORIG_Z_DIR_PIN 48 // PINL.1, 36, DIR_DRV3 -#define ORIG_Z_ENABLE_PIN 62 // PINK.0, 89, ENA_DRV3 -#define ORIG_Z_MIN_PIN 14 // PINJ.1, 64, OPTO3 +// PINL.3, 38, STP_DRV3 +#define ORIG_Z_STEP_PIN 46 +// PINL.1, 36, DIR_DRV3 +#define ORIG_Z_DIR_PIN 48 +// PINK.0, 89, ENA_DRV3 +#define ORIG_Z_ENABLE_PIN 62 +// PINJ.1, 64, OPTO3 +#define ORIG_Z_MIN_PIN 14 #define ORIG_Z_MAX_PIN -1 // PIND.2, 45, OPTO6 (would be "19", -1 = disabled) -#define ORIG_E0_STEP_PIN 26 // PINA.4, 74, STP_DRV4 -#define ORIG_E0_DIR_PIN 28 // PINA.6, 72, DIR_DRV4 -#define ORIG_E0_ENABLE_PIN 24 // PINA.2, 76 ENA_DRV4 +// PINA.4, 74, STP_DRV4 +#define ORIG_E0_STEP_PIN 26 +// PINA.6, 72, DIR_DRV4 +#define ORIG_E0_DIR_PIN 28 +// PINA.2, 76 ENA_DRV4 +#define ORIG_E0_ENABLE_PIN 24 -#define ORIG_E1_STEP_PIN 36 // PINC.1, 54, STP_DRV5 -#define ORIG_E1_DIR_PIN 34 // PINC.3, 56, DIR_DRV5 -#define ORIG_E1_ENABLE_PIN 30 // PINC.7, 60, ENA_DRV5 +// PINC.1, 54, STP_DRV5 +#define ORIG_E1_STEP_PIN 36 +// PINC.3, 56, DIR_DRV5 +#define ORIG_E1_DIR_PIN 34 +// PINC.7, 60, ENA_DRV5 +#define ORIG_E1_ENABLE_PIN 30 #define SDPOWER -1 -#define SDSS 53 // PINB.0, 19, SS -#define LED_PIN 13 // PINB.7, 26, LED13 -#define ORIG_FAN_PIN 25 // OUT1 PINA.3, 75, OUT1 -#define FAN_BOARD_PIN 27 // OUT2 +// PINB.0, 19, SS +#define SDSS 53 +// PINB.7, 26, LED13 +#define LED_PIN 13 +// OUT1 PINA.3, 75, OUT1 +#define ORIG_FAN_PIN 25 +// OUT2 +#define FAN_BOARD_PIN 27 #define ORIG_PS_ON_PIN -1 -#define HEATER_0_PIN 10 // PINB.4, 23, HZ1 -#define HEATER_1_PIN 9 // PINH.6, 18, HZ2 -#define HEATER_2_PIN 8 // PINH.5, 17, HZ3 +// PINB.4, 23, HZ1 +#define HEATER_0_PIN 10 +// PINH.6, 18, HZ2 +#define HEATER_1_PIN 9 +// PINH.5, 17, HZ3 +#define HEATER_2_PIN 8 // analog pin mappings -#define TEMP_0_PIN 13 // PINK.5, 84, TH1 -#define TEMP_1_PIN 14 // PINK.6, 83, TH2 -#define TEMP_2_PIN 15 // PINK.7, 82, TH3 +// PINK.5, 84, TH1 +#define TEMP_0_PIN 13 + // PINK.6, 83, TH2 +#define TEMP_1_PIN 14 +// PINK.7, 82, TH3 +#define TEMP_2_PIN 15 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, #define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN, // these pins are defined in the SD library if building with SD support -#define SCK_PIN 52 // PINB.1, 20, SCK -#define MISO_PIN 50 // PINB.3, 22, MISO -#define MOSI_PIN 51 // PINB.2, 21, MOSI -#define MAX6675_SS 53 // PINB.0, 19, SS +// PINB.1, 20, SCK +#define SCK_PIN 52 +// PINB.3, 22, MISO +#define MISO_PIN 50 +// PINB.2, 21, MOSI +#define MOSI_PIN 51 +// PINB.0, 19, SS +#define MAX6675_SS 53 #endif // MOTHERBOARD == 12 @@ -1572,24 +1749,22 @@ STEPPER_CURRENT_CONTROL #error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. #endif - - - #define ORIG_X_STEP_PIN 26 #define ORIG_X_DIR_PIN 28 #define ORIG_X_ENABLE_PIN 24 #define ORIG_X_MIN_PIN 41 -#define ORIG_X_MAX_PIN 37 //2 //Max endstops default to disabled "-1", set to commented value to enable. + //2 //Max endstops default to disabled "-1", set to commented value to enable. +#define ORIG_X_MAX_PIN 37 -#define ORIG_Y_STEP_PIN 60 // A6 -#define ORIG_Y_DIR_PIN 61 // A7 +#define ORIG_Y_STEP_PIN 60 +#define ORIG_Y_DIR_PIN 61 #define ORIG_Y_ENABLE_PIN 22 #define ORIG_Y_MIN_PIN 14 -#define ORIG_Y_MAX_PIN 15 //15 +#define ORIG_Y_MAX_PIN 15 -#define ORIG_Z_STEP_PIN 54 // A0 -#define ORIG_Z_DIR_PIN 55 // A1 -#define ORIG_Z_ENABLE_PIN 56 // A2 +#define ORIG_Z_STEP_PIN 54 +#define ORIG_Z_DIR_PIN 55 +#define ORIG_Z_ENABLE_PIN 56 #define ORIG_Z_MIN_PIN 18 #define ORIG_Z_MAX_PIN 19 @@ -1606,22 +1781,32 @@ STEPPER_CURRENT_CONTROL #define LED_PIN 13 -#define ORIG_FAN_PIN 7 // IO pin. Buffer needed +// IO pin. Buffer needed +#define ORIG_FAN_PIN 7 #define ORIG_PS_ON_PIN 12 -#define HEATER_0_PIN 9 // EXTRUDER 1 -#define HEATER_1_PIN 8 // EXTRUDER 2 (FAN On Sprinter) -#define HEATER_2_PIN 10 // Heated bed +// EXTRUDER 1 +#define HEATER_0_PIN 9 +// EXTRUDER 2 (FAN On Sprinter) +#define HEATER_1_PIN 8 +// Heated bed +#define HEATER_2_PIN 10 #define THERMOCOUPLE_0_PIN 8 -#define TEMP_3_PIN 8 // Thermocouple 0 ANALOG NUMBERING -#define TEMP_0_PIN 13 // ANALOG NUMBERING -#define TEMP_1_PIN 15 // ANALOG NUMBERING +// Thermocouple 0 ANALOG NUMBERING +#define TEMP_3_PIN 8 +// ANALOG NUMBERING +#define TEMP_0_PIN 13 +// ANALOG NUMBERING +#define TEMP_1_PIN 15 #define TEMP_2_PIN -1 // ANALOG NUMBERING -#define HEATER_BED_PIN 10 // BED -#define TEMP_BED_PIN 14 // ANALOG NUMBERING + // BED +#define HEATER_BED_PIN 10 +// ANALOG NUMBERING +#define TEMP_BED_PIN 14 -#define BEEPER_PIN 33 // Beeper on AUX-4 +// Beeper on AUX-4 +#define BEEPER_PIN 33 #define BEEPER_TYPE 1 #define SDSUPPORT 1 // sd card reader on board #define ORIG_SDCARDDETECT -1 @@ -1640,7 +1825,7 @@ STEPPER_CURRENT_CONTROL //buttons are directly attached using AUX-2 #define BTN_EN1 37 #define BTN_EN2 35 -#define BTN_ENC 43 //the click +#define BTN_ENC 43 #define BLEN_C 2 #define BLEN_B 1 @@ -1707,11 +1892,14 @@ STEPPER_CURRENT_CONTROL #define KILL_PIN -1 #define HEATER_0_PIN 10 -#define HEATER_1_PIN 8 //BED +//BED +#define HEATER_1_PIN 8 #define HEATER_2_PIN 7 -#define TEMP_0_PIN 13 // ANALOG NUMBERING -#define TEMP_1_PIN 14 // BED,ANALOG NUMBERING +// ANALOG NUMBERING +#define TEMP_0_PIN 13 + // BED,ANALOG NUMBERING +#define TEMP_1_PIN 14 #define TEMP_2_PIN 15 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, @@ -1723,11 +1911,15 @@ STEPPER_CURRENT_CONTROL #define SDSUPPORT 1 // already defined in config.h #define SDCARDDETECTINVERTED 1 // already defined in config.h -// these pins are defined in the SD library if building with SD support -#define SCK_PIN 52 // PINB.1, 20, SCK -#define MISO_PIN 50 // PINB.3, 22, MISO -#define MOSI_PIN 51 // PINB.2, 21, MOSI -#define MAX6675_SS -1//53 // PINB.0, 19, SS +// these pins are defined in the SD library if building with SD support +// PINB.1, 20, SCK +#define SCK_PIN 52 +// PINB.3, 22, MISO +#define MISO_PIN 50 +// PINB.2, 21, MOSI +#define MOSI_PIN 51 +//53 // PINB.0, 19, SS +#define MAX6675_SS -1 #define BEEPER_PIN -1 // Activate beeper on extension shield #define BEEPER_TYPE 1 @@ -1752,17 +1944,18 @@ STEPPER_CURRENT_CONTROL #define ORIG_X_DIR_PIN 27 #define ORIG_X_ENABLE_PIN 25 #define ORIG_X_MIN_PIN 37 -#define ORIG_X_MAX_PIN 40 //2 //Max endstops default to disabled "-1", set to commented value to enable. + //2 //Max endstops default to disabled "-1", set to commented value to enable. +#define ORIG_X_MAX_PIN 40 -#define ORIG_Y_STEP_PIN 4 // A6 -#define ORIG_Y_DIR_PIN 54 // A0 +#define ORIG_Y_STEP_PIN 4 +#define ORIG_Y_DIR_PIN 54 #define ORIG_Y_ENABLE_PIN 5 #define ORIG_Y_MIN_PIN 41 -#define ORIG_Y_MAX_PIN 38 //15 +#define ORIG_Y_MAX_PIN 38 -#define ORIG_Z_STEP_PIN 56 // A2 -#define ORIG_Z_DIR_PIN 60 // A6 -#define ORIG_Z_ENABLE_PIN 55 // A1 +#define ORIG_Z_STEP_PIN 56 +#define ORIG_Z_DIR_PIN 60 +#define ORIG_Z_ENABLE_PIN 55 #define ORIG_Z_MIN_PIN 18 #define ORIG_Z_MAX_PIN 19 @@ -1789,19 +1982,28 @@ STEPPER_CURRENT_CONTROL #define ORIG_FAN2_PIN 6 #define ORIG_PS_ON_PIN 12 -#define HEATER_0_PIN 9 // EXTRUDER 1 -#define HEATER_2_PIN 8 // Heated bed -#define HEATER_1_PIN 10 // EXTRUDER 2 + // EXTRUDER 1 +#define HEATER_0_PIN 9 +// Heated bed +#define HEATER_2_PIN 8 +// EXTRUDER 2 +#define HEATER_1_PIN 10 -#define TEMP_0_PIN 13 // Thermistor 0 ANALOG NUMBERING -#define TEMP_2_PIN 15 // Thermistor 1 ANALOG NUMBERING -#define TEMP_1_PIN 14 // Thermistor 2 for heated bed ANALOG NUMBERING -#define TEMP_3_PIN 8 // Thermocouple 0 -#define TEMP_4_PIN 4 // Thermocouple 1 +// Thermistor 0 ANALOG NUMBERING +#define TEMP_0_PIN 13 +// Thermistor 1 ANALOG NUMBERING +#define TEMP_2_PIN 15 + // Thermistor 2 for heated bed ANALOG NUMBERING +#define TEMP_1_PIN 14 + // Thermocouple 0 +#define TEMP_3_PIN 8 + // Thermocouple 1 +#define TEMP_4_PIN 4 #define THERMOCOUPLE_0_PIN 8 #define THERMOCOUPLE_0_PIN 4 -#define BEEPER_PIN 64 // Beeper on AUX-4 +// Beeper on AUX-4 +#define BEEPER_PIN 64 #define LCD_PINS_RS 14 #define LCD_PINS_ENABLE 15 @@ -1814,7 +2016,7 @@ STEPPER_CURRENT_CONTROL //buttons are directly attached using AUX-2 #define BTN_EN1 59 #define BTN_EN2 64 -#define BTN_ENC 43 //the click +#define BTN_ENC 43 #define BLEN_C 2 #define BLEN_B 1 @@ -1848,17 +2050,18 @@ STEPPER_CURRENT_CONTROL #define ORIG_X_DIR_PIN 47 #define ORIG_X_ENABLE_PIN 49 #define ORIG_X_MIN_PIN 5 -#define ORIG_X_MAX_PIN -1 //2 //Max endstops default to disabled "-1", set to commented value to enable. +//2 //Max endstops default to disabled "-1", set to commented value to enable. +#define ORIG_X_MAX_PIN -1 -#define ORIG_Y_STEP_PIN 39 // A6 -#define ORIG_Y_DIR_PIN 40 // A0 +#define ORIG_Y_STEP_PIN 39 +#define ORIG_Y_DIR_PIN 40 #define ORIG_Y_ENABLE_PIN 38 #define ORIG_Y_MIN_PIN 2 -#define ORIG_Y_MAX_PIN -1 //15 +#define ORIG_Y_MAX_PIN -1 -#define ORIG_Z_STEP_PIN 42 // A2 -#define ORIG_Z_DIR_PIN 43 // A6 -#define ORIG_Z_ENABLE_PIN 41 // A1 +#define ORIG_Z_STEP_PIN 42 +#define ORIG_Z_DIR_PIN 43 +#define ORIG_Z_ENABLE_PIN 41 #define ORIG_Z_MIN_PIN 6 #define ORIG_Z_MAX_PIN -1 @@ -1886,16 +2089,23 @@ STEPPER_CURRENT_CONTROL #define ORIG_PS_ON_PIN -1 #define KILL_PIN -1 -#define HEATER_0_PIN 7 // EXTRUDER 1 -#define HEATER_1_PIN 3 // BED -#define HEATER_2_PIN 8 // EXTRUDER 2 +// EXTRUDER 1 +#define HEATER_0_PIN 7 +// BED +#define HEATER_1_PIN 3 +// EXTRUDER 2 +#define HEATER_2_PIN 8 #define HEATER_3_PIN -1 -#define TEMP_0_PIN 7 // ANALOG NUMBERING -#define TEMP_1_PIN 6 // BED SENSOR ANALOG NUMBERING -#define TEMP_2_PIN 6 // ANALOG NUMBERING -#define TEMP_3_PIN -1 // ANALOG NUMBERING +// ANALOG NUMBERING +#define TEMP_0_PIN 7 +// BED SENSOR ANALOG NUMBERING +#define TEMP_1_PIN 6 +// ANALOG NUMBERING +#define TEMP_2_PIN 6 +// ANALOG NUMBERING +#define TEMP_3_PIN -1 #define BEEPER_PIN -1 @@ -1925,17 +2135,18 @@ STEPPER_CURRENT_CONTROL #define ORIG_X_DIR_PIN 57 #define ORIG_X_ENABLE_PIN 59 #define ORIG_X_MIN_PIN 37 -#define ORIG_X_MAX_PIN 40 //2 //Max endstops default to disabled "-1", set to commented value to enable. +//2 //Max endstops default to disabled "-1", set to commented value to enable. +#define ORIG_X_MAX_PIN 40 -#define ORIG_Y_STEP_PIN 5 // A6 -#define ORIG_Y_DIR_PIN 17 // A0 +#define ORIG_Y_STEP_PIN 5 +#define ORIG_Y_DIR_PIN 17 #define ORIG_Y_ENABLE_PIN 4 #define ORIG_Y_MIN_PIN 41 -#define ORIG_Y_MAX_PIN 38 //15 +#define ORIG_Y_MAX_PIN 38 -#define ORIG_Z_STEP_PIN 16 // A2 -#define ORIG_Z_DIR_PIN 11 // A6 -#define ORIG_Z_ENABLE_PIN 3 // A1 +#define ORIG_Z_STEP_PIN 16 +#define ORIG_Z_DIR_PIN 11 +#define ORIG_Z_ENABLE_PIN 3 #define ORIG_Z_MIN_PIN 18 #define ORIG_Z_MAX_PIN 19 @@ -1963,10 +2174,14 @@ STEPPER_CURRENT_CONTROL #define ORIG_PS_ON_PIN 12 //#define KILL_PIN -1 -#define HEATER_0_PIN 9 // EXTRUDER 1 -#define HEATER_2_PIN 8 // EXTRUDER 2 -#define HEATER_3_PIN 2 // EXTRUDER 3 -#define HEATER_1_PIN 10 // heater bed +// EXTRUDER 0 - changed 10-9-2015 +#define HEATER_0_PIN 2 +// EXTRUDER 1 - changed 10-9-2015 +#define HEATER_2_PIN 9 +// EXTRUDER 2 - changed 10-9-2015 +#define HEATER_3_PIN 8 +// heater bed +#define HEATER_1_PIN 10 /* Temperature sensors @@ -1995,8 +2210,9 @@ S3(ext)=9 #define THERMOCOUPLE_2_PIN 8 #define THERMOCOUPLE_3_PIN 9 -#define BEEPER_PIN 61 // Beeper on AUX-4 -#define SDSUPPORT true // sd card reader on board +// Beeper on AUX-4 +#define BEEPER_PIN 61 +#define SDSUPPORT 1 // sd card reader on board // #define UI_DISPLAY_RS_PIN 32 // #define UI_DISPLAY_ENABLE_PIN 31 @@ -2061,11 +2277,13 @@ S3(ext)=9 #define TEMP_0_PIN 0 #define HEATER_1_PIN 3 +// This is T2 on the board! #define TEMP_1_PIN 2 #define HEATER_2_PIN 7 +// This is T1 on the board! #define TEMP_2_PIN 1 - +// T3 on board #define TEMP_3_PIN 7 #define ORIG_E0_STEP_PIN 34 @@ -2119,10 +2337,10 @@ S3(ext)=9 #ifndef Thermistor_Solution #define Thermistor_Solution 0 #endif -///////////////********define for temperature senser chip connection -///**** temperature sensor port in Rev 2.0 for max6675 +// define for temperature senser chip connection +// temperature sensor port in Rev 2.0 for max6675 // #define MAX6675_TEMP_Senser false ///*** canceled hardware integration -///**** Temperature sensor port in Rev 2.0 for AD595 +// Temperature sensor port in Rev 2.0 for AD595 #define AD595_TEMP_Senser false /////*** you can input at port 59 60 61 ///Analoge Pin 8 9 10 #endif @@ -2135,7 +2353,7 @@ S3(ext)=9 #if MOTHERBOARD == 314 #define KNOWN_BOARD 1 #define PiBot true -///////////////////////*************** + #if PiBot_V_1_4==true || PiBot_V_1_6==true || PiBot_V_2_0==true #define PiBot_V_1_0 false #else @@ -2144,7 +2362,7 @@ S3(ext)=9 #endif #ifndef PiBotSemitec -#define PiBotSemitec false //****for semitec NTC 100K b=4230(test value) default b=4267 +#define PiBotSemitec false // for semitec NTC 100K b=4230(test value) default b=4267 #endif #ifndef PI_PRUSA_I3 @@ -2152,14 +2370,14 @@ S3(ext)=9 #endif #ifndef PiBotMachine -#define PiBotMachine false ////****if use for pibot 3D printer uncomment this line. +#define PiBotMachine false // if use for pibot 3D printer uncomment this line. #endif #if PI_PRUSA_I3==true -#define PiBotMachine true ////****if use for pibot 3D printer uncomment this line. +#define PiBotMachine true // if use for pibot 3D printer uncomment this line. #endif -/////////////////*********** ////define in AVR public files, when you finish the chip select. +// define in AVR public files, when you finish the chip select. #ifndef __AVR_ATmega1280__ #ifndef __AVR_ATmega2560__ #error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. @@ -2197,18 +2415,24 @@ S3(ext)=9 #define ORIG_SDCARDDETECT 49 #define LED_PIN 13 -#define ORIG_FAN_PIN 7 ////*****fan +#define ORIG_FAN_PIN 7 #define ORIG_PS_ON_PIN 12 #define KILL_PIN -1 -#define HEATER_0_PIN 8 ////**** Extuder1 -#define HEATER_1_PIN 10 ////***Bed -#define HEATER_2_PIN 9 ////***Extuder2 -#define TEMP_0_PIN 13 // ANALOG NUMBERING ////***Extuder1 -#define TEMP_1_PIN 15 // ANALOG NUMBERING ////***Bed -#define TEMP_2_PIN 14 // ANALOG NUMBERING ////***Extuder2 +// Extuder1 +#define HEATER_0_PIN 8 +// Bed +#define HEATER_1_PIN 10 +// Extuder2 +#define HEATER_2_PIN 9 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 13 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 15 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 14 -////***ISP for TFcard +// ISP for TFcard #define SDSS 53 #define SCK_PIN 52 #define MISO_PIN 50 @@ -2216,7 +2440,7 @@ S3(ext)=9 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, #define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN, -#endif ///////****** end PiBot for Repetier V1.0 +#endif // end PiBot for Repetier V1.0 #if PiBot_V_1_4==true || PiBot_V_1_6==true @@ -2260,33 +2484,38 @@ S3(ext)=9 #define ORIG_SDCARDDETECT 10 #define LED_PIN 30 -#define ORIG_FAN_PIN 7 ////*****fan +#define ORIG_FAN_PIN 7 //uncomment when the 2nd fan used - works only without heated bed! #define ORIG_FAN2_PIN 2 #define PS_ON_PIN 40 #define KILL_PIN -1 -#define HEATER_0_PIN 3 ////**** Extuder1 -#define HEATER_1_PIN 12 ////*** Bed -#define HEATER_2_PIN 6 ////*** Extuder2 -//uncomment when the 3rd extruder used -#define HEATER_3_PIN 9 ////*** Extuder3 -//uncomment when the 4th extruder used -#define HEATER_4_PIN 11 ////*** Extuder4 +// Extuder1 +#define HEATER_0_PIN 3 +// Bed +#define HEATER_1_PIN 12 +// Extuder2 +#define HEATER_2_PIN 6 + // Extuder3 +#define HEATER_3_PIN 9 +// Extuder4 +#define HEATER_4_PIN 11 -#define TEMP_0_PIN 14 // ANALOG NUMBERING ////***Extuder1 -#define TEMP_1_PIN 15 // ANALOG NUMBERING ////***Bed -#define TEMP_2_PIN 13 // ANALOG NUMBERING ////***Extuder2 -//uncomment when 3 extruder used -#define TEMP_3_PIN 12 // ANALOG NUMBERING ////***Extuder3 -//uncomment when 4 extruder used -#define TEMP_4_PIN 11 // ANALOG NUMBERING ////***Extuder4 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 14 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 15 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 13 +// ANALOG NUMBERING Extuder3 +#define TEMP_3_PIN 12 +// ANALOG NUMBERING Extuder4 +#define TEMP_4_PIN 11 -/////////////////////********************************************* -#define PiBot_Z_PROBE_PIN 64 /////****PiBot use this pin as Z-Probing pin -//////////////////////////////////////////************************ +//PiBot use this pin as Z-Probing pin +#define PiBot_Z_PROBE_PIN 64 -////***ISP for TFcard +// ISP for TFcard #define SDSS 53 #define SCK_PIN 52 #define MISO_PIN 50 @@ -2297,7 +2526,7 @@ S3(ext)=9 #define E2_PINS ORIG_E2_STEP_PIN,ORIG_E2_DIR_PIN,ORIG_E2_ENABLE_PIN, #define E3_PINS ORIG_E3_STEP_PIN,ORIG_E3_DIR_PIN,ORIG_E3_ENABLE_PIN, -#endif ///////****** end PiBot for Repetier V1.4 or V1.6 +#endif // end PiBot for Repetier V1.4 or V1.6 #if PiBot_V_2_0==true @@ -2327,87 +2556,124 @@ S3(ext)=9 #define ORIG_E1_DIR_PIN 34 #define ORIG_E1_ENABLE_PIN 33 -/////////////////////********************************************* -#define PiBot_Z_PROBE_PIN 68 /////**** PiBot use this pin as Z-Probing pin +// ========================================= +#define PiBot_Z_PROBE_PIN 68 // PiBot use this pin as Z-Probing pin #define LED_PIN -1 -#define ORIG_FAN_PIN 6 ////***** PWM6 fan1 -#define ORIG_FAN2_PIN 7 ////***** PWM7 fan2 +// PWM6 fan1 +#define ORIG_FAN_PIN 6 + // PWM7 fan2 +#define ORIG_FAN2_PIN 7 -#define ORIG_PS_ON_PIN 17 /////*****have hardware in PiBot HDV2.0 +// have hardware in PiBot HDV2.0 +#define ORIG_PS_ON_PIN 17 #define KILL_PIN -1 -#define HEATER_0_PIN 5 ////*** PWM5 Extuder1 -#define HEATER_1_PIN 4 ////*** PWM4 Bed -#define HEATER_2_PIN 2 ////*** PWM2 Extuder2 -#define HEATER_3_PIN -1 /////***for Pibot ////*** PWM Extuder3 -#define HEATER_4_PIN -1 /////***for Pibot ////*** PWM Extuder4 +// PWM5 Extuder1 +#define HEATER_0_PIN 5 +// PWM4 Bed +#define HEATER_1_PIN 4 +// PWM2 Extuder2 +#define HEATER_2_PIN 2 +// for Pibot PWM Extuder3 +#define HEATER_3_PIN -1 +// for Pibot PWM Extuder4 +#define HEATER_4_PIN -1 -#if Thermistor_Solution==0 ///*** 000 0 2 4 -#define TEMP_0_PIN 2 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 0 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 4 // ANALOG NUMBERING ////*** Extuder2 +#if Thermistor_Solution==0 // 000 0 2 4 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 2 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 0 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 4 #endif -#if Thermistor_Solution==1 ///*** 001 1 2 4 -#define TEMP_0_PIN 2 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 1 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 4 // ANALOG NUMBERING ////*** Extuder2 +#if Thermistor_Solution==1 // 001 1 2 4 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 2 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 1 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 4 #endif -#if Thermistor_Solution==2 ///*** 010 0 3 4 -#define TEMP_0_PIN 3 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 0 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 4 // ANALOG NUMBERING ////*** Extuder2 +#if Thermistor_Solution==2 // 010 0 3 4 +#define TEMP_0_PIN 3 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 0 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 4 #endif -#if Thermistor_Solution==3 ///*** 011 1 3 4 -#define TEMP_0_PIN 3 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 1 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 4 // ANALOG NUMBERING ////*** Extuder2 +#if Thermistor_Solution==3 // 011 1 3 4 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 3 +#define TEMP_1_PIN 1 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 4 #endif -#if Thermistor_Solution==4 ///*** 100 0 2 5 -#define TEMP_0_PIN 2 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 0 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 5 // ANALOG NUMBERING ////*** Extuder2 +#if Thermistor_Solution==4 // 100 0 2 5 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 2 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 0 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 5 #endif -#if Thermistor_Solution==5 ///*** 101 1 2 5 -#define TEMP_0_PIN 2 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 1 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 5 // ANALOG NUMBERING ////*** Extuder2 +#if Thermistor_Solution==5 // 101 1 2 5 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 2 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 1 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 5 #endif -#if Thermistor_Solution==6 ///*** 110 0 3 5 -#define TEMP_0_PIN 3 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 0 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 5 // ANALOG NUMBERING ////*** Extuder2 +#if Thermistor_Solution==6 // 110 0 3 5 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 3 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 0 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 5 #endif -#if Thermistor_Solution==7 ///*** 111 1 3 5 -#define TEMP_0_PIN 3 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 1 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 5 // ANALOG NUMBERING ////*** Extuder2 +#if Thermistor_Solution==7 // 111 1 3 5 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 3 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 1 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 5 #endif #if !defined(TEMP_0_PIN) || !defined(TEMP_1_PIN) || !defined(TEMP_2_PIN) ||!defined(Thermistor_Solution) -#define TEMP_0_PIN 2 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 0 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 4 // ANALOG NUMBERING ////*** Extuder2 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 2 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 0 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 4 #endif -//////*************ad595 temp senser +// ad595 temp senser #if AD595_TEMP_Senser==true -#define TEMP_0_PIN 8 // ANALOG NUMBERING ////*** Extuder1 -#define TEMP_1_PIN 9 // ANALOG NUMBERING ////*** Bed -#define TEMP_2_PIN 10 // ANALOG NUMBERING ////*** Extuder2 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 8 +// ANALOG NUMBERING Bed +#define TEMP_1_PIN 9 +// ANALOG NUMBERING Extuder2 +#define TEMP_2_PIN 10 #endif -////////////////////*******max6675 ISP port temp->ISP-ENABLE -/////********these enable pins have been isolated by capacitor +// max6675 ISP port temp->ISP-ENABLE +// these enable pins have been isolated by capacitor /*#if MAX6675_TEMP_Senser==true -#define TEMP_0_PIN 14 // ANALOG NUMBERING ////***Extuder1 -#define TEMP_1_PIN 15 // ANALOG NUMBERING ////***Bed -#define TEMP_2_PIN 13 // ANALOG NUMBERING ////***Extuder2 +// ANALOG NUMBERING Extuder1 +#define TEMP_0_PIN 14 // ANALOG NUMBERING Extuder1 +#define TEMP_1_PIN 15 // ANALOG NUMBERING Bed +#define TEMP_2_PIN 13 // ANALOG NUMBERING Extuder2 //uncomment when 3 extruder used -#define TEMP_3_PIN 12 // ANALOG NUMBERING ////***Extuder3 +#define TEMP_3_PIN 12 // ANALOG NUMBERING Extuder3 #endif*/ -///////*********ISP for TFcard +// ISP for TFcard #define SDPOWER -1 #define ORIG_SDCARDDETECT 40 #define SDSS 53 @@ -2418,9 +2684,9 @@ S3(ext)=9 #define E0_PINS ORIG_E0_STEP_PIN,ORIG_E0_DIR_PIN,ORIG_E0_ENABLE_PIN, #define E1_PINS ORIG_E1_STEP_PIN,ORIG_E1_DIR_PIN,ORIG_E1_ENABLE_PIN, -#endif /////***end PiBot Controller Rev 2.0 +#endif // end PiBot Controller Rev 2.0 -#endif ///////******end PiBot for Repetier +#endif // end PiBot for Repetier /**************************************************************************************** * Sanguish Beta pin assignment @@ -2511,13 +2777,17 @@ S3(ext)=9 #ifndef FAN_BOARD_PIN #define FAN_BOARD_PIN -1 #endif + +#ifndef E2_PINS +#define E2_PINS +#endif #if NUM_EXTRUDER==1 #undef E1_PINS #define E1_PINS #endif -#if NUM_EXTRUDER<3 +#if NUM_EXTRUDER < 3 #undef E2_PINS #define E2_PINS #endif @@ -2570,7 +2840,10 @@ S3(ext)=9 #define E5_ENABLE_PIN ORIG_E5_ENABLE_PIN #define FAN_PIN ORIG_FAN_PIN +#ifdef ORIG_FAN2_PIN #define FAN2_PIN ORIG_FAN2_PIN +#endif + #define PS_ON_PIN ORIG_PS_ON_PIN #ifndef ORIG_SDCARDDETECT @@ -2584,5 +2857,3 @@ S3(ext)=9 HEATER_0_PIN, HEATER_1_PIN, /*ORIG_FAN_PIN,*/ E0_PINS E1_PINS E2_PINS TEMP_0_PIN, TEMP_1_PIN,SDSS } #endif - - diff --git a/Repetier/u8glib_ex.h b/Repetier/u8glib_ex.h index fd03300..81b3801 100644 --- a/Repetier/u8glib_ex.h +++ b/Repetier/u8glib_ex.h @@ -116,6 +116,11 @@ ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ +// these warnings appear and are no problem. +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-variable" +#pragma GCC diagnostic ignored "-Wunused-parameter" + // ============= u8g.h ==================== /* @@ -156,6 +161,7 @@ ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #ifndef _U8G_H #define _U8G_H + /* uncomment the following line to support displays larger than 240x240 */ //#define U8G_16BIT 1 @@ -854,6 +860,7 @@ defined(__18CXX) || defined(__PIC32MX) #define U8G_SPI_CLK_CYCLE_50NS 1 #define U8G_SPI_CLK_CYCLE_300NS 2 #define U8G_SPI_CLK_CYCLE_400NS 3 +#define U8G_SPI_CLK_CYCLE_500NS 4 #define U8G_SPI_CLK_CYCLE_NONE 255 uint8_t u8g_InitCom(u8g_t *u8g, u8g_dev_t *dev, uint8_t clk_cycle_time); @@ -1385,15 +1392,15 @@ void st_Draw(uint8_t fps); void st_Step(uint8_t player_pos, uint8_t is_auto_fire, uint8_t is_fire); /*===============================================================*/ -/* u8g_com_i2c.c */ - -/* options for u8g_i2c_init() */ -#define U8G_I2C_OPT_NONE 0 -#define U8G_I2C_OPT_NO_ACK 2 -#define U8G_I2C_OPT_DEV_0 0 -#define U8G_I2C_OPT_DEV_1 4 -#define U8G_I2C_OPT_FAST 16 - +/* u8g_com_i2c.c */ + +/* options for u8g_i2c_init() */ +#define U8G_I2C_OPT_NONE 0 +#define U8G_I2C_OPT_NO_ACK 2 +#define U8G_I2C_OPT_DEV_0 0 +#define U8G_I2C_OPT_DEV_1 4 +#define U8G_I2C_OPT_FAST 16 + /* u8g_com_i2c.c */ /* retrun values from u8g_twi_get_error() */ @@ -2608,418 +2615,418 @@ u8g_dev_t u8g_dev_st7920_128x64_4x_hw_spi = { u8g_dev_st7920_128x64_4x_fn, &u8g_ u8g_dev_t u8g_dev_st7920_128x64_4x_8bit = { u8g_dev_st7920_128x64_4x_fn, &u8g_dev_st7920_128x64_4x_pb, U8G_COM_FAST_PARALLEL }; u8g_dev_t u8g_dev_st7920_128x64_4x_custom = { u8g_dev_st7920_128x64_4x_fn, &u8g_dev_st7920_128x64_4x_pb, u8g_com_arduino_st7920_custom_fn }; -// ================ u8g_dev_ssd1306_128x64.c ========== - -/* - - u8g_dev_ssd1306_128x64.c - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - -*/ - -#define WIDTH 128 -#define HEIGHT 64 -#define PAGE_HEIGHT 8 - -/* init sequence adafruit 128x64 OLED (NOT TESTED) */ -static const uint8_t u8g_dev_ssd1306_128x64_adafruit1_init_seq[] PROGMEM = { - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ - U8G_ESC_CS(1), /* enable chip */ - - 0x0ae, /* display off, sleep mode */ - 0x0d5, 0x080, /* clock divide ratio (0x00=1) and oscillator frequency (0x8) */ - 0x0a8, 0x03f, /* */ - - 0x0d3, 0x000, /* */ - - 0x040, /* start line */ - - 0x08d, 0x010, /* [1] charge pump setting (p62): 0x014 enable, 0x010 disable */ - - 0x020, 0x000, /* */ - 0x0a1, /* segment remap a0/a1*/ - 0x0c8, /* c0: scan dir normal, c8: reverse */ - 0x0da, 0x012, /* com pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5) */ - 0x081, 0x09f, /* [1] set contrast control */ - 0x0d9, 0x022, /* [1] pre-charge period 0x022/f1*/ - 0x0db, 0x040, /* vcomh deselect level */ - - 0x02e, /* 2012-05-27: Deactivate scroll */ - 0x0a4, /* output ram to display */ - 0x0a6, /* none inverted normal display mode */ - 0x0af, /* display on */ - - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_END /* end of sequence */ -}; - -/* init sequence adafruit 128x64 OLED (NOT TESTED) */ -static const uint8_t u8g_dev_ssd1306_128x64_adafruit2_init_seq[] PROGMEM = { - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ - U8G_ESC_CS(1), /* enable chip */ - - 0x0ae, /* display off, sleep mode */ - 0x0d5, 0x080, /* clock divide ratio (0x00=1) and oscillator frequency (0x8) */ - 0x0a8, 0x03f, /* */ - - 0x0d3, 0x000, /* */ - - 0x040, /* start line */ - - 0x08d, 0x014, /* [2] charge pump setting (p62): 0x014 enable, 0x010 disable */ - - 0x020, 0x000, /* */ - 0x0a1, /* segment remap a0/a1*/ - 0x0c8, /* c0: scan dir normal, c8: reverse */ - 0x0da, 0x012, /* com pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5) */ - 0x081, 0x0cf, /* [2] set contrast control */ - 0x0d9, 0x0f1, /* [2] pre-charge period 0x022/f1*/ - 0x0db, 0x040, /* vcomh deselect level */ - - 0x02e, /* 2012-05-27: Deactivate scroll */ - 0x0a4, /* output ram to display */ - 0x0a6, /* none inverted normal display mode */ - 0x0af, /* display on */ - - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_END /* end of sequence */ -}; - -/* init sequence adafruit 128x64 OLED (NOT TESTED), like adafruit3, but with page addressing mode */ -static const uint8_t u8g_dev_ssd1306_128x64_adafruit3_init_seq[] PROGMEM = { - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ - U8G_ESC_CS(1), /* enable chip */ - - 0x0ae, /* display off, sleep mode */ - 0x0d5, 0x080, /* clock divide ratio (0x00=1) and oscillator frequency (0x8) */ - 0x0a8, 0x03f, /* */ - - 0x0d3, 0x000, /* */ - - 0x040, /* start line */ - - 0x08d, 0x014, /* [2] charge pump setting (p62): 0x014 enable, 0x010 disable */ - - 0x020, 0x002, /* 2012-05-27: page addressing mode */ - 0x0a1, /* segment remap a0/a1*/ - 0x0c8, /* c0: scan dir normal, c8: reverse */ - 0x0da, 0x012, /* com pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5) */ - 0x081, 0x0cf, /* [2] set contrast control */ - 0x0d9, 0x0f1, /* [2] pre-charge period 0x022/f1*/ - 0x0db, 0x040, /* vcomh deselect level */ - - 0x02e, /* 2012-05-27: Deactivate scroll */ - 0x0a4, /* output ram to display */ - 0x0a6, /* none inverted normal display mode */ - 0x0af, /* display on */ - - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_END /* end of sequence */ -}; - -/* init sequence Univision datasheet (NOT TESTED) */ -static const uint8_t u8g_dev_ssd1306_128x64_univision_init_seq[] PROGMEM = { - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ - U8G_ESC_CS(1), /* enable chip */ - - 0x0ae, /* display off, sleep mode */ - 0x0d5, 0x080, /* clock divide ratio (0x00=1) and oscillator frequency (0x8) */ - 0x0a8, 0x03f, /* multiplex ratio */ - 0x0d3, 0x000, /* display offset */ - 0x040, /* start line */ - 0x08d, 0x010, /* charge pump setting (p62): 0x014 enable, 0x010 disable */ - 0x0a1, /* segment remap a0/a1*/ - 0x0c8, /* c0: scan dir normal, c8: reverse */ - 0x0da, 0x012, /* com pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5) */ - 0x081, 0x09f, /* set contrast control */ - 0x0d9, 0x022, /* pre-charge period */ - 0x0db, 0x040, /* vcomh deselect level */ - 0x022, 0x000, /* page addressing mode WRONG: 3 byte cmd! */ - 0x0a4, /* output ram to display */ - 0x0a6, /* none inverted normal display mode */ - 0x0af, /* display on */ - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_END /* end of sequence */ -}; - -/* select one init sequence here */ -//#define u8g_dev_ssd1306_128x64_init_seq u8g_dev_ssd1306_128x64_univision_init_seq -//#define u8g_dev_ssd1306_128x64_init_seq u8g_dev_ssd1306_128x64_adafruit1_init_seq -// 26. Apr 2014: in this thead: http://forum.arduino.cc/index.php?topic=234930.msg1696754;topicseen#msg1696754 -// it is mentiond, that adafruit2_init_seq works better --> this will be used by the ssd1306_adafruit device -//#define u8g_dev_ssd1306_128x64_init_seq u8g_dev_ssd1306_128x64_adafruit2_init_seq - -#define u8g_dev_ssd1306_128x64_init_seq u8g_dev_ssd1306_128x64_adafruit3_init_seq - - -static const uint8_t u8g_dev_ssd1306_128x64_data_start[] PROGMEM = { - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_CS(1), /* enable chip */ - 0x010, /* set upper 4 bit of the col adr to 0 */ - 0x000, /* set lower 4 bit of the col adr to 0 */ - U8G_ESC_END /* end of sequence */ -}; - -/* the sh1106 is compatible to the ssd1306, but is 132x64. display seems to be centered */ -static const uint8_t u8g_dev_sh1106_128x64_data_start[] PROGMEM = { - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_CS(1), /* enable chip */ - 0x010, /* set upper 4 bit of the col adr to 0 */ - 0x002, /* set lower 4 bit of the col adr to 2 (centered display with sh1106) */ - U8G_ESC_END /* end of sequence */ -}; - -static const uint8_t u8g_dev_ssd13xx_sleep_on[] PROGMEM = { - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_CS(1), /* enable chip */ - 0x0ae, /* display off */ - U8G_ESC_CS(0), /* disable chip, bugfix 12 nov 2014 */ - U8G_ESC_END /* end of sequence */ -}; - -static const uint8_t u8g_dev_ssd13xx_sleep_off[] PROGMEM = { - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_CS(1), /* enable chip */ - 0x0af, /* display on */ - U8G_ESC_DLY(50), /* delay 50 ms */ - U8G_ESC_CS(0), /* disable chip, bugfix 12 nov 2014 */ - U8G_ESC_END /* end of sequence */ -}; - -uint8_t u8g_dev_ssd1306_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - switch(msg) - { - case U8G_DEV_MSG_INIT: - u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_adafruit2_init_seq); - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_NEXT: - { - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | pb->p.page); /* select current page (SSD1306) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - if ( u8g_pb_WriteBuffer(pb, u8g, dev) == 0 ) - return 0; - u8g_SetChipSelect(u8g, dev, 0); - } - break; - case U8G_DEV_MSG_SLEEP_ON: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); - return 1; - case U8G_DEV_MSG_SLEEP_OFF: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); - return 1; - } - return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); -} - -uint8_t u8g_dev_ssd1306_adafruit_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - switch(msg) - { - case U8G_DEV_MSG_INIT: - u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_init_seq); - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_NEXT: - { - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | pb->p.page); /* select current page (SSD1306) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - if ( u8g_pb_WriteBuffer(pb, u8g, dev) == 0 ) - return 0; - u8g_SetChipSelect(u8g, dev, 0); - } - break; - case U8G_DEV_MSG_SLEEP_ON: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); - return 1; - case U8G_DEV_MSG_SLEEP_OFF: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); - return 1; - } - return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); -} - -uint8_t u8g_dev_sh1106_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - switch(msg) - { - case U8G_DEV_MSG_INIT: - u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_init_seq); - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_NEXT: - { - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_sh1106_128x64_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | pb->p.page); /* select current page (SSD1306) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - if ( u8g_pb_WriteBuffer(pb, u8g, dev) == 0 ) - return 0; - u8g_SetChipSelect(u8g, dev, 0); - } - break; - case U8G_DEV_MSG_SLEEP_ON: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); - return 1; - case U8G_DEV_MSG_SLEEP_OFF: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); - return 1; - } - return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); -} - - -uint8_t u8g_dev_ssd1306_128x64_2x_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - switch(msg) - { - case U8G_DEV_MSG_INIT: - u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_init_seq); - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_NEXT: - { - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | (pb->p.page*2)); /* select current page (SSD1306) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)pb->buf); - u8g_SetChipSelect(u8g, dev, 0); - - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | (pb->p.page*2+1)); /* select current page (SSD1306) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)(pb->buf)+pb->width); - u8g_SetChipSelect(u8g, dev, 0); - } - break; - case U8G_DEV_MSG_SLEEP_ON: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); - return 1; - case U8G_DEV_MSG_SLEEP_OFF: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); - return 1; - } - return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg); -} - -uint8_t u8g_dev_sh1106_128x64_2x_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - switch(msg) - { - case U8G_DEV_MSG_INIT: - u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_init_seq); - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_NEXT: - { - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - - u8g_WriteEscSeqP(u8g, dev, u8g_dev_sh1106_128x64_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | (pb->p.page*2)); /* select current page (SSD1306) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)pb->buf); - u8g_SetChipSelect(u8g, dev, 0); - - u8g_WriteEscSeqP(u8g, dev, u8g_dev_sh1106_128x64_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | (pb->p.page*2+1)); /* select current page (SSD1306) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)(pb->buf)+pb->width); - u8g_SetChipSelect(u8g, dev, 0); - } - break; - case U8G_DEV_MSG_SLEEP_ON: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); - return 1; - case U8G_DEV_MSG_SLEEP_OFF: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); - return 1; - } - return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg); -} - - - - -U8G_PB_DEV(u8g_dev_ssd1306_128x64_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_128x64_fn, U8G_COM_SW_SPI); -U8G_PB_DEV(u8g_dev_ssd1306_128x64_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_128x64_fn, U8G_COM_HW_SPI); -U8G_PB_DEV(u8g_dev_ssd1306_128x64_i2c, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_128x64_fn, U8G_COM_SSD_I2C); - -U8G_PB_DEV(u8g_dev_ssd1306_adafruit_128x64_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_adafruit_128x64_fn, U8G_COM_SW_SPI); -U8G_PB_DEV(u8g_dev_ssd1306_adafruit_128x64_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_adafruit_128x64_fn, U8G_COM_HW_SPI); -U8G_PB_DEV(u8g_dev_ssd1306_adafruit_128x64_i2c, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_adafruit_128x64_fn, U8G_COM_SSD_I2C); - - -uint8_t u8g_dev_ssd1306_128x64_2x_buf[WIDTH*2] U8G_NOCOMMON ; -u8g_pb_t u8g_dev_ssd1306_128x64_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_ssd1306_128x64_2x_buf}; -u8g_dev_t u8g_dev_ssd1306_128x64_2x_sw_spi = { u8g_dev_ssd1306_128x64_2x_fn, &u8g_dev_ssd1306_128x64_2x_pb, U8G_COM_SW_SPI }; -u8g_dev_t u8g_dev_ssd1306_128x64_2x_hw_spi = { u8g_dev_ssd1306_128x64_2x_fn, &u8g_dev_ssd1306_128x64_2x_pb, U8G_COM_HW_SPI }; -u8g_dev_t u8g_dev_ssd1306_128x64_2x_i2c = { u8g_dev_ssd1306_128x64_2x_fn, &u8g_dev_ssd1306_128x64_2x_pb, U8G_COM_SSD_I2C }; - - -U8G_PB_DEV(u8g_dev_sh1106_128x64_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_sh1106_128x64_fn, U8G_COM_SW_SPI); -U8G_PB_DEV(u8g_dev_sh1106_128x64_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_sh1106_128x64_fn, U8G_COM_HW_SPI); -U8G_PB_DEV(u8g_dev_sh1106_128x64_i2c, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_sh1106_128x64_fn, U8G_COM_SSD_I2C); - -uint8_t u8g_dev_sh1106_128x64_2x_buf[WIDTH*2] U8G_NOCOMMON ; -u8g_pb_t u8g_dev_sh1106_128x64_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_sh1106_128x64_2x_buf}; -u8g_dev_t u8g_dev_sh1106_128x64_2x_sw_spi = { u8g_dev_sh1106_128x64_2x_fn, &u8g_dev_sh1106_128x64_2x_pb, U8G_COM_SW_SPI }; -u8g_dev_t u8g_dev_sh1106_128x64_2x_hw_spi = { u8g_dev_sh1106_128x64_2x_fn, &u8g_dev_sh1106_128x64_2x_pb, U8G_COM_HW_SPI }; -u8g_dev_t u8g_dev_sh1106_128x64_2x_i2c = { u8g_dev_sh1106_128x64_2x_fn, &u8g_dev_sh1106_128x64_2x_pb, U8G_COM_SSD_I2C }; - +// ================ u8g_dev_ssd1306_128x64.c ========== + +/* + + u8g_dev_ssd1306_128x64.c + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + +*/ + +#define WIDTH 128 +#define HEIGHT 64 +#define PAGE_HEIGHT 8 + +/* init sequence adafruit 128x64 OLED (NOT TESTED) */ +static const uint8_t u8g_dev_ssd1306_128x64_adafruit1_init_seq[] PROGMEM = { + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ + U8G_ESC_CS(1), /* enable chip */ + + 0x0ae, /* display off, sleep mode */ + 0x0d5, 0x080, /* clock divide ratio (0x00=1) and oscillator frequency (0x8) */ + 0x0a8, 0x03f, /* */ + + 0x0d3, 0x000, /* */ + + 0x040, /* start line */ + + 0x08d, 0x010, /* [1] charge pump setting (p62): 0x014 enable, 0x010 disable */ + + 0x020, 0x000, /* */ + 0x0a1, /* segment remap a0/a1*/ + 0x0c8, /* c0: scan dir normal, c8: reverse */ + 0x0da, 0x012, /* com pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5) */ + 0x081, 0x09f, /* [1] set contrast control */ + 0x0d9, 0x022, /* [1] pre-charge period 0x022/f1*/ + 0x0db, 0x040, /* vcomh deselect level */ + + 0x02e, /* 2012-05-27: Deactivate scroll */ + 0x0a4, /* output ram to display */ + 0x0a6, /* none inverted normal display mode */ + 0x0af, /* display on */ + + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_END /* end of sequence */ +}; + +/* init sequence adafruit 128x64 OLED (NOT TESTED) */ +static const uint8_t u8g_dev_ssd1306_128x64_adafruit2_init_seq[] PROGMEM = { + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ + U8G_ESC_CS(1), /* enable chip */ + + 0x0ae, /* display off, sleep mode */ + 0x0d5, 0x080, /* clock divide ratio (0x00=1) and oscillator frequency (0x8) */ + 0x0a8, 0x03f, /* */ + + 0x0d3, 0x000, /* */ + + 0x040, /* start line */ + + 0x08d, 0x014, /* [2] charge pump setting (p62): 0x014 enable, 0x010 disable */ + + 0x020, 0x000, /* */ + 0x0a1, /* segment remap a0/a1*/ + 0x0c8, /* c0: scan dir normal, c8: reverse */ + 0x0da, 0x012, /* com pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5) */ + 0x081, 0x0cf, /* [2] set contrast control */ + 0x0d9, 0x0f1, /* [2] pre-charge period 0x022/f1*/ + 0x0db, 0x040, /* vcomh deselect level */ + + 0x02e, /* 2012-05-27: Deactivate scroll */ + 0x0a4, /* output ram to display */ + 0x0a6, /* none inverted normal display mode */ + 0x0af, /* display on */ + + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_END /* end of sequence */ +}; + +/* init sequence adafruit 128x64 OLED (NOT TESTED), like adafruit3, but with page addressing mode */ +static const uint8_t u8g_dev_ssd1306_128x64_adafruit3_init_seq[] PROGMEM = { + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ + U8G_ESC_CS(1), /* enable chip */ + + 0x0ae, /* display off, sleep mode */ + 0x0d5, 0x080, /* clock divide ratio (0x00=1) and oscillator frequency (0x8) */ + 0x0a8, 0x03f, /* */ + + 0x0d3, 0x000, /* */ + + 0x040, /* start line */ + + 0x08d, 0x014, /* [2] charge pump setting (p62): 0x014 enable, 0x010 disable */ + + 0x020, 0x002, /* 2012-05-27: page addressing mode */ + 0x0a1, /* segment remap a0/a1*/ + 0x0c8, /* c0: scan dir normal, c8: reverse */ + 0x0da, 0x012, /* com pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5) */ + 0x081, 0x0cf, /* [2] set contrast control */ + 0x0d9, 0x0f1, /* [2] pre-charge period 0x022/f1*/ + 0x0db, 0x040, /* vcomh deselect level */ + + 0x02e, /* 2012-05-27: Deactivate scroll */ + 0x0a4, /* output ram to display */ + 0x0a6, /* none inverted normal display mode */ + 0x0af, /* display on */ + + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_END /* end of sequence */ +}; + +/* init sequence Univision datasheet (NOT TESTED) */ +static const uint8_t u8g_dev_ssd1306_128x64_univision_init_seq[] PROGMEM = { + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ + U8G_ESC_CS(1), /* enable chip */ + + 0x0ae, /* display off, sleep mode */ + 0x0d5, 0x080, /* clock divide ratio (0x00=1) and oscillator frequency (0x8) */ + 0x0a8, 0x03f, /* multiplex ratio */ + 0x0d3, 0x000, /* display offset */ + 0x040, /* start line */ + 0x08d, 0x010, /* charge pump setting (p62): 0x014 enable, 0x010 disable */ + 0x0a1, /* segment remap a0/a1*/ + 0x0c8, /* c0: scan dir normal, c8: reverse */ + 0x0da, 0x012, /* com pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5) */ + 0x081, 0x09f, /* set contrast control */ + 0x0d9, 0x022, /* pre-charge period */ + 0x0db, 0x040, /* vcomh deselect level */ + 0x022, 0x000, /* page addressing mode WRONG: 3 byte cmd! */ + 0x0a4, /* output ram to display */ + 0x0a6, /* none inverted normal display mode */ + 0x0af, /* display on */ + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_END /* end of sequence */ +}; + +/* select one init sequence here */ +//#define u8g_dev_ssd1306_128x64_init_seq u8g_dev_ssd1306_128x64_univision_init_seq +//#define u8g_dev_ssd1306_128x64_init_seq u8g_dev_ssd1306_128x64_adafruit1_init_seq +// 26. Apr 2014: in this thead: http://forum.arduino.cc/index.php?topic=234930.msg1696754;topicseen#msg1696754 +// it is mentiond, that adafruit2_init_seq works better --> this will be used by the ssd1306_adafruit device +//#define u8g_dev_ssd1306_128x64_init_seq u8g_dev_ssd1306_128x64_adafruit2_init_seq + +#define u8g_dev_ssd1306_128x64_init_seq u8g_dev_ssd1306_128x64_adafruit3_init_seq + + +static const uint8_t u8g_dev_ssd1306_128x64_data_start[] PROGMEM = { + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_CS(1), /* enable chip */ + 0x010, /* set upper 4 bit of the col adr to 0 */ + 0x000, /* set lower 4 bit of the col adr to 0 */ + U8G_ESC_END /* end of sequence */ +}; + +/* the sh1106 is compatible to the ssd1306, but is 132x64. display seems to be centered */ +static const uint8_t u8g_dev_sh1106_128x64_data_start[] PROGMEM = { + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_CS(1), /* enable chip */ + 0x010, /* set upper 4 bit of the col adr to 0 */ + 0x002, /* set lower 4 bit of the col adr to 2 (centered display with sh1106) */ + U8G_ESC_END /* end of sequence */ +}; + +static const uint8_t u8g_dev_ssd13xx_sleep_on[] PROGMEM = { + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_CS(1), /* enable chip */ + 0x0ae, /* display off */ + U8G_ESC_CS(0), /* disable chip, bugfix 12 nov 2014 */ + U8G_ESC_END /* end of sequence */ +}; + +static const uint8_t u8g_dev_ssd13xx_sleep_off[] PROGMEM = { + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_CS(1), /* enable chip */ + 0x0af, /* display on */ + U8G_ESC_DLY(50), /* delay 50 ms */ + U8G_ESC_CS(0), /* disable chip, bugfix 12 nov 2014 */ + U8G_ESC_END /* end of sequence */ +}; + +uint8_t u8g_dev_ssd1306_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + switch(msg) + { + case U8G_DEV_MSG_INIT: + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_adafruit2_init_seq); + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_NEXT: + { + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | pb->p.page); /* select current page (SSD1306) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + if ( u8g_pb_WriteBuffer(pb, u8g, dev) == 0 ) + return 0; + u8g_SetChipSelect(u8g, dev, 0); + } + break; + case U8G_DEV_MSG_SLEEP_ON: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); + return 1; + case U8G_DEV_MSG_SLEEP_OFF: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); + return 1; + } + return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); +} + +uint8_t u8g_dev_ssd1306_adafruit_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + switch(msg) + { + case U8G_DEV_MSG_INIT: + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_init_seq); + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_NEXT: + { + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | pb->p.page); /* select current page (SSD1306) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + if ( u8g_pb_WriteBuffer(pb, u8g, dev) == 0 ) + return 0; + u8g_SetChipSelect(u8g, dev, 0); + } + break; + case U8G_DEV_MSG_SLEEP_ON: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); + return 1; + case U8G_DEV_MSG_SLEEP_OFF: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); + return 1; + } + return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); +} + +uint8_t u8g_dev_sh1106_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + switch(msg) + { + case U8G_DEV_MSG_INIT: + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_init_seq); + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_NEXT: + { + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_sh1106_128x64_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | pb->p.page); /* select current page (SSD1306) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + if ( u8g_pb_WriteBuffer(pb, u8g, dev) == 0 ) + return 0; + u8g_SetChipSelect(u8g, dev, 0); + } + break; + case U8G_DEV_MSG_SLEEP_ON: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); + return 1; + case U8G_DEV_MSG_SLEEP_OFF: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); + return 1; + } + return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); +} + + +uint8_t u8g_dev_ssd1306_128x64_2x_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + switch(msg) + { + case U8G_DEV_MSG_INIT: + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_init_seq); + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_NEXT: + { + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | (pb->p.page*2)); /* select current page (SSD1306) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)pb->buf); + u8g_SetChipSelect(u8g, dev, 0); + + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | (pb->p.page*2+1)); /* select current page (SSD1306) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)(pb->buf)+pb->width); + u8g_SetChipSelect(u8g, dev, 0); + } + break; + case U8G_DEV_MSG_SLEEP_ON: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); + return 1; + case U8G_DEV_MSG_SLEEP_OFF: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); + return 1; + } + return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg); +} + +uint8_t u8g_dev_sh1106_128x64_2x_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + switch(msg) + { + case U8G_DEV_MSG_INIT: + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_300NS); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd1306_128x64_init_seq); + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_NEXT: + { + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + + u8g_WriteEscSeqP(u8g, dev, u8g_dev_sh1106_128x64_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | (pb->p.page*2)); /* select current page (SSD1306) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)pb->buf); + u8g_SetChipSelect(u8g, dev, 0); + + u8g_WriteEscSeqP(u8g, dev, u8g_dev_sh1106_128x64_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | (pb->p.page*2+1)); /* select current page (SSD1306) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)(pb->buf)+pb->width); + u8g_SetChipSelect(u8g, dev, 0); + } + break; + case U8G_DEV_MSG_SLEEP_ON: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_on); + return 1; + case U8G_DEV_MSG_SLEEP_OFF: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ssd13xx_sleep_off); + return 1; + } + return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg); +} + + + + +U8G_PB_DEV(u8g_dev_ssd1306_128x64_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_128x64_fn, U8G_COM_SW_SPI); +U8G_PB_DEV(u8g_dev_ssd1306_128x64_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_128x64_fn, U8G_COM_HW_SPI); +U8G_PB_DEV(u8g_dev_ssd1306_128x64_i2c, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_128x64_fn, U8G_COM_SSD_I2C); + +U8G_PB_DEV(u8g_dev_ssd1306_adafruit_128x64_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_adafruit_128x64_fn, U8G_COM_SW_SPI); +U8G_PB_DEV(u8g_dev_ssd1306_adafruit_128x64_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_adafruit_128x64_fn, U8G_COM_HW_SPI); +U8G_PB_DEV(u8g_dev_ssd1306_adafruit_128x64_i2c, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ssd1306_adafruit_128x64_fn, U8G_COM_SSD_I2C); + + +uint8_t u8g_dev_ssd1306_128x64_2x_buf[WIDTH*2] U8G_NOCOMMON ; +u8g_pb_t u8g_dev_ssd1306_128x64_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_ssd1306_128x64_2x_buf}; +u8g_dev_t u8g_dev_ssd1306_128x64_2x_sw_spi = { u8g_dev_ssd1306_128x64_2x_fn, &u8g_dev_ssd1306_128x64_2x_pb, U8G_COM_SW_SPI }; +u8g_dev_t u8g_dev_ssd1306_128x64_2x_hw_spi = { u8g_dev_ssd1306_128x64_2x_fn, &u8g_dev_ssd1306_128x64_2x_pb, U8G_COM_HW_SPI }; +u8g_dev_t u8g_dev_ssd1306_128x64_2x_i2c = { u8g_dev_ssd1306_128x64_2x_fn, &u8g_dev_ssd1306_128x64_2x_pb, U8G_COM_SSD_I2C }; + + +U8G_PB_DEV(u8g_dev_sh1106_128x64_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_sh1106_128x64_fn, U8G_COM_SW_SPI); +U8G_PB_DEV(u8g_dev_sh1106_128x64_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_sh1106_128x64_fn, U8G_COM_HW_SPI); +U8G_PB_DEV(u8g_dev_sh1106_128x64_i2c, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_sh1106_128x64_fn, U8G_COM_SSD_I2C); + +uint8_t u8g_dev_sh1106_128x64_2x_buf[WIDTH*2] U8G_NOCOMMON ; +u8g_pb_t u8g_dev_sh1106_128x64_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_sh1106_128x64_2x_buf}; +u8g_dev_t u8g_dev_sh1106_128x64_2x_sw_spi = { u8g_dev_sh1106_128x64_2x_fn, &u8g_dev_sh1106_128x64_2x_pb, U8G_COM_SW_SPI }; +u8g_dev_t u8g_dev_sh1106_128x64_2x_hw_spi = { u8g_dev_sh1106_128x64_2x_fn, &u8g_dev_sh1106_128x64_2x_pb, U8G_COM_HW_SPI }; +u8g_dev_t u8g_dev_sh1106_128x64_2x_i2c = { u8g_dev_sh1106_128x64_2x_fn, &u8g_dev_sh1106_128x64_2x_pb, U8G_COM_SSD_I2C }; + // ================ u8g_font.c =================== @@ -6809,11 +6816,11 @@ volatile uint8_t *u8g_outClock; static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) { -#ifdef UI_SPI_MOSI +#ifdef UI_SPI_MOSI SET_OUTPUT(UI_SPI_MOSI); SET_OUTPUT(UI_SPI_SCK); WRITE(UI_SPI_MOSI, LOW); - WRITE(UI_SPI_SCK, HIGH); + WRITE(UI_SPI_SCK, HIGH); #endif /* u8g_outData = portOutputRegister(digitalPinToPort(dataPin)); @@ -6832,8 +6839,8 @@ static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) U8G_NOINLINE; static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) { - uint8_t cnt = 8; /* + uint8_t cnt = 8; uint8_t bitData = u8g_bitData; uint8_t bitNotData = u8g_bitNotData; uint8_t bitClock = u8g_bitClock; @@ -6861,10 +6868,10 @@ static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) } while( cnt != 0 ); */ - U8G_ATOMIC_START(); - #ifdef UI_SPI_MOSI + U8G_ATOMIC_START(); + #ifdef UI_SPI_MOSI - for( cnt=0; cnt<8; cnt++ ) + for(uint8_t cnt=0; cnt<8; cnt++ ) { WRITE(UI_SPI_SCK, LOW); WRITE(UI_SPI_MOSI, val&0x80); @@ -6882,7 +6889,7 @@ asm volatile("nop\n\t" "nop\n\t" ::); //u8g_MicroDelay(); - } + } #endif U8G_ATOMIC_END(); } @@ -6982,8 +6989,6 @@ static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) static void u8g_com_arduino_st7920_write_byte_seq(uint8_t rs, uint8_t *ptr, uint8_t len) { - uint8_t i; - if ( rs == 0 ) { /* command */ @@ -7010,8 +7015,6 @@ static void u8g_com_arduino_st7920_write_byte_seq(uint8_t rs, uint8_t *ptr, uint static void u8g_com_arduino_st7920_write_byte(uint8_t rs, uint8_t val) { - uint8_t i; - if ( rs == 0 ) { /* command */ @@ -7613,3091 +7616,3098 @@ void u8g_DrawRBox(u8g_t *u8g, u8g_uint_t x, u8g_uint_t y, u8g_uint_t w, u8g_uint //u8g_draw_vline(u8g, x+w, yu, hh); } } - -// ============ u8g_com_arduino_ssd_i2c.c ================= - -/* - - u8g_com_arduino_ssd_i2c.c - - com interface for arduino (AND atmega) and the SSDxxxx chip (SOLOMON) variant - I2C protocol - - ToDo: Rename this to u8g_com_avr_ssd_i2c.c - - Universal 8bit Graphics Library - - Copyright (c) 2012, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - Special pin usage: - U8G_PI_I2C_OPTION additional options - U8G_PI_A0_STATE used to store the last value of the command/data register selection - U8G_PI_SET_A0 1: Signal request to update I2C device with new A0_STATE, 0: Do nothing, A0_STATE matches I2C device - U8G_PI_SCL clock line (NOT USED) - U8G_PI_SDA data line (NOT USED) - - U8G_PI_RESET reset line (currently disabled, see below) - - Protocol: - SLA, Cmd/Data Selection, Arguments - The command/data register is selected by a special instruction byte, which is sent after SLA - - The continue bit is always 0 so that a (re)start is equired for the change from cmd to/data mode -*/ - - -#if defined(U8G_WITH_PINLIST) - - -#define I2C_SLA (0x3c*2) -//#define I2C_CMD_MODE 0x080 -#define I2C_CMD_MODE 0x000 -#define I2C_DATA_MODE 0x040 - -uint8_t u8g_com_arduino_ssd_start_sequence(u8g_t *u8g) -{ - /* are we requested to set the a0 state? */ - if ( u8g->pin_list[U8G_PI_SET_A0] == 0 ) - return 1; - - /* setup bus, might be a repeated start */ - if ( u8g_i2c_start(I2C_SLA) == 0 ) - return 0; - if ( u8g->pin_list[U8G_PI_A0_STATE] == 0 ) - { - if ( u8g_i2c_send_byte(I2C_CMD_MODE) == 0 ) - return 0; - } - else - { - if ( u8g_i2c_send_byte(I2C_DATA_MODE) == 0 ) - return 0; - } - - u8g->pin_list[U8G_PI_SET_A0] = 0; - return 1; -} - -uint8_t u8g_com_arduino_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - switch(msg) - { - case U8G_COM_MSG_INIT: - //u8g_com_arduino_digital_write(u8g, U8G_PI_SCL, HIGH); - //u8g_com_arduino_digital_write(u8g, U8G_PI_SDA, HIGH); - //u8g->pin_list[U8G_PI_A0_STATE] = 0; /* inital RS state: unknown mode */ - - u8g_i2c_init(u8g->pin_list[U8G_PI_I2C_OPTION]); - - break; - - case U8G_COM_MSG_STOP: - break; - - case U8G_COM_MSG_RESET: - /* Currently disabled, but it could be enable. Previous restrictions have been removed */ - /* u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); */ - break; - - case U8G_COM_MSG_CHIP_SELECT: - u8g->pin_list[U8G_PI_A0_STATE] = 0; - u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again, also forces start condition */ - if ( arg_val == 0 ) - { - /* disable chip, send stop condition */ - u8g_i2c_stop(); - } - else - { - /* enable, do nothing: any byte writing will trigger the i2c start */ - } - break; - - case U8G_COM_MSG_WRITE_BYTE: - //u8g->pin_list[U8G_PI_SET_A0] = 1; - if ( u8g_com_arduino_ssd_start_sequence(u8g) == 0 ) - return u8g_i2c_stop(), 0; - if ( u8g_i2c_send_byte(arg_val) == 0 ) - return u8g_i2c_stop(), 0; - // u8g_i2c_stop(); - break; - - case U8G_COM_MSG_WRITE_SEQ: - //u8g->pin_list[U8G_PI_SET_A0] = 1; - if ( u8g_com_arduino_ssd_start_sequence(u8g) == 0 ) - return u8g_i2c_stop(), 0; - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - if ( u8g_i2c_send_byte(*ptr++) == 0 ) - return u8g_i2c_stop(), 0; - arg_val--; - } - } - // u8g_i2c_stop(); - break; - - case U8G_COM_MSG_WRITE_SEQ_P: - //u8g->pin_list[U8G_PI_SET_A0] = 1; - if ( u8g_com_arduino_ssd_start_sequence(u8g) == 0 ) - return u8g_i2c_stop(), 0; - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - if ( u8g_i2c_send_byte(u8g_pgm_read(ptr)) == 0 ) - return 0; - ptr++; - arg_val--; - } - } - // u8g_i2c_stop(); - break; - - case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ - u8g->pin_list[U8G_PI_A0_STATE] = arg_val; - u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again */ - -#ifdef OLD_CODE - if ( i2c_state != 0 ) - { - u8g_i2c_stop(); - i2c_state = 0; - } - - if ( u8g_com_arduino_ssd_start_sequence(arg_val) == 0 ) - return 0; - - /* setup bus, might be a repeated start */ - /* - if ( u8g_i2c_start(I2C_SLA) == 0 ) - return 0; - if ( arg_val == 0 ) - { - i2c_state = 1; - - if ( u8g_i2c_send_byte(I2C_CMD_MODE) == 0 ) - return 0; - } - else - { - i2c_state = 2; - if ( u8g_i2c_send_byte(I2C_DATA_MODE) == 0 ) - return 0; - } - */ -#endif - break; - } - return 1; -} - -#else /* defined(U8G_WITH_PINLIST) */ - -uint8_t u8g_com_arduino_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - return 1; -} - -#endif /* defined(U8G_WITH_PINLIST) */ - -// ============ u8g_com_i2c.c =============== - -/* - - u8g_com_i2c.c - - generic i2c interface - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - -*/ - - -//#define U8G_I2C_WITH_NO_ACK - -static uint8_t u8g_i2c_err_code; -static uint8_t u8g_i2c_opt; /* U8G_I2C_OPT_NO_ACK, SAM: U8G_I2C_OPT_DEV_1 */ -/* - position values - 1: start condition - 2: sla transfer -*/ -static uint8_t u8g_i2c_err_pos; - - -void u8g_i2c_clear_error(void) -{ - u8g_i2c_err_code = U8G_I2C_ERR_NONE; - u8g_i2c_err_pos = 0; -} - -uint8_t u8g_i2c_get_error(void) -{ - return u8g_i2c_err_code; -} - -uint8_t u8g_i2c_get_err_pos(void) -{ - return u8g_i2c_err_pos; -} - -static void u8g_i2c_set_error(uint8_t code, uint8_t pos) -{ - if ( u8g_i2c_err_code > 0 ) - return; - u8g_i2c_err_code |= code; - u8g_i2c_err_pos = pos; -} - - - -#if defined(__AVR__) -#define U8G_ATMEGA_HW_TWI - -/* remove the definition for attiny */ -#if __AVR_ARCH__ == 2 -#undef U8G_ATMEGA_HW_TWI -#endif -#if __AVR_ARCH__ == 25 -#undef U8G_ATMEGA_HW_TWI -#endif -#endif - -#if defined(U8G_ATMEGA_HW_TWI) - -#include -#include - - - -void u8g_i2c_init(uint8_t options) -{ - /* - TWBR: bit rate register - TWSR: status register (contains preselector bits) - - prescalar - 0 1 - 1 4 - 2 16 - 3 64 - - f = F_CPU/(16+2*TWBR*prescalar) - - F_CPU = 16MHz - TWBR = 152; - TWSR = 0; - --> 50KHz - - TWBR = 72; - TWSR = 0; - --> 100KHz - - TWBR = 12; - TWSR = 0; - --> 400KHz - - F_CPU/(2*100000)-8 --> calculate TWBR value for 100KHz -*/ - u8g_i2c_opt = options; - TWSR = 0; - if ( options & U8G_I2C_OPT_FAST ) - { - TWBR = F_CPU/(2*400000)-8; - } - else - { - TWBR = F_CPU/(2*100000)-8; - } - u8g_i2c_clear_error(); -} - -uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos) -{ - volatile uint16_t cnt = 2000; /* timout value should be > 280 for 50KHz Bus and 16 Mhz CPU, however the start condition might need longer */ - while( !(TWCR & mask) ) - { - if ( cnt == 0 ) - { - if ( u8g_i2c_opt & U8G_I2C_OPT_NO_ACK ) - { - return 1; /* all ok */ - } - else - { - u8g_i2c_set_error(U8G_I2C_ERR_TIMEOUT, pos); - return 0; /* error */ - } - } - cnt--; - } - return 1; /* all ok */ -} - -/* sla includes all 8 bits (with r/w bit), assums master transmit */ -uint8_t u8g_i2c_start(uint8_t sla) -{ - register uint8_t status; - - /* send start */ - TWCR = _BV(TWINT) | _BV(TWSTA) | _BV(TWEN); - - /* wait */ - if ( u8g_i2c_wait(_BV(TWINT), 1) == 0 ) - return 0; - - status = TW_STATUS; - - /* check status after start */ - if ( status != TW_START && status != TW_REP_START ) - { - u8g_i2c_set_error(U8G_I2C_ERR_BUS, 1); - return 0; - } - - /* set slave address */ - TWDR = sla; - - /* enable sla transfer */ - TWCR = _BV(TWINT) | _BV(TWEN); - - /* wait */ - if ( u8g_i2c_wait(_BV(TWINT), 2) == 0 ) - return 0; - - if ( u8g_i2c_opt & U8G_I2C_OPT_NO_ACK ) - { - /* do not check for ACK */ - } - else - { - status = TW_STATUS; - /* check status after sla */ - if ( status != TW_MT_SLA_ACK ) - { - u8g_i2c_set_error(U8G_I2C_ERR_BUS, 2); - return 0; - } - } - - return 1; -} - -uint8_t u8g_i2c_send_byte(uint8_t data) -{ - register uint8_t status; - TWDR = data; - TWCR = _BV(TWINT) | _BV(TWEN); - if ( u8g_i2c_wait(_BV(TWINT), 3) == 0 ) - return 0; - - if ( u8g_i2c_opt & U8G_I2C_OPT_NO_ACK ) - { - /* do not check for ACK */ - } - else - { - status = TW_STATUS; - if ( status != TW_MT_DATA_ACK ) - { - u8g_i2c_set_error(U8G_I2C_ERR_BUS, 3); - return 0; - } - } - - return 1; -} - -void u8g_i2c_stop(void) -{ - /* write stop */ - TWCR = _BV(TWINT) | _BV(TWEN) | _BV(TWSTO); - - /* no error is checked for the stop condition */ - u8g_i2c_wait(_BV(TWSTO), 4); - -} - -/* -void twi_send(uint8_t adr, uint8_t data1, uint8_t data2) -{ - u8g_i2c_start(adr<<1); - u8g_i2c_send_byte(data1); - u8g_i2c_send_byte(data2); - u8g_i2c_stop(); -} -*/ - -#elif defined(ARDUINO) && defined(__SAM3X8E__) -/* Arduino Due */ -#include "Arduino.h" -#include "sam.h" - -/* - -Controller - -TWI0 TWCK0 PA18 A DUE PCB: SCL1 -TWI0 TWD0 PA17 A DUE PCB: SDA1 -TWI1 TWCK1 PB13 A DUE PCB: SCL 21 -TWI1 TWD1 PB12 A DUE PCB: SDA 20 - -Arduino definitions - -#define PIN_WIRE_SDA (20u) -#define PIN_WIRE_SCL (21u) -#define WIRE_INTERFACE TWI1 -#define WIRE_INTERFACE_ID ID_TWI1 -#define WIRE_ISR_HANDLER TWI1_Handler - -#define PIN_WIRE1_SDA (70u) -#define PIN_WIRE1_SCL (71u) -#define WIRE1_INTERFACE TWI0 -#define WIRE1_INTERFACE_ID ID_TWI0 -#define WIRE1_ISR_HANDLER TWI0_Handler - - -*/ - -static void i2c_400KHz_delay(void) -{ - /* should be at least 4 */ - /* should be 5 for 100KHz transfer speed */ - - - /* - Arduino Due - 0x NOP: 470KHz - 4x NOP: 450KHz - 8x NOP: 430KHz - 16x NOP: 400KHz - */ - - __NOP(); - __NOP(); - __NOP(); - __NOP(); - - __NOP(); - __NOP(); - __NOP(); - __NOP(); - - __NOP(); - __NOP(); - __NOP(); - __NOP(); - - __NOP(); - __NOP(); - __NOP(); - __NOP(); -} - -static void i2c_100KHz_delay(void) -{ - /* - 1x u8g_MicroDelay() ca. 130KHz - 2x u8g_MicroDelay() ca. 80KHz - */ - u8g_MicroDelay(); - u8g_MicroDelay(); -} - - -uint32_t i2c_started = 0; -uint32_t i2c_scl_pin = 0; -uint32_t i2c_sda_pin = 0; -void (*i2c_delay)(void) = i2c_100KHz_delay; - -const PinDescription *i2c_scl_pin_desc; -const PinDescription *i2c_sda_pin_desc; - - -/* maybe this can be optimized */ -static void i2c_init(void) -{ - i2c_sda_pin_desc = &(g_APinDescription[i2c_sda_pin]); - i2c_scl_pin_desc = &(g_APinDescription[i2c_scl_pin]); - pinMode(i2c_sda_pin, OUTPUT); - digitalWrite(i2c_sda_pin, HIGH); - pinMode(i2c_scl_pin, OUTPUT); - digitalWrite(i2c_scl_pin, HIGH); - PIO_Configure( i2c_sda_pin_desc->pPort, PIO_OUTPUT_0, i2c_sda_pin_desc->ulPin, PIO_OPENDRAIN ); - PIO_Configure( i2c_scl_pin_desc->pPort, PIO_OUTPUT_0, i2c_scl_pin_desc->ulPin, PIO_OPENDRAIN ); - PIO_Clear( i2c_sda_pin_desc->pPort, i2c_sda_pin_desc->ulPin) ; - PIO_Clear( i2c_scl_pin_desc->pPort, i2c_scl_pin_desc->ulPin) ; - PIO_Configure( i2c_sda_pin_desc->pPort, PIO_INPUT, i2c_sda_pin_desc->ulPin, PIO_DEFAULT ) ; - PIO_Configure( i2c_scl_pin_desc->pPort, PIO_INPUT, i2c_scl_pin_desc->ulPin, PIO_DEFAULT ) ; - i2c_delay(); -} - -/* actually, the scl line is not observed, so this procedure does not return a value */ -static void i2c_read_scl_and_delay(void) -{ - uint32_t dwMask = i2c_scl_pin_desc->ulPin; - //PIO_Configure( i2c_scl_pin_desc->pPort, PIO_INPUT, i2c_scl_pin_desc->ulPin, PIO_DEFAULT ) ; - //PIO_SetInput( i2c_scl_pin_desc->pPort, i2c_scl_pin_desc->ulPin, PIO_DEFAULT ) ; - - /* set as input */ - i2c_scl_pin_desc->pPort->PIO_ODR = dwMask ; - i2c_scl_pin_desc->pPort->PIO_PER = dwMask ; - - i2c_delay(); -} - -static void i2c_clear_scl(void) -{ - uint32_t dwMask = i2c_scl_pin_desc->ulPin; - - /* set open collector and drive low */ - //PIO_Configure( i2c_scl_pin_desc->pPort, PIO_OUTPUT_0, i2c_scl_pin_desc->ulPin, PIO_OPENDRAIN ); - //PIO_SetOutput( i2c_scl_pin_desc->pPort, i2c_scl_pin_desc->ulPin, 0, 1, 0); - - /* open drain, zero default output */ - i2c_scl_pin_desc->pPort->PIO_MDER = dwMask; - i2c_scl_pin_desc->pPort->PIO_CODR = dwMask; - i2c_scl_pin_desc->pPort->PIO_OER = dwMask; - i2c_scl_pin_desc->pPort->PIO_PER = dwMask; - - //PIO_Clear( i2c_scl_pin_desc->pPort, i2c_scl_pin_desc->ulPin) ; -} - -static uint8_t i2c_read_sda(void) -{ - uint32_t dwMask = i2c_sda_pin_desc->ulPin; - //PIO_Configure( i2c_sda_pin_desc->pPort, PIO_INPUT, i2c_sda_pin_desc->ulPin, PIO_DEFAULT ) ; - //PIO_SetInput( i2c_sda_pin_desc->pPort, i2c_sda_pin_desc->ulPin, PIO_DEFAULT ) ; - - /* set as input */ - i2c_sda_pin_desc->pPort->PIO_ODR = dwMask ; - i2c_sda_pin_desc->pPort->PIO_PER = dwMask ; - - - return 1; -} - -static void i2c_clear_sda(void) -{ - uint32_t dwMask = i2c_sda_pin_desc->ulPin; - - /* set open collector and drive low */ - //PIO_Configure( i2c_sda_pin_desc->pPort, PIO_OUTPUT_0, i2c_sda_pin_desc->ulPin, PIO_OPENDRAIN ); - //PIO_SetOutput( i2c_sda_pin_desc->pPort, i2c_sda_pin_desc->ulPin, 0, 1, 0); - - /* open drain, zero default output */ - i2c_sda_pin_desc->pPort->PIO_MDER = dwMask ; - i2c_sda_pin_desc->pPort->PIO_CODR = dwMask ; - i2c_sda_pin_desc->pPort->PIO_OER = dwMask ; - i2c_sda_pin_desc->pPort->PIO_PER = dwMask ; - - //PIO_Clear( i2c_sda_pin_desc->pPort, i2c_sda_pin_desc->ulPin) ; -} - -static void i2c_start(void) -{ - if ( i2c_started != 0 ) - { - /* if already started: do restart */ - i2c_read_sda(); /* SDA = 1 */ - i2c_delay(); - i2c_read_scl_and_delay(); - } - i2c_read_sda(); - /* - if (i2c_read_sda() == 0) - { - // do something because arbitration is lost - } - */ - /* send the start condition, both lines go from 1 to 0 */ - i2c_clear_sda(); - i2c_delay(); - i2c_clear_scl(); - i2c_started = 1; -} - - -static void i2c_stop(void) -{ - /* set SDA to 0 */ - i2c_clear_sda(); - i2c_delay(); - - /* now release all lines */ - i2c_read_scl_and_delay(); - - /* set SDA to 1 */ - i2c_read_sda(); - i2c_delay(); - i2c_started = 0; -} - -static void i2c_write_bit(uint8_t val) -{ - if (val) - i2c_read_sda(); - else - i2c_clear_sda(); - - i2c_delay(); - i2c_read_scl_and_delay(); - i2c_clear_scl(); -} - -static uint8_t i2c_read_bit(void) -{ - uint8_t val; - /* do not drive SDA */ - i2c_read_sda(); - i2c_delay(); - i2c_read_scl_and_delay(); - val = i2c_read_sda(); - i2c_delay(); - i2c_clear_scl(); - return val; -} - -static uint8_t i2c_write_byte(uint8_t b) -{ - i2c_write_bit(b & 128); - i2c_write_bit(b & 64); - i2c_write_bit(b & 32); - i2c_write_bit(b & 16); - i2c_write_bit(b & 8); - i2c_write_bit(b & 4); - i2c_write_bit(b & 2); - i2c_write_bit(b & 1); - - /* read ack from client */ - /* 0: ack was given by client */ - /* 1: nothing happend during ack cycle */ - return i2c_read_bit(); -} - - - -void u8g_i2c_init(uint8_t options) -{ - u8g_i2c_opt = options; - u8g_i2c_clear_error(); - - if ( u8g_i2c_opt & U8G_I2C_OPT_FAST ) - { - i2c_delay = i2c_400KHz_delay; - } - else - { - i2c_delay = i2c_100KHz_delay; - } - - - if ( u8g_i2c_opt & U8G_I2C_OPT_DEV_1 ) - { - i2c_scl_pin = PIN_WIRE1_SCL; - i2c_sda_pin = PIN_WIRE1_SDA; - - //REG_PIOA_PDR = PIO_PB12A_TWD1 | PIO_PB13A_TWCK1; - } - else - { - - i2c_scl_pin = PIN_WIRE_SCL; - i2c_sda_pin = PIN_WIRE_SDA; - - //REG_PIOA_PDR = PIO_PA17A_TWD0 | PIO_PA18A_TWCK0; - } - - i2c_init(); - -} - -/* sla includes also the r/w bit */ -uint8_t u8g_i2c_start(uint8_t sla) -{ - i2c_start(); - i2c_write_byte(sla); - return 1; -} - -uint8_t u8g_i2c_send_byte(uint8_t data) -{ - return i2c_write_byte(data); -} - -void u8g_i2c_stop(void) -{ - i2c_stop(); -} - - -#elif defined(U8G_RASPBERRY_PI) - -#include -#include -#include -#include -#include - -#define I2C_SLA 0x3c - -static int fd=-1; -static uint8_t i2cMode = 0; - -void u8g_i2c_init(uint8_t options) { - u8g_i2c_clear_error(); - u8g_i2c_opt = options; - - if (wiringPiSetup() == -1) { - printf("wiringPi-Error\n"); - exit(1); - } - - fd = wiringPiI2CSetup(I2C_SLA); - if (fd < 0) { - printf ("Unable to open I2C device 0: %s\n", strerror (errno)) ; - exit (1) ; - } - //u8g_SetPIOutput(u8g, U8G_PI_RESET); - //u8g_SetPIOutput(u8g, U8G_PI_A0); -} -uint8_t u8g_i2c_start(uint8_t sla) { - u8g_i2c_send_mode(0); - - return 1; -} - -void u8g_i2c_stop(void) { -} - -uint8_t u8g_i2c_send_mode(uint8_t mode) { - i2cMode = mode; -} - -uint8_t u8g_i2c_send_byte(uint8_t data) { - wiringPiI2CWriteReg8(fd, i2cMode, data); - - return 1; -} - -uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos) -{ - return 1; -} - -#else - -/* empty interface */ - -void u8g_i2c_init(uint8_t options) -{ - u8g_i2c_clear_error(); -} - -uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos) -{ - return 1; -} - -uint8_t u8g_i2c_start(uint8_t sla) -{ - return 1; -} -uint8_t u8g_i2c_send_byte(uint8_t data) -{ - return 1; -} - -void u8g_i2c_stop(void) -{ -} - - -#endif -// ============== u8g_pb8v1.c =============== - -/* - - u8g_pb8v1.c - - 8bit height monochrom (1 bit) page buffer - byte has vertical orientation - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - -*/ - -void u8g_pb8v1_Init(u8g_pb_t *b, void *buf, u8g_uint_t width) U8G_NOINLINE; -void u8g_pb8v1_set_pixel(u8g_pb_t *b, u8g_uint_t x, u8g_uint_t y, uint8_t color_index) U8G_NOINLINE; -void u8g_pb8v1_SetPixel(u8g_pb_t *b, const u8g_dev_arg_pixel_t * const arg_pixel) U8G_NOINLINE ; -void u8g_pb8v1_Set8PixelStd(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) U8G_NOINLINE; - -/* Obsolete, usually set by the init of the structure */ -void u8g_pb8v1_Init(u8g_pb_t *b, void *buf, u8g_uint_t width) -{ - b->buf = buf; - b->width = width; - u8g_pb_Clear(b); -} - -void u8g_pb8v1_set_pixel(u8g_pb_t *b, u8g_uint_t x, u8g_uint_t y, uint8_t color_index) -{ - register uint8_t mask; - uint8_t *ptr = (uint8_t*)b->buf; - - y -= b->p.page_y0; - mask = 1; - y &= 0x07; - mask <<= y; - ptr += x; - if ( color_index ) - { - *ptr |= mask; - } - else - { - mask ^=0xff; - *ptr &= mask; - } -} - - -void u8g_pb8v1_SetPixel(u8g_pb_t *b, const u8g_dev_arg_pixel_t * const arg_pixel) -{ - if ( arg_pixel->y < b->p.page_y0 ) - return; - if ( arg_pixel->y > b->p.page_y1 ) - return; - if ( arg_pixel->x >= b->width ) - return; - u8g_pb8v1_set_pixel(b, arg_pixel->x, arg_pixel->y, arg_pixel->color); -} - -void u8g_pb8v1_Set8PixelStd(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) -{ - register uint8_t pixel = arg_pixel->pixel; - do - { - if ( pixel & 128 ) - { - u8g_pb8v1_SetPixel(b, arg_pixel); - } - switch( arg_pixel->dir ) - { - case 0: arg_pixel->x++; break; - case 1: arg_pixel->y++; break; - case 2: arg_pixel->x--; break; - case 3: arg_pixel->y--; break; - } - pixel <<= 1; - } while( pixel != 0 ); -} - - -void u8g_pb8v1_Set8PixelOpt2(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) -{ - register uint8_t pixel = arg_pixel->pixel; - u8g_uint_t dx = 0; - u8g_uint_t dy = 0; - - switch( arg_pixel->dir ) - { - case 0: dx++; break; - case 1: dy++; break; - case 2: dx--; break; - case 3: dy--; break; - } - - do - { - if ( pixel & 128 ) - u8g_pb8v1_SetPixel(b, arg_pixel); - arg_pixel->x += dx; - arg_pixel->y += dy; - pixel <<= 1; - } while( pixel != 0 ); - -} - -uint8_t u8g_dev_pb8v1_base_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - switch(msg) - { - case U8G_DEV_MSG_SET_8PIXEL: - if ( u8g_pb_Is8PixelVisible(pb, (u8g_dev_arg_pixel_t *)arg) ) - u8g_pb8v1_Set8PixelOpt2(pb, (u8g_dev_arg_pixel_t *)arg); - break; - case U8G_DEV_MSG_SET_PIXEL: - u8g_pb8v1_SetPixel(pb, (u8g_dev_arg_pixel_t *)arg); - break; - case U8G_DEV_MSG_INIT: - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_FIRST: - u8g_pb_Clear(pb); - u8g_page_First(&(pb->p)); - break; - case U8G_DEV_MSG_PAGE_NEXT: - if ( u8g_page_Next(&(pb->p)) == 0 ) - return 0; - u8g_pb_Clear(pb); - break; -#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION - case U8G_DEV_MSG_IS_BBX_INTERSECTION: - return u8g_pb_IsIntersection(pb, (u8g_dev_arg_bbx_t *)arg); -#endif - case U8G_DEV_MSG_GET_PAGE_BOX: - u8g_pb_GetPageBox(pb, (u8g_box_t *)arg); - break; - case U8G_DEV_MSG_GET_WIDTH: - *((u8g_uint_t *)arg) = pb->width; - break; - case U8G_DEV_MSG_GET_HEIGHT: - *((u8g_uint_t *)arg) = pb->p.total_height; - break; - case U8G_DEV_MSG_SET_COLOR_ENTRY: - break; - case U8G_DEV_MSG_SET_XY_CB: - break; - case U8G_DEV_MSG_GET_MODE: - return U8G_MODE_BW; - } - return 1; -} - - -// ============== u8g_pb16v1.c ================ - -/* - - u8g_pb16v1.c - - 16bit height monochrom (1 bit) page buffer - byte has vertical orientation - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - -*/ - -#include - -void u8g_pb16v1_Init(u8g_pb_t *b, void *buf, u8g_uint_t width) U8G_NOINLINE; -void u8g_pb16v1_set_pixel(u8g_pb_t *b, u8g_uint_t x, u8g_uint_t y, uint8_t color_index) U8G_NOINLINE; -void u8g_pb16v1_SetPixel(u8g_pb_t *b, const u8g_dev_arg_pixel_t * const arg_pixel) U8G_NOINLINE ; -void u8g_pb16v1_Set8PixelStd(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) U8G_NOINLINE; - - -void u8g_pb16v1_Clear(u8g_pb_t *b) -{ - uint8_t *ptr = (uint8_t *)b->buf; - uint8_t *end_ptr = ptr; - end_ptr += b->width*2; - do - { - *ptr++ = 0; - } while( ptr != end_ptr ); -} - -/* Obsolete, usually set by the init of the structure */ -void u8g_pb16v1_Init(u8g_pb_t *b, void *buf, u8g_uint_t width) -{ - b->buf = buf; - b->width = width; - u8g_pb16v1_Clear(b); -} - -void u8g_pb16v1_set_pixel(u8g_pb_t *b, u8g_uint_t x, u8g_uint_t y, uint8_t color_index) -{ - register uint8_t mask; - uint8_t *ptr = (uint8_t*)b->buf; - - y -= b->p.page_y0; - if ( y >= 8 ) - { - ptr += b->width; - y &= 0x07; - } - mask = 1; - mask <<= y; - ptr += x; - if ( color_index ) - { - *ptr |= mask; - } - else - { - mask ^=0xff; - *ptr &= mask; - } -} - - -void u8g_pb16v1_SetPixel(u8g_pb_t *b, const u8g_dev_arg_pixel_t * const arg_pixel) -{ - if ( arg_pixel->y < b->p.page_y0 ) - return; - if ( arg_pixel->y > b->p.page_y1 ) - return; - if ( arg_pixel->x >= b->width ) - return; - u8g_pb16v1_set_pixel(b, arg_pixel->x, arg_pixel->y, arg_pixel->color); -} - -void u8g_pb16v1_Set8PixelStd(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) -{ - register uint8_t pixel = arg_pixel->pixel; - do - { - if ( pixel & 128 ) - { - u8g_pb16v1_SetPixel(b, arg_pixel); - } - switch( arg_pixel->dir ) - { - case 0: arg_pixel->x++; break; - case 1: arg_pixel->y++; break; - case 2: arg_pixel->x--; break; - case 3: arg_pixel->y--; break; - } - pixel <<= 1; - } while( pixel != 0 ); -} - - -void u8g_pb16v1_Set8PixelOpt2(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) -{ - register uint8_t pixel = arg_pixel->pixel; - u8g_uint_t dx = 0; - u8g_uint_t dy = 0; - - switch( arg_pixel->dir ) - { - case 0: dx++; break; - case 1: dy++; break; - case 2: dx--; break; - case 3: dy--; break; - } - - do - { - if ( pixel & 128 ) - u8g_pb16v1_SetPixel(b, arg_pixel); - arg_pixel->x += dx; - arg_pixel->y += dy; - pixel <<= 1; - } while( pixel != 0 ); - -} - -uint8_t u8g_dev_pb16v1_base_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - switch(msg) - { - case U8G_DEV_MSG_SET_8PIXEL: - if ( u8g_pb_Is8PixelVisible(pb, (u8g_dev_arg_pixel_t *)arg) ) - u8g_pb16v1_Set8PixelOpt2(pb, (u8g_dev_arg_pixel_t *)arg); - break; - case U8G_DEV_MSG_SET_PIXEL: - u8g_pb16v1_SetPixel(pb, (u8g_dev_arg_pixel_t *)arg); - break; - case U8G_DEV_MSG_INIT: - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_FIRST: - u8g_pb16v1_Clear(pb); - u8g_page_First(&(pb->p)); - break; - case U8G_DEV_MSG_PAGE_NEXT: - if ( u8g_page_Next(&(pb->p)) == 0 ) - return 0; - u8g_pb16v1_Clear(pb); - break; -#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION - case U8G_DEV_MSG_IS_BBX_INTERSECTION: - return u8g_pb_IsIntersection(pb, (u8g_dev_arg_bbx_t *)arg); -#endif - case U8G_DEV_MSG_GET_PAGE_BOX: - u8g_pb_GetPageBox(pb, (u8g_box_t *)arg); - break; - case U8G_DEV_MSG_GET_WIDTH: - *((u8g_uint_t *)arg) = pb->width; - break; - case U8G_DEV_MSG_GET_HEIGHT: - *((u8g_uint_t *)arg) = pb->p.total_height; - break; - case U8G_DEV_MSG_SET_COLOR_ENTRY: - break; - case U8G_DEV_MSG_SET_XY_CB: - break; - case U8G_DEV_MSG_GET_MODE: - return U8G_MODE_BW; - } - return 1; -} - -// ========== u8g_arduino_sw_spi.c ================ - -/* - - u8g_arduino_sw_spi.c - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - Update for ATOMIC operation done (01 Jun 2013) - U8G_ATOMIC_OR(ptr, val) - U8G_ATOMIC_AND(ptr, val) - U8G_ATOMIC_START(); - U8G_ATOMIC_END(); - - -*/ - -#if defined(ARDUINO) - -/*=========================================================*/ -/* Arduino, AVR */ - -#if defined(__AVR__) - -//uint8_t u8g_bitData, u8g_bitNotData; -//uint8_t u8g_bitClock, u8g_bitNotClock; -//volatile uint8_t *u8g_outData; -//volatile uint8_t *u8g_outClock; - -/*static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) -{ - u8g_outData = portOutputRegister(digitalPinToPort(dataPin)); - u8g_outClock = portOutputRegister(digitalPinToPort(clockPin)); - u8g_bitData = digitalPinToBitMask(dataPin); - u8g_bitClock = digitalPinToBitMask(clockPin); - - u8g_bitNotClock = u8g_bitClock; - u8g_bitNotClock ^= 0x0ff; - - u8g_bitNotData = u8g_bitData; - u8g_bitNotData ^= 0x0ff; -} - -static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) U8G_NOINLINE; -static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) -{ - uint8_t cnt = 8; - uint8_t bitData = u8g_bitData; - uint8_t bitNotData = u8g_bitNotData; - uint8_t bitClock = u8g_bitClock; - uint8_t bitNotClock = u8g_bitNotClock; - volatile uint8_t *outData = u8g_outData; - volatile uint8_t *outClock = u8g_outClock; - U8G_ATOMIC_START(); - do - { - if ( val & 128 ) - *outData |= bitData; - else - *outData &= bitNotData; - - *outClock |= bitClock; - val <<= 1; - cnt--; - *outClock &= bitNotClock; - } while( cnt != 0 ); - U8G_ATOMIC_END(); -}*/ - -/*=========================================================*/ -/* Arduino, Chipkit */ -#elif defined(__18CXX) || defined(__PIC32MX) - -uint16_t dog_bitData, dog_bitNotData; -uint16_t dog_bitClock, dog_bitNotClock; -volatile uint32_t *dog_outData; -volatile uint32_t *dog_outClock; -volatile uint32_t dog_pic32_spi_tmp; - -static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) -{ - dog_outData = portOutputRegister(digitalPinToPort(dataPin)); - dog_outClock = portOutputRegister(digitalPinToPort(clockPin)); - dog_bitData = digitalPinToBitMask(dataPin); - dog_bitClock = digitalPinToBitMask(clockPin); - - dog_bitNotClock = dog_bitClock; - dog_bitNotClock ^= 0x0ffff; - - dog_bitNotData = dog_bitData; - dog_bitNotData ^= 0x0ffff; -} - -static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) -{ - uint8_t cnt = 8; - U8G_ATOMIC_START(); - do - { - if ( val & 128 ) - *dog_outData |= dog_bitData; - else - *dog_outData &= dog_bitNotData; - val <<= 1; - /* - There must be some delay here. However - fetching the adress dog_outClock is enough delay, so - do not place dog_outClock in a local variable. This will - break the procedure - */ - *dog_outClock |= dog_bitClock; - cnt--; - *dog_outClock &= dog_bitNotClock; - /* - little additional delay after clk pulse, done by 3x32bit reads - from I/O. Optimized for PIC32 with 80 MHz. - */ - dog_pic32_spi_tmp = *dog_outClock; - dog_pic32_spi_tmp = *dog_outClock; - dog_pic32_spi_tmp = *dog_outClock; - } while( cnt != 0 ); - U8G_ATOMIC_END(); -} - -/*=========================================================*/ -/* Arduino Due */ -#elif defined(__SAM3X8E__) - -/* Due */ - -void u8g_digital_write_sam_high(uint8_t pin) -{ - PIO_Set( g_APinDescription[pin].pPort, g_APinDescription[pin].ulPin) ; -} - -void u8g_digital_write_sam_low(uint8_t pin) -{ - PIO_Clear( g_APinDescription[pin].pPort, g_APinDescription[pin].ulPin) ; -} - -static uint8_t u8g_sam_data_pin; -static uint8_t u8g_sam_clock_pin; - -/*static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) -{ - u8g_sam_data_pin = dataPin; - u8g_sam_clock_pin = clockPin; -} - -static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) -{ - uint8_t i = 8; - do - { - if ( val & 128 ) - u8g_digital_write_sam_high(u8g_sam_data_pin); - else - u8g_digital_write_sam_low(u8g_sam_data_pin); - val <<= 1; - //u8g_MicroDelay(); - u8g_digital_write_sam_high(u8g_sam_clock_pin); - u8g_MicroDelay(); - u8g_digital_write_sam_low(u8g_sam_clock_pin); - u8g_MicroDelay(); - i--; - } while( i != 0 ); -} -*/ - -#else -/* empty interface */ - -static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) -{ -} - -static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) -{ -} - -#endif - - -uint8_t u8g_com_arduino_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - switch(msg) - { - case U8G_COM_MSG_INIT: - u8g_com_arduino_assign_pin_output_high(u8g); - u8g_com_arduino_digital_write(u8g, U8G_PI_SCK, LOW); - u8g_com_arduino_digital_write(u8g, U8G_PI_MOSI, LOW); - u8g_com_arduino_init_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK]); - break; - - case U8G_COM_MSG_STOP: - break; - - case U8G_COM_MSG_RESET: - if ( u8g->pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) - u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); - break; - - case U8G_COM_MSG_CHIP_SELECT: - if ( arg_val == 0 ) - { - /* disable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS, HIGH); - } - else - { - /* enable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_SCK, LOW); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS, LOW); - /* issue 227 */ - u8g_com_arduino_init_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK]); - } - break; - - case U8G_COM_MSG_WRITE_BYTE: - u8g_com_arduino_do_shift_out_msb_first( arg_val ); - //u8g_arduino_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], arg_val); - break; - - case U8G_COM_MSG_WRITE_SEQ: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_com_arduino_do_shift_out_msb_first(*ptr++); - // u8g_arduino_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], *ptr++); - arg_val--; - } - } - break; - - case U8G_COM_MSG_WRITE_SEQ_P: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_com_arduino_do_shift_out_msb_first( u8g_pgm_read(ptr) ); - //u8g_arduino_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], u8g_pgm_read(ptr)); - ptr++; - arg_val--; - } - } - break; - - case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ - u8g_com_arduino_digital_write(u8g, U8G_PI_A0, arg_val); - break; - } - return 1; -} - -#else /* ARDUINO */ - -uint8_t u8g_com_arduino_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - return 1; -} - -#endif /* ARDUINO */ - -// ================ u8g_dev_ks0108_128x64.c =================== - -/* - - u8g_dev_ks0108_128x64.c - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - - ADDRESS = 0 (Command Mode) - 0x03f Display On - 0x0c0 Start Display at line 0 - 0x040 | y write to y address (y:0..63) - 0x0b8 | x write to page [0..7] - - - u8g_Init8Bit(u8g, dev, d0, d1, d2, d3, d4, d5, d6, d7, en, cs1, cs2, di, rw, reset) - u8g_Init8Bit(u8g, dev, 8, 9, 10, 11, 4, 5, 6, 7, 18, 14, 15, 17, 16, U8G_PIN_NONE) - -*/ - -#define WIDTH 128 -#define HEIGHT 64 -#define PAGE_HEIGHT 8 - -static const uint8_t u8g_dev_ks0108_128x64_init_seq[] PROGMEM = { - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ - U8G_ESC_CS(1), /* enable chip 1 */ - 0x03f, /* display on */ - 0x0c0, /* start at line 0 */ - U8G_ESC_DLY(20), /* delay 20 ms */ - U8G_ESC_CS(2), /* enable chip 2 */ - 0x03f, /* display on */ - 0x0c0, /* start at line 0 */ - U8G_ESC_DLY(20), /* delay 20 ms */ - U8G_ESC_CS(0), /* disable all chips */ - U8G_ESC_END /* end of sequence */ -}; - - -uint8_t u8g_dev_ks0108_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - - switch(msg) - { - case U8G_DEV_MSG_INIT: - u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_NONE); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_ks0108_128x64_init_seq); - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_NEXT: - { - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - - u8g_SetAddress(u8g, dev, 0); /* command mode */ - u8g_SetChipSelect(u8g, dev, 2); - u8g_WriteByte(u8g, dev, 0x0b8 | pb->p.page); /* select current page (KS0108b) */ - u8g_WriteByte(u8g, dev, 0x040 ); /* set address 0 */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - u8g_WriteSequence(u8g, dev, 64, (uint8_t*)pb->buf); - u8g_SetChipSelect(u8g, dev, 0); - - u8g_SetAddress(u8g, dev, 0); /* command mode */ - u8g_SetChipSelect(u8g, dev, 1); - u8g_WriteByte(u8g, dev, 0x0b8 | pb->p.page); /* select current page (KS0108b) */ - u8g_WriteByte(u8g, dev, 0x040 ); /* set address 0 */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - u8g_WriteSequence(u8g, dev, 64, 64+(uint8_t *)pb->buf); - u8g_SetChipSelect(u8g, dev, 0); - - } - break; - } - return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); -} - -U8G_PB_DEV(u8g_dev_ks0108_128x64, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ks0108_128x64_fn, U8G_COM_PARALLEL); -U8G_PB_DEV(u8g_dev_ks0108_128x64_fast, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ks0108_128x64_fn, U8G_COM_FAST_PARALLEL); - -// ================= 8g_com_arduino_parallel.c ================== - -/* - - u8g_com_arduino_parallel.c - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - - PIN_D0 8 - PIN_D1 9 - PIN_D2 10 - PIN_D3 11 - PIN_D4 4 - PIN_D5 5 - PIN_D6 6 - PIN_D7 7 - - PIN_CS1 14 - PIN_CS2 15 - PIN_RW 16 - PIN_DI 17 - PIN_EN 18 - - u8g_Init8Bit(u8g, dev, d0, d1, d2, d3, d4, d5, d6, d7, en, cs1, cs2, di, rw, reset) - u8g_Init8Bit(u8g, dev, 8, 9, 10, 11, 4, 5, 6, 7, 18, 14, 15, 17, 16, U8G_PIN_NONE) - -*/ - -#if defined(ARDUINO) - - -void u8g_com_arduino_parallel_write(u8g_t *u8g, uint8_t val) -{ - u8g_com_arduino_digital_write(u8g, U8G_PI_D0, val&1); - val >>= 1; - u8g_com_arduino_digital_write(u8g, U8G_PI_D1, val&1); - val >>= 1; - u8g_com_arduino_digital_write(u8g, U8G_PI_D2, val&1); - val >>= 1; - u8g_com_arduino_digital_write(u8g, U8G_PI_D3, val&1); - val >>= 1; - u8g_com_arduino_digital_write(u8g, U8G_PI_D4, val&1); - val >>= 1; - u8g_com_arduino_digital_write(u8g, U8G_PI_D5, val&1); - val >>= 1; - u8g_com_arduino_digital_write(u8g, U8G_PI_D6, val&1); - val >>= 1; - u8g_com_arduino_digital_write(u8g, U8G_PI_D7, val&1); - - /* EN cycle time must be 1 micro second, digitalWrite is slow enough to do this */ - u8g_com_arduino_digital_write(u8g, U8G_PI_EN, HIGH); - u8g_MicroDelay(); /* delay by 1000ns, reference: ST7920: 140ns, SBN1661: 100ns */ - u8g_com_arduino_digital_write(u8g, U8G_PI_EN, LOW); - u8g_10MicroDelay(); /* ST7920 commands: 72us */ -} - - -uint8_t u8g_com_arduino_parallel_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - switch(msg) - { - case U8G_COM_MSG_INIT: - /* setup the RW pin as output and force it to low */ - if ( u8g->pin_list[U8G_PI_RW] != U8G_PIN_NONE ) - { - pinMode(u8g->pin_list[U8G_PI_RW], OUTPUT); - u8g_com_arduino_digital_write(u8g, U8G_PI_RW, LOW); - } - /* set all pins (except RW pin) */ - u8g_com_arduino_assign_pin_output_high(u8g); - break; - case U8G_COM_MSG_STOP: - break; - case U8G_COM_MSG_CHIP_SELECT: - if ( arg_val == 0 ) - { - /* disable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, HIGH); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, HIGH); - } - else if ( arg_val == 1 ) - { - /* enable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, LOW); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, HIGH); - } - else if ( arg_val == 2 ) - { - /* enable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, HIGH); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, LOW); - } - else - { - /* enable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, LOW); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, LOW); - } - break; - case U8G_COM_MSG_WRITE_BYTE: - u8g_com_arduino_parallel_write(u8g, arg_val); - break; - case U8G_COM_MSG_WRITE_SEQ: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_com_arduino_parallel_write(u8g, *ptr++); - arg_val--; - } - } - break; - case U8G_COM_MSG_WRITE_SEQ_P: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_com_arduino_parallel_write(u8g, u8g_pgm_read(ptr)); - ptr++; - arg_val--; - } - } - break; - case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ - u8g_com_arduino_digital_write(u8g, U8G_PI_DI, arg_val); - break; - case U8G_COM_MSG_RESET: - if ( u8g->pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) - u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); - break; - - } - return 1; -} - -#else - - -uint8_t u8g_com_arduino_parallel_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - return 1; -} - -#endif /* ARDUINO */ - - -// =============== u8g_arduino_fast_parallel.c ================ -/* - - u8g_arduino_fast_parallel.c - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - PIN_D0 8 - PIN_D1 9 - PIN_D2 10 - PIN_D3 11 - PIN_D4 4 - PIN_D5 5 - PIN_D6 6 - PIN_D7 7 - - PIN_CS1 14 - PIN_CS2 15 - PIN_RW 16 - PIN_DI 17 - PIN_EN 18 - - u8g_Init8Bit(u8g, dev, d0, d1, d2, d3, d4, d5, d6, d7, en, cs1, cs2, di, rw, reset) - u8g_Init8Bit(u8g, dev, 8, 9, 10, 11, 4, 5, 6, 7, 18, 14, 15, 17, 16, U8G_PIN_NONE) - - Update for ATOMIC operation done (01 Jun 2013) - U8G_ATOMIC_OR(ptr, val) - U8G_ATOMIC_AND(ptr, val) - U8G_ATOMIC_START(); - U8G_ATOMIC_END(); - -*/ - -#if defined(ARDUINO) - -#define PIN_D0 UI_DISPLAY_D0_PIN -#define PIN_D1 UI_DISPLAY_D1_PIN -#define PIN_D2 UI_DISPLAY_D2_PIN -#define PIN_D3 UI_DISPLAY_D3_PIN -#define PIN_D4 UI_DISPLAY_D4_PIN -#define PIN_D5 UI_DISPLAY_D5_PIN -#define PIN_D6 UI_DISPLAY_D6_PIN -#define PIN_D7 UI_DISPLAY_D7_PIN - -#define PIN_CS1 UI_DISPLAY_CS1 -#define PIN_CS2 UI_DISPLAY_CS2 -#define PIN_RW UI_DISPLAY_RW_PIN -#define PIN_DI UI_DISPLAY_DI -#define PIN_EN UI_DISPLAY_ENABLE_PIN - -//#define PIN_RESET - - -#if defined(__PIC32MX) -/* CHIPKIT PIC32 */ -static volatile uint32_t *u8g_data_port[8]; -static uint32_t u8g_data_mask[8]; -#else -static volatile uint8_t *u8g_data_port[8]; -static uint8_t u8g_data_mask[8]; -#endif - - - -static void u8g_com_arduino_fast_parallel_init(u8g_t *u8g) -{ - u8g_data_port[0] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D0]));// added conversion for due to compile - u8g_data_mask[0] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D0]); - u8g_data_port[1] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D1]));// added conversion for due to compile - u8g_data_mask[1] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D1]); - u8g_data_port[2] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D2]));// added conversion for due to compile - u8g_data_mask[2] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D2]); - u8g_data_port[3] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D3]));// added conversion for due to compile - u8g_data_mask[3] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D3]); - - u8g_data_port[4] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D4])); // added conversion for due to compile - u8g_data_mask[4] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D4]); - u8g_data_port[5] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D5]));// added conversion for due to compile - u8g_data_mask[5] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D5]); - u8g_data_port[6] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D6]));// added conversion for due to compile - u8g_data_mask[6] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D6]); - u8g_data_port[7] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D7]));// added conversion for due to compile - u8g_data_mask[7] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D7]); -} - -/* atomic protection must be done by calling function */ -static void u8g_com_arduino_fast_write_data_pin(uint8_t pin, uint8_t val) -{ - if ( val != 0 ) - *u8g_data_port[pin] |= u8g_data_mask[pin]; - else - *u8g_data_port[pin] &= ~u8g_data_mask[pin]; -} - - -void u8g_com_arduino_fast_parallel_write(u8g_t *u8g, uint8_t val) -{ - U8G_ATOMIC_START(); - u8g_com_arduino_fast_write_data_pin( 0, val&1 ); - val >>= 1; - u8g_com_arduino_fast_write_data_pin( 1, val&1 ); - val >>= 1; - u8g_com_arduino_fast_write_data_pin( 2, val&1 ); - val >>= 1; - u8g_com_arduino_fast_write_data_pin( 3, val&1 ); - val >>= 1; - - u8g_com_arduino_fast_write_data_pin( 4, val&1 ); - val >>= 1; - u8g_com_arduino_fast_write_data_pin( 5, val&1 ); - val >>= 1; - u8g_com_arduino_fast_write_data_pin( 6, val&1 ); - val >>= 1; - u8g_com_arduino_fast_write_data_pin( 7, val&1 ); - val >>= 1; - U8G_ATOMIC_END(); - - /* EN cycle time must be 1 micro second */ - u8g_com_arduino_digital_write(u8g, U8G_PI_EN, HIGH); - u8g_MicroDelay(); /* delay by 1000ns, reference: ST7920: 140ns, SBN1661: 100ns */ - u8g_com_arduino_digital_write(u8g, U8G_PI_EN, LOW); - u8g_10MicroDelay(); /* ST7920 commands: 72us */ - u8g_10MicroDelay(); /* ST7920 commands: 72us */ -} - - -uint8_t u8g_com_arduino_fast_parallel_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - switch(msg) - { - case U8G_COM_MSG_INIT: - u8g_com_arduino_fast_parallel_init(u8g); - /* setup the RW pin as output and force it to low */ - if ( u8g->pin_list[U8G_PI_RW] != U8G_PIN_NONE ) - { - pinMode(u8g->pin_list[U8G_PI_RW], OUTPUT); - u8g_com_arduino_digital_write(u8g, U8G_PI_RW, LOW); - } - /* set all pins (except RW pin) */ - u8g_com_arduino_assign_pin_output_high(u8g); - break; - case U8G_COM_MSG_STOP: - break; - - case U8G_COM_MSG_CHIP_SELECT: - if ( arg_val == 0 ) - { - /* disable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, HIGH); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, HIGH); - } - else if ( arg_val == 1 ) - { - /* enable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, LOW); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, HIGH); - } - else if ( arg_val == 2 ) - { - /* enable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, HIGH); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, LOW); - } - else - { - /* enable */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, LOW); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, LOW); - } - break; - case U8G_COM_MSG_WRITE_BYTE: - u8g_com_arduino_fast_parallel_write(u8g, arg_val); - break; - case U8G_COM_MSG_WRITE_SEQ: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_com_arduino_fast_parallel_write(u8g, *ptr++); - arg_val--; - } - } - break; - case U8G_COM_MSG_WRITE_SEQ_P: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_com_arduino_fast_parallel_write(u8g, u8g_pgm_read(ptr)); - ptr++; - arg_val--; - } - } - break; - case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ - u8g_com_arduino_digital_write(u8g, U8G_PI_DI, arg_val); - break; - case U8G_COM_MSG_RESET: - if ( u8g->pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) - u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); - break; - - } - return 1; -} - -#else - - -uint8_t u8g_com_arduino_fast_parallel_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - return 1; -} - - -#endif /* ARDUINO */ - - -/* - - u8g_dev_st7565_nhd_c12864.c - - Support for the NHD-C12864A1Z-FSB-FBW (Newhaven Display) - - Universal 8bit Graphics Library - - Copyright (c) 2012, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - -*/ - -#define WIDTH 128 -#define HEIGHT 64 -#define PAGE_HEIGHT 8 - -const uint8_t u8g_dev_st7565_nhd_c12864_init_seq[] PROGMEM = { - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_RST(10), /* do reset low pulse with (10*16)+2 milliseconds */ - U8G_ESC_CS(1), /* enable chip */ - - 0x040, /* set display start line */ - 0x0a1, /* ADC set to reverse */ - 0x0c0, /* common output mode: set scan direction normal operation */ - 0x0a6, /* display normal, bit val 0: LCD pixel off. */ - 0x0a2, /* LCD bias 1/9 */ - 0x02f, /* all power control circuits on */ - 0x0f8, /* set booster ratio to */ - 0x000, /* 4x */ - 0x027, /* set V0 voltage resistor ratio to large */ - 0x081, /* set contrast */ - 0x008, /* contrast: 0x008 is a good value for NHD C12864, Nov 2012: User reports that 0x1a is much better */ - 0x0ac, /* indicator */ - 0x000, /* disable */ - 0x0af, /* display on */ - - U8G_ESC_DLY(100), /* delay 100 ms */ - 0x0a5, /* display all points, ST7565 */ - U8G_ESC_DLY(100), /* delay 100 ms */ - U8G_ESC_DLY(100), /* delay 100 ms */ - 0x0a4, /* normal display */ - U8G_ESC_CS(0), /* disable chip */ - U8G_ESC_END /* end of sequence */ -}; - -static const uint8_t u8g_dev_st7565_nhd_c12864_data_start[] PROGMEM = { - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_CS(1), /* enable chip */ - 0x010, /* set upper 4 bit of the col adr to 0 */ - 0x004, /* set lower 4 bit of the col adr to 4 (NHD C12864) */ - U8G_ESC_END /* end of sequence */ -}; - -static const uint8_t u8g_dev_st7565_c12864_sleep_on[] PROGMEM = { - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_CS(1), /* enable chip */ - 0x0ac, /* static indicator off */ - 0x000, /* indicator register set (not sure if this is required) */ - 0x0ae, /* display off */ - 0x0a5, /* all points on */ - U8G_ESC_CS(0), /* disable chip, bugfix 12 nov 2014 */ - U8G_ESC_END /* end of sequence */ -}; - -static const uint8_t u8g_dev_st7565_c12864_sleep_off[] PROGMEM = { - U8G_ESC_ADR(0), /* instruction mode */ - U8G_ESC_CS(1), /* enable chip */ - 0x0a4, /* all points off */ - 0x0af, /* display on */ - U8G_ESC_DLY(50), /* delay 50 ms */ - U8G_ESC_CS(0), /* disable chip, bugfix 12 nov 2014 */ - U8G_ESC_END /* end of sequence */ -}; - -uint8_t u8g_dev_st7565_nhd_c12864_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - switch(msg) - { - case U8G_DEV_MSG_INIT: - u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_400NS); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_init_seq); - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_NEXT: - { - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | pb->p.page); /* select current page (ST7565R) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - if ( u8g_pb_WriteBuffer(pb, u8g, dev) == 0 ) - return 0; - u8g_SetChipSelect(u8g, dev, 0); - } - break; - case U8G_DEV_MSG_CONTRAST: - u8g_SetChipSelect(u8g, dev, 1); - u8g_SetAddress(u8g, dev, 0); /* instruction mode */ - u8g_WriteByte(u8g, dev, 0x081); - u8g_WriteByte(u8g, dev, (*(uint8_t *)arg) >> 2); - u8g_SetChipSelect(u8g, dev, 0); - return 1; - case U8G_DEV_MSG_SLEEP_ON: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_c12864_sleep_on); - return 1; - case U8G_DEV_MSG_SLEEP_OFF: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_c12864_sleep_off); - return 1; - } - return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); -} - -uint8_t u8g_dev_st7565_nhd_c12864_2x_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - switch(msg) - { - case U8G_DEV_MSG_INIT: - u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_400NS); - u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_init_seq); - break; - case U8G_DEV_MSG_STOP: - break; - case U8G_DEV_MSG_PAGE_NEXT: - { - u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); - - u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | (2*pb->p.page)); /* select current page (ST7565R) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - u8g_WriteSequence(u8g, dev, pb->width, (uint8_t*)pb->buf); - u8g_SetChipSelect(u8g, dev, 0); - - u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_data_start); - u8g_WriteByte(u8g, dev, 0x0b0 | (2*pb->p.page+1)); /* select current page (ST7565R) */ - u8g_SetAddress(u8g, dev, 1); /* data mode */ - u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)(pb->buf)+pb->width); - u8g_SetChipSelect(u8g, dev, 0); - } - break; - case U8G_DEV_MSG_CONTRAST: - u8g_SetChipSelect(u8g, dev, 1); - u8g_SetAddress(u8g, dev, 0); /* instruction mode */ - u8g_WriteByte(u8g, dev, 0x081); - u8g_WriteByte(u8g, dev, (*(uint8_t *)arg) >> 2); - u8g_SetChipSelect(u8g, dev, 0); - return 1; - case U8G_DEV_MSG_SLEEP_ON: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_c12864_sleep_on); - return 1; - case U8G_DEV_MSG_SLEEP_OFF: - u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_c12864_sleep_off); - return 1; - } - return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg); -} - -U8G_PB_DEV(u8g_dev_st7565_nhd_c12864_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_st7565_nhd_c12864_fn, U8G_COM_SW_SPI); -U8G_PB_DEV(u8g_dev_st7565_nhd_c12864_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_st7565_nhd_c12864_fn, U8G_COM_HW_SPI); - - -uint8_t u8g_dev_st7565_nhd_c12864_2x_buf[WIDTH*2] U8G_NOCOMMON ; -u8g_pb_t u8g_dev_st7565_nhd_c12864_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_st7565_nhd_c12864_2x_buf}; -u8g_dev_t u8g_dev_st7565_nhd_c12864_2x_sw_spi = { u8g_dev_st7565_nhd_c12864_2x_fn, &u8g_dev_st7565_nhd_c12864_2x_pb, U8G_COM_SW_SPI }; -u8g_dev_t u8g_dev_st7565_nhd_c12864_2x_hw_spi = { u8g_dev_st7565_nhd_c12864_2x_fn, &u8g_dev_st7565_nhd_c12864_2x_pb, U8G_COM_HW_SPI }; - -/* - - u8g_com_arduino_hw_spi.c - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - SPI Clock Cycle Type - - SSD1351 50ns 20 MHz - SSD1322 300ns 3.3 MHz - SSD1327 300ns - SSD1306 300ns - ST7565 400ns 2.5 MHz - ST7920 400ns - - Arduino DUE - - PA25 MISO - PA26 MOSI 75 - PA27 SCLK 76 - - -typedef struct { - WoReg SPI_CR; (Spi Offset: 0x00) Control Register - RwReg SPI_MR; (Spi Offset: 0x04) Mode Register - RoReg SPI_RDR; (Spi Offset: 0x08) Receive Data Register - WoReg SPI_TDR; (Spi Offset: 0x0C) Transmit Data Register - RoReg SPI_SR; (Spi Offset: 0x10) Status Register - WoReg SPI_IER; (Spi Offset: 0x14) Interrupt Enable Register - WoReg SPI_IDR; (Spi Offset: 0x18) Interrupt Disable Register - RoReg SPI_IMR; (Spi Offset: 0x1C) Interrupt Mask Register - RoReg Reserved1[4]; - RwReg SPI_CSR[4]; (Spi Offset: 0x30) Chip Select Register - RoReg Reserved2[41]; - RwReg SPI_WPMR; (Spi Offset: 0xE4) Write Protection Control Register - RoReg SPI_WPSR; (Spi Offset: 0xE8) Write Protection Status Register -} Spi; - - Power Management Controller (PMC) - arduino-1.5.2/hardware/arduino/sam/system/CMSIS/Device/ATMEL/sam3xa/include/instance/instance_pmc.h - - enable PIO - - REG_PMC_PCER0 = 1UL << ID_PIOA - - enable SPI - REG_PMC_PCER0 = 1UL << ID_SPI0 - - - - enable PIOA and SPI0 - REG_PMC_PCER0 = (1UL << ID_PIOA) | (1UL << ID_SPI0); - - Parallel Input/Output Controller (PIO) - arduino-1.5.2/hardware/arduino/sam/system/CMSIS/Device/ATMEL/sam3xa/include/instance/instance_pioa.h - - enable special function of the pin: disable PIO on A26 and A27: - REG_PIOA_PDR = 0x0c000000 - PIOA->PIO_PDR = 0x0c000000 - - SPI - SPI0->SPI_CR = SPI_CR_SPIDIS - SPI0->SPI_CR = SPI_CR_SWRST ; - SPI0->SPI_CR = SPI_CR_SWRST ; - SPI0->SPI_CR = SPI_CR_SPIEN - - Bit 0: Master Mode = 1 (active) - Bit 1: Peripheral Select = 0 (fixed) - Bit 2: Chip Select Decode Mode = 1 (4 to 16) - Bit 4: Mode Fault Detection = 1 (disabled) - Bit 5: Wait Data Read = 0 (disabled) - Bit 7: Loop Back Mode = 0 (disabled) - Bit 16-19: Peripheral Chip Select = 0 (chip select 0) - SPI0->SPI_MR = SPI_MR_MSTR | SPI_MR_PCSDEC | SPI_MR_MODFDIS - - Bit 0: Clock Polarity = 0 - Bit 1: Clock Phase = 0 - Bit 4-7: Bits = 0 (8 Bit) - Bit 8-15: SCBR = 1 - SPI0->SPI_CSR[0] = SPI_CSR_SCBR(x) Serial Baud Rate - SCBR / 84000000 > 50 / 1000000000 - SCBR / 84 > 5 / 100 - SCBR > 50 *84 / 1000 --> SCBR=5 - SCBR > 300*84 / 1000 --> SCBR=26 - SCBR > 400*84 / 1000 --> SCBR=34 - - Arduino Due test code: - REG_PMC_PCER0 = (1UL << ID_PIOA) | (1UL << ID_SPI0); - REG_PIOA_PDR = 0x0c000000; - SPI0->SPI_CR = SPI_CR_SPIDIS; - SPI0->SPI_CR = SPI_CR_SWRST; - SPI0->SPI_CR = SPI_CR_SWRST; - SPI0->SPI_CR = SPI_CR_SPIEN; - SPI0->SPI_MR = SPI_MR_MSTR | SPI_MR_PCSDEC | SPI_MR_MODFDIS; - SPI0->SPI_CSR[0] = SPI_CSR_SCBR(30); - - for(;;) - { - while( (SPI0->SPI_SR & SPI_SR_TDRE) == 0 ) - ; - SPI0->SPI_TDR = 0x050; - } - -*/ - -#if defined(ARDUINO) - -#if defined(__AVR__) -#define U8G_ARDUINO_ATMEGA_HW_SPI -/* remove the definition for attiny */ -#if __AVR_ARCH__ == 2 -#undef U8G_ARDUINO_ATMEGA_HW_SPI -#endif -#if __AVR_ARCH__ == 25 -#undef U8G_ARDUINO_ATMEGA_HW_SPI -#endif -#endif - -#if defined(U8G_ARDUINO_ATMEGA_HW_SPI) - -//#include -//#include - -#if ARDUINO < 100 - -/* fixed pins */ -#if defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__) // Sanguino.cc board -#define PIN_SCK 7 -#define PIN_MISO 6 -#define PIN_MOSI 5 -#define PIN_CS 4 -#else // Arduino Board -#define PIN_SCK 13 -#define PIN_MISO 12 -#define PIN_MOSI 11 -#define PIN_CS 10 -#endif // (__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__) - -#else - -/* use Arduino pin definitions */ -#define PIN_SCK SCK -#define PIN_MISO MISO_PIN -#define PIN_MOSI MOSI_PIN -#define PIN_CS SS - -#endif - - - -//static uint8_t u8g_spi_out(uint8_t data) U8G_NOINLINE; -static uint8_t u8g_spi_out(uint8_t data) -{ - /* unsigned char x = 100; */ - /* send data */ - SPDR = data; - /* wait for transmission */ - while (!(SPSR & (1<pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) - u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); - break; - - case U8G_COM_MSG_WRITE_BYTE: - u8g_spi_out(arg_val); - break; - - case U8G_COM_MSG_WRITE_SEQ: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_spi_out(*ptr++); - arg_val--; - } - } - break; - case U8G_COM_MSG_WRITE_SEQ_P: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_spi_out(u8g_pgm_read(ptr)); - ptr++; - arg_val--; - } - } - break; - } - return 1; -} - -/* #elif defined(__18CXX) || defined(__PIC32MX) */ - -#elif defined(__SAM3X8E__) // Arduino Due, maybe we should better check for __SAM3X8E__ - -/* use Arduino pin definitions */ -#define PIN_SCK SCK -#define PIN_MISO MISO -#define PIN_MOSI MOSI -#define PIN_CS SS - - -static uint8_t u8g_spi_out(uint8_t data) -{ - /* wait until tx register is empty */ - while( (SPI0->SPI_SR & SPI_SR_TDRE) == 0 ) - ; - /* send data */ - SPI0->SPI_TDR = (uint32_t)data; - return data; -} - - -uint8_t u8g_com_arduino_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - switch(msg) - { - case U8G_COM_MSG_STOP: - break; - - case U8G_COM_MSG_INIT: - u8g_com_arduino_assign_pin_output_high(u8g); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS, HIGH); - - /* Arduino Due specific code */ - - /* enable PIOA and SPI0 */ - REG_PMC_PCER0 = (1UL << ID_PIOA) | (1UL << ID_SPI0); - - /* disable PIO on A26 and A27 */ - REG_PIOA_PDR = 0x0c000000; - - /* reset SPI0 (from sam lib) */ - SPI0->SPI_CR = SPI_CR_SPIDIS; - SPI0->SPI_CR = SPI_CR_SWRST; - SPI0->SPI_CR = SPI_CR_SWRST; - SPI0->SPI_CR = SPI_CR_SPIEN; - u8g_MicroDelay(); - - /* master mode, no fault detection, chip select 0 */ - SPI0->SPI_MR = SPI_MR_MSTR | SPI_MR_PCSDEC | SPI_MR_MODFDIS; - - /* Polarity, Phase, 8 Bit data transfer, baud rate */ - /* x * 1000 / 84 --> clock cycle in ns - 5 * 1000 / 84 = 58 ns - SCBR > 50 *84 / 1000 --> SCBR=5 - SCBR > 300*84 / 1000 --> SCBR=26 - SCBR > 400*84 / 1000 --> SCBR=34 - */ - - if ( arg_val <= U8G_SPI_CLK_CYCLE_50NS ) - { - SPI0->SPI_CSR[0] = SPI_CSR_SCBR(5) | 1; - } - else if ( arg_val <= U8G_SPI_CLK_CYCLE_300NS ) - { - SPI0->SPI_CSR[0] = SPI_CSR_SCBR(26) | 1; - } - else if ( arg_val <= U8G_SPI_CLK_CYCLE_400NS ) - { - SPI0->SPI_CSR[0] = SPI_CSR_SCBR(34) | 1; - } - else - { - SPI0->SPI_CSR[0] = SPI_CSR_SCBR(84) | 1; - } - - u8g_MicroDelay(); - break; - - case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ - u8g_com_arduino_digital_write(u8g, U8G_PI_A0, arg_val); - u8g_MicroDelay(); - break; - - case U8G_COM_MSG_CHIP_SELECT: - if ( arg_val == 0 ) - { - /* disable */ - u8g_MicroDelay(); /* this delay is required to avoid that the display is switched off too early --> DOGS102 with DUE */ - u8g_com_arduino_digital_write(u8g, U8G_PI_CS, HIGH); - u8g_MicroDelay(); - } - else - { - /* enable */ - //u8g_com_arduino_digital_write(u8g, U8G_PI_SCK, LOW); - u8g_com_arduino_digital_write(u8g, U8G_PI_CS, LOW); - u8g_MicroDelay(); - } - break; - - case U8G_COM_MSG_RESET: - if ( u8g->pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) - u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); - break; - - case U8G_COM_MSG_WRITE_BYTE: - u8g_spi_out(arg_val); - u8g_MicroDelay(); - break; - - case U8G_COM_MSG_WRITE_SEQ: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_spi_out(*ptr++); - arg_val--; - } - } - break; - case U8G_COM_MSG_WRITE_SEQ_P: - { - register uint8_t *ptr = (uint8_t*)arg_ptr; - while( arg_val > 0 ) - { - u8g_spi_out(u8g_pgm_read(ptr)); - ptr++; - arg_val--; - } - } - break; - } - return 1; -} - - - -#else /* U8G_ARDUINO_ATMEGA_HW_SPI */ - -#endif /* U8G_ARDUINO_ATMEGA_HW_SPI */ - -#else /* ARDUINO */ - -uint8_t u8g_com_arduino_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) -{ - return 1; -} - -#endif /* ARDUINO */ - -/* - - u8g_rot.c - - Universal 8bit Graphics Library - - Copyright (c) 2011, olikraus@gmail.com - All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, - are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, this list - of conditions and the following disclaimer. - - * Redistributions in binary form must reproduce the above copyright notice, this - list of conditions and the following disclaimer in the documentation and/or other - materials provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND - CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, - INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR - CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT - NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, - STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - - -*/ - -uint8_t u8g_dev_rot90_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg); -uint8_t u8g_dev_rot180_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg); -uint8_t u8g_dev_rot270_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg); - -uint8_t u8g_dev_rot_dummy_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - return 0; -} - -u8g_dev_t u8g_dev_rot = { u8g_dev_rot_dummy_fn, NULL, NULL }; - - -void u8g_UndoRotation(u8g_t *u8g) -{ - if ( u8g->dev != &u8g_dev_rot ) - return; - u8g->dev = (u8g_dev_t*)u8g_dev_rot.dev_mem; - u8g_UpdateDimension(u8g); -} - -void u8g_SetRot90(u8g_t *u8g) -{ - if ( u8g->dev != &u8g_dev_rot ) - { - u8g_dev_rot.dev_mem = u8g->dev; - u8g->dev = &u8g_dev_rot; - } - u8g_dev_rot.dev_fn = u8g_dev_rot90_fn; - u8g_UpdateDimension(u8g); -} - -void u8g_SetRot180(u8g_t *u8g) -{ - if ( u8g->dev != &u8g_dev_rot ) - { - u8g_dev_rot.dev_mem = u8g->dev; - u8g->dev = &u8g_dev_rot; - } - u8g_dev_rot.dev_fn = u8g_dev_rot180_fn; - u8g_UpdateDimension(u8g); -} - -void u8g_SetRot270(u8g_t *u8g) -{ - if ( u8g->dev != &u8g_dev_rot ) - { - u8g_dev_rot.dev_mem = u8g->dev; - u8g->dev = &u8g_dev_rot; - } - u8g_dev_rot.dev_fn = u8g_dev_rot270_fn; - u8g_UpdateDimension(u8g); -} - -uint8_t u8g_dev_rot90_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - u8g_dev_t *rotation_chain = (u8g_dev_t *)(dev->dev_mem); - switch(msg) - { - default: - /* - case U8G_DEV_MSG_INIT: - case U8G_DEV_MSG_STOP: - case U8G_DEV_MSG_PAGE_FIRST: - case U8G_DEV_MSG_PAGE_NEXT: - case U8G_DEV_MSG_SET_COLOR_ENTRY: - case U8G_DEV_MSG_SET_XY_CB: - */ - return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); -#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION - case U8G_DEV_MSG_IS_BBX_INTERSECTION: - { - u8g_dev_arg_bbx_t *bbx = (u8g_dev_arg_bbx_t *)arg; - u8g_uint_t x, y, tmp; - - /* transform the reference point */ - y = bbx->x; - x = u8g->height; - /* x = u8g_GetWidthLL(u8g, rotation_chain); */ - x -= bbx->y; - x--; - - /* adjust point to be the uppler left corner again */ - x -= bbx->h; - x++; - - /* swap box dimensions */ - tmp = bbx->w; - bbx->w = bbx->h; - bbx->h = tmp; - - /* store x,y */ - bbx->x = x; - bbx->y = y; - } - return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); -#endif /* U8G_DEV_MSG_IS_BBX_INTERSECTION */ - case U8G_DEV_MSG_GET_PAGE_BOX: - /* get page size from next device in the chain */ - u8g_call_dev_fn(u8g, rotation_chain, msg, arg); - //printf("pre x: %3d..%3d y: %3d..%3d ", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); - { - u8g_box_t new_box; - //new_box.x0 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y1 - 1; - //new_box.x1 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y0 - 1; - - new_box.x0 = ((u8g_box_t *)arg)->y0; - new_box.x1 = ((u8g_box_t *)arg)->y1; - new_box.y0 = ((u8g_box_t *)arg)->x0; - new_box.y1 = ((u8g_box_t *)arg)->x1; - *((u8g_box_t *)arg) = new_box; - //printf("post x: %3d..%3d y: %3d..%3d\n", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); - } - break; - case U8G_DEV_MSG_GET_WIDTH: - *((u8g_uint_t *)arg) = u8g_GetHeightLL(u8g,rotation_chain); - break; - case U8G_DEV_MSG_GET_HEIGHT: - *((u8g_uint_t *)arg) = u8g_GetWidthLL(u8g, rotation_chain); - break; - case U8G_DEV_MSG_SET_PIXEL: - case U8G_DEV_MSG_SET_TPIXEL: - { - u8g_uint_t x, y; - y = ((u8g_dev_arg_pixel_t *)arg)->x; - x = u8g_GetWidthLL(u8g, rotation_chain); - x -= ((u8g_dev_arg_pixel_t *)arg)->y; - x--; - ((u8g_dev_arg_pixel_t *)arg)->x = x; - ((u8g_dev_arg_pixel_t *)arg)->y = y; - } - u8g_call_dev_fn(u8g, rotation_chain, msg, arg); - break; - case U8G_DEV_MSG_SET_8PIXEL: - case U8G_DEV_MSG_SET_4TPIXEL: - { - u8g_uint_t x, y; - //uint16_t x,y; - y = ((u8g_dev_arg_pixel_t *)arg)->x; - x = u8g_GetWidthLL(u8g, rotation_chain); - x -= ((u8g_dev_arg_pixel_t *)arg)->y; - x--; - ((u8g_dev_arg_pixel_t *)arg)->x = x; - ((u8g_dev_arg_pixel_t *)arg)->y = y; - ((u8g_dev_arg_pixel_t *)arg)->dir+=1; - ((u8g_dev_arg_pixel_t *)arg)->dir &= 3; - } - u8g_call_dev_fn(u8g, rotation_chain, msg, arg); - break; - } - return 1; -} - -uint8_t u8g_dev_rot180_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - u8g_dev_t *rotation_chain = (u8g_dev_t *)(dev->dev_mem); - switch(msg) - { - default: - /* - case U8G_DEV_MSG_INIT: - case U8G_DEV_MSG_STOP: - case U8G_DEV_MSG_PAGE_FIRST: - case U8G_DEV_MSG_PAGE_NEXT: - case U8G_DEV_MSG_SET_COLOR_ENTRY: - case U8G_DEV_MSG_SET_XY_CB: - */ - return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); -#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION - case U8G_DEV_MSG_IS_BBX_INTERSECTION: - { - u8g_dev_arg_bbx_t *bbx = (u8g_dev_arg_bbx_t *)arg; - u8g_uint_t x, y; - - /* transform the reference point */ - //y = u8g_GetHeightLL(u8g, rotation_chain); - y = u8g->height; - y -= bbx->y; - y--; - - //x = u8g_GetWidthLL(u8g, rotation_chain); - x = u8g->width; - x -= bbx->x; - x--; - - /* adjust point to be the uppler left corner again */ - y -= bbx->h; - y++; - - x -= bbx->w; - x++; - - /* store x,y */ - bbx->x = x; - bbx->y = y; - } - return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); -#endif /* U8G_DEV_MSG_IS_BBX_INTERSECTION */ - case U8G_DEV_MSG_GET_PAGE_BOX: - /* get page size from next device in the chain */ - u8g_call_dev_fn(u8g, rotation_chain, msg, arg); - //printf("pre x: %3d..%3d y: %3d..%3d ", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); - { - u8g_box_t new_box; - - new_box.x0 = u8g_GetWidthLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->x1 - 1; - new_box.x1 = u8g_GetWidthLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->x0 - 1; - new_box.y0 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y1 - 1; - new_box.y1 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y0 - 1; - *((u8g_box_t *)arg) = new_box; - //printf("post x: %3d..%3d y: %3d..%3d\n", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); - } - break; - case U8G_DEV_MSG_GET_WIDTH: - *((u8g_uint_t *)arg) = u8g_GetWidthLL(u8g,rotation_chain); - break; - case U8G_DEV_MSG_GET_HEIGHT: - *((u8g_uint_t *)arg) = u8g_GetHeightLL(u8g, rotation_chain); - break; - case U8G_DEV_MSG_SET_PIXEL: - case U8G_DEV_MSG_SET_TPIXEL: - { - u8g_uint_t x, y; - - y = u8g_GetHeightLL(u8g, rotation_chain); - y -= ((u8g_dev_arg_pixel_t *)arg)->y; - y--; - - x = u8g_GetWidthLL(u8g, rotation_chain); - x -= ((u8g_dev_arg_pixel_t *)arg)->x; - x--; - - ((u8g_dev_arg_pixel_t *)arg)->x = x; - ((u8g_dev_arg_pixel_t *)arg)->y = y; - } - u8g_call_dev_fn(u8g, rotation_chain, msg, arg); - break; - case U8G_DEV_MSG_SET_8PIXEL: - case U8G_DEV_MSG_SET_4TPIXEL: - { - u8g_uint_t x, y; - - y = u8g_GetHeightLL(u8g, rotation_chain); - y -= ((u8g_dev_arg_pixel_t *)arg)->y; - y--; - - x = u8g_GetWidthLL(u8g, rotation_chain); - x -= ((u8g_dev_arg_pixel_t *)arg)->x; - x--; - - ((u8g_dev_arg_pixel_t *)arg)->x = x; - ((u8g_dev_arg_pixel_t *)arg)->y = y; - ((u8g_dev_arg_pixel_t *)arg)->dir+=2; - ((u8g_dev_arg_pixel_t *)arg)->dir &= 3; - } - u8g_call_dev_fn(u8g, rotation_chain, msg, arg); - break; - } - return 1; -} - -uint8_t u8g_dev_rot270_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) -{ - u8g_dev_t *rotation_chain = (u8g_dev_t *)(dev->dev_mem); - switch(msg) - { - default: - /* - case U8G_DEV_MSG_INIT: - case U8G_DEV_MSG_STOP: - case U8G_DEV_MSG_PAGE_FIRST: - case U8G_DEV_MSG_PAGE_NEXT: - case U8G_DEV_MSG_SET_COLOR_ENTRY: - case U8G_DEV_MSG_SET_XY_CB: - */ - return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); -#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION - case U8G_DEV_MSG_IS_BBX_INTERSECTION: - { - u8g_dev_arg_bbx_t *bbx = (u8g_dev_arg_bbx_t *)arg; - u8g_uint_t x, y, tmp; - - /* transform the reference point */ - x = bbx->y; - - y = u8g->width; - /* y = u8g_GetHeightLL(u8g, rotation_chain); */ - y -= bbx->x; - y--; - - /* adjust point to be the uppler left corner again */ - y -= bbx->w; - y++; - - /* swap box dimensions */ - tmp = bbx->w; - bbx->w = bbx->h; - bbx->h = tmp; - - /* store x,y */ - bbx->x = x; - bbx->y = y; - } - return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); -#endif /* U8G_DEV_MSG_IS_BBX_INTERSECTION */ - case U8G_DEV_MSG_GET_PAGE_BOX: - /* get page size from next device in the chain */ - u8g_call_dev_fn(u8g, rotation_chain, msg, arg); - //printf("pre x: %3d..%3d y: %3d..%3d ", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); - { - u8g_box_t new_box; - - new_box.x0 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y1 - 1; - new_box.x1 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y0 - 1; - new_box.y0 = u8g_GetWidthLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->x1 - 1; - new_box.y1 = u8g_GetWidthLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->x0 - 1; - *((u8g_box_t *)arg) = new_box; - //printf("post x: %3d..%3d y: %3d..%3d\n", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); - } - break; - case U8G_DEV_MSG_GET_WIDTH: - *((u8g_uint_t *)arg) = u8g_GetHeightLL(u8g,rotation_chain); - break; - case U8G_DEV_MSG_GET_HEIGHT: - *((u8g_uint_t *)arg) = u8g_GetWidthLL(u8g, rotation_chain); - break; - case U8G_DEV_MSG_SET_PIXEL: - case U8G_DEV_MSG_SET_TPIXEL: - { - u8g_uint_t x, y; - x = ((u8g_dev_arg_pixel_t *)arg)->y; - - y = u8g_GetHeightLL(u8g, rotation_chain); - y -= ((u8g_dev_arg_pixel_t *)arg)->x; - y--; - - /* - x = u8g_GetWidthLL(u8g, rotation_chain); - x -= ((u8g_dev_arg_pixel_t *)arg)->y; - x--; - */ - ((u8g_dev_arg_pixel_t *)arg)->x = x; - ((u8g_dev_arg_pixel_t *)arg)->y = y; - } - u8g_call_dev_fn(u8g, rotation_chain, msg, arg); - break; - case U8G_DEV_MSG_SET_8PIXEL: - case U8G_DEV_MSG_SET_4TPIXEL: - { - u8g_uint_t x, y; - x = ((u8g_dev_arg_pixel_t *)arg)->y; - - y = u8g_GetHeightLL(u8g, rotation_chain); - y -= ((u8g_dev_arg_pixel_t *)arg)->x; - y--; - - /* - x = u8g_GetWidthLL(u8g, rotation_chain); - x -= ((u8g_dev_arg_pixel_t *)arg)->y; - x--; - */ - ((u8g_dev_arg_pixel_t *)arg)->x = x; - ((u8g_dev_arg_pixel_t *)arg)->y = y; - ((u8g_dev_arg_pixel_t *)arg)->dir+=3; - ((u8g_dev_arg_pixel_t *)arg)->dir &= 3; - } - u8g_call_dev_fn(u8g, rotation_chain, msg, arg); - break; - } - return 1; -} - - - - + +// ============ u8g_com_arduino_ssd_i2c.c ================= + +/* + + u8g_com_arduino_ssd_i2c.c + + com interface for arduino (AND atmega) and the SSDxxxx chip (SOLOMON) variant + I2C protocol + + ToDo: Rename this to u8g_com_avr_ssd_i2c.c + + Universal 8bit Graphics Library + + Copyright (c) 2012, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + Special pin usage: + U8G_PI_I2C_OPTION additional options + U8G_PI_A0_STATE used to store the last value of the command/data register selection + U8G_PI_SET_A0 1: Signal request to update I2C device with new A0_STATE, 0: Do nothing, A0_STATE matches I2C device + U8G_PI_SCL clock line (NOT USED) + U8G_PI_SDA data line (NOT USED) + + U8G_PI_RESET reset line (currently disabled, see below) + + Protocol: + SLA, Cmd/Data Selection, Arguments + The command/data register is selected by a special instruction byte, which is sent after SLA + + The continue bit is always 0 so that a (re)start is equired for the change from cmd to/data mode +*/ + + +#if defined(U8G_WITH_PINLIST) + + +#define I2C_SLA (0x3c*2) +//#define I2C_CMD_MODE 0x080 +#define I2C_CMD_MODE 0x000 +#define I2C_DATA_MODE 0x040 + +uint8_t u8g_com_arduino_ssd_start_sequence(u8g_t *u8g) +{ + /* are we requested to set the a0 state? */ + if ( u8g->pin_list[U8G_PI_SET_A0] == 0 ) + return 1; + + /* setup bus, might be a repeated start */ + if ( u8g_i2c_start(I2C_SLA) == 0 ) + return 0; + if ( u8g->pin_list[U8G_PI_A0_STATE] == 0 ) + { + if ( u8g_i2c_send_byte(I2C_CMD_MODE) == 0 ) + return 0; + } + else + { + if ( u8g_i2c_send_byte(I2C_DATA_MODE) == 0 ) + return 0; + } + + u8g->pin_list[U8G_PI_SET_A0] = 0; + return 1; +} + +uint8_t u8g_com_arduino_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + switch(msg) + { + case U8G_COM_MSG_INIT: + //u8g_com_arduino_digital_write(u8g, U8G_PI_SCL, HIGH); + //u8g_com_arduino_digital_write(u8g, U8G_PI_SDA, HIGH); + //u8g->pin_list[U8G_PI_A0_STATE] = 0; /* inital RS state: unknown mode */ + + u8g_i2c_init(u8g->pin_list[U8G_PI_I2C_OPTION]); + + break; + + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_RESET: + /* Currently disabled, but it could be enable. Previous restrictions have been removed */ + /* u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); */ + break; + + case U8G_COM_MSG_CHIP_SELECT: + u8g->pin_list[U8G_PI_A0_STATE] = 0; + u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again, also forces start condition */ + if ( arg_val == 0 ) + { + /* disable chip, send stop condition */ + u8g_i2c_stop(); + } + else + { + /* enable, do nothing: any byte writing will trigger the i2c start */ + } + break; + + case U8G_COM_MSG_WRITE_BYTE: + //u8g->pin_list[U8G_PI_SET_A0] = 1; + if ( u8g_com_arduino_ssd_start_sequence(u8g) == 0 ) + return u8g_i2c_stop(), 0; + if ( u8g_i2c_send_byte(arg_val) == 0 ) + return u8g_i2c_stop(), 0; + // u8g_i2c_stop(); + break; + + case U8G_COM_MSG_WRITE_SEQ: + //u8g->pin_list[U8G_PI_SET_A0] = 1; + if ( u8g_com_arduino_ssd_start_sequence(u8g) == 0 ) + return u8g_i2c_stop(), 0; + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + if ( u8g_i2c_send_byte(*ptr++) == 0 ) + return u8g_i2c_stop(), 0; + arg_val--; + } + } + // u8g_i2c_stop(); + break; + + case U8G_COM_MSG_WRITE_SEQ_P: + //u8g->pin_list[U8G_PI_SET_A0] = 1; + if ( u8g_com_arduino_ssd_start_sequence(u8g) == 0 ) + return u8g_i2c_stop(), 0; + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + if ( u8g_i2c_send_byte(u8g_pgm_read(ptr)) == 0 ) + return 0; + ptr++; + arg_val--; + } + } + // u8g_i2c_stop(); + break; + + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + u8g->pin_list[U8G_PI_A0_STATE] = arg_val; + u8g->pin_list[U8G_PI_SET_A0] = 1; /* force a0 to set again */ + +#ifdef OLD_CODE + if ( i2c_state != 0 ) + { + u8g_i2c_stop(); + i2c_state = 0; + } + + if ( u8g_com_arduino_ssd_start_sequence(arg_val) == 0 ) + return 0; + + /* setup bus, might be a repeated start */ + /* + if ( u8g_i2c_start(I2C_SLA) == 0 ) + return 0; + if ( arg_val == 0 ) + { + i2c_state = 1; + + if ( u8g_i2c_send_byte(I2C_CMD_MODE) == 0 ) + return 0; + } + else + { + i2c_state = 2; + if ( u8g_i2c_send_byte(I2C_DATA_MODE) == 0 ) + return 0; + } + */ +#endif + break; + } + return 1; +} + +#else /* defined(U8G_WITH_PINLIST) */ + +uint8_t u8g_com_arduino_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + return 1; +} + +#endif /* defined(U8G_WITH_PINLIST) */ + +// ============ u8g_com_i2c.c =============== + +/* + + u8g_com_i2c.c + + generic i2c interface + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +*/ + + +//#define U8G_I2C_WITH_NO_ACK + +static uint8_t u8g_i2c_err_code; +static uint8_t u8g_i2c_opt; /* U8G_I2C_OPT_NO_ACK, SAM: U8G_I2C_OPT_DEV_1 */ +/* + position values + 1: start condition + 2: sla transfer +*/ +static uint8_t u8g_i2c_err_pos; + + +void u8g_i2c_clear_error(void) +{ + u8g_i2c_err_code = U8G_I2C_ERR_NONE; + u8g_i2c_err_pos = 0; +} + +uint8_t u8g_i2c_get_error(void) +{ + return u8g_i2c_err_code; +} + +uint8_t u8g_i2c_get_err_pos(void) +{ + return u8g_i2c_err_pos; +} + +static void u8g_i2c_set_error(uint8_t code, uint8_t pos) +{ + if ( u8g_i2c_err_code > 0 ) + return; + u8g_i2c_err_code |= code; + u8g_i2c_err_pos = pos; +} + + + +#if defined(__AVR__) +#define U8G_ATMEGA_HW_TWI + +/* remove the definition for attiny */ +#if __AVR_ARCH__ == 2 +#undef U8G_ATMEGA_HW_TWI +#endif +#if __AVR_ARCH__ == 25 +#undef U8G_ATMEGA_HW_TWI +#endif +#endif + +#if defined(U8G_ATMEGA_HW_TWI) + +#include +#include + + + +void u8g_i2c_init(uint8_t options) +{ + /* + TWBR: bit rate register + TWSR: status register (contains preselector bits) + + prescalar + 0 1 + 1 4 + 2 16 + 3 64 + + f = F_CPU/(16+2*TWBR*prescalar) + + F_CPU = 16MHz + TWBR = 152; + TWSR = 0; + --> 50KHz + + TWBR = 72; + TWSR = 0; + --> 100KHz + + TWBR = 12; + TWSR = 0; + --> 400KHz + + F_CPU/(2*100000)-8 --> calculate TWBR value for 100KHz +*/ + u8g_i2c_opt = options; + TWSR = 0; + if ( options & U8G_I2C_OPT_FAST ) + { + TWBR = F_CPU/(2*400000)-8; + } + else + { + TWBR = F_CPU/(2*100000)-8; + } + u8g_i2c_clear_error(); +} + +uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos) +{ + volatile uint16_t cnt = 2000; /* timout value should be > 280 for 50KHz Bus and 16 Mhz CPU, however the start condition might need longer */ + while( !(TWCR & mask) ) + { + if ( cnt == 0 ) + { + if ( u8g_i2c_opt & U8G_I2C_OPT_NO_ACK ) + { + return 1; /* all ok */ + } + else + { + u8g_i2c_set_error(U8G_I2C_ERR_TIMEOUT, pos); + return 0; /* error */ + } + } + cnt--; + } + return 1; /* all ok */ +} + +/* sla includes all 8 bits (with r/w bit), assums master transmit */ +uint8_t u8g_i2c_start(uint8_t sla) +{ + register uint8_t status; + + /* send start */ + TWCR = _BV(TWINT) | _BV(TWSTA) | _BV(TWEN); + + /* wait */ + if ( u8g_i2c_wait(_BV(TWINT), 1) == 0 ) + return 0; + + status = TW_STATUS; + + /* check status after start */ + if ( status != TW_START && status != TW_REP_START ) + { + u8g_i2c_set_error(U8G_I2C_ERR_BUS, 1); + return 0; + } + + /* set slave address */ + TWDR = sla; + + /* enable sla transfer */ + TWCR = _BV(TWINT) | _BV(TWEN); + + /* wait */ + if ( u8g_i2c_wait(_BV(TWINT), 2) == 0 ) + return 0; + + if ( u8g_i2c_opt & U8G_I2C_OPT_NO_ACK ) + { + /* do not check for ACK */ + } + else + { + status = TW_STATUS; + /* check status after sla */ + if ( status != TW_MT_SLA_ACK ) + { + u8g_i2c_set_error(U8G_I2C_ERR_BUS, 2); + return 0; + } + } + + return 1; +} + +uint8_t u8g_i2c_send_byte(uint8_t data) +{ + register uint8_t status; + TWDR = data; + TWCR = _BV(TWINT) | _BV(TWEN); + if ( u8g_i2c_wait(_BV(TWINT), 3) == 0 ) + return 0; + + if ( u8g_i2c_opt & U8G_I2C_OPT_NO_ACK ) + { + /* do not check for ACK */ + } + else + { + status = TW_STATUS; + if ( status != TW_MT_DATA_ACK ) + { + u8g_i2c_set_error(U8G_I2C_ERR_BUS, 3); + return 0; + } + } + + return 1; +} + +void u8g_i2c_stop(void) +{ + /* write stop */ + TWCR = _BV(TWINT) | _BV(TWEN) | _BV(TWSTO); + + /* no error is checked for the stop condition */ + u8g_i2c_wait(_BV(TWSTO), 4); + +} + +/* +void twi_send(uint8_t adr, uint8_t data1, uint8_t data2) +{ + u8g_i2c_start(adr<<1); + u8g_i2c_send_byte(data1); + u8g_i2c_send_byte(data2); + u8g_i2c_stop(); +} +*/ + +#elif defined(ARDUINO) && defined(__SAM3X8E__) +/* Arduino Due */ +#include "Arduino.h" +#include "sam.h" + +/* + +Controller + +TWI0 TWCK0 PA18 A DUE PCB: SCL1 +TWI0 TWD0 PA17 A DUE PCB: SDA1 +TWI1 TWCK1 PB13 A DUE PCB: SCL 21 +TWI1 TWD1 PB12 A DUE PCB: SDA 20 + +Arduino definitions + +#define PIN_WIRE_SDA (20u) +#define PIN_WIRE_SCL (21u) +#define WIRE_INTERFACE TWI1 +#define WIRE_INTERFACE_ID ID_TWI1 +#define WIRE_ISR_HANDLER TWI1_Handler + +#define PIN_WIRE1_SDA (70u) +#define PIN_WIRE1_SCL (71u) +#define WIRE1_INTERFACE TWI0 +#define WIRE1_INTERFACE_ID ID_TWI0 +#define WIRE1_ISR_HANDLER TWI0_Handler + + +*/ + +static void i2c_400KHz_delay(void) +{ + /* should be at least 4 */ + /* should be 5 for 100KHz transfer speed */ + + + /* + Arduino Due + 0x NOP: 470KHz + 4x NOP: 450KHz + 8x NOP: 430KHz + 16x NOP: 400KHz + */ + + __NOP(); + __NOP(); + __NOP(); + __NOP(); + + __NOP(); + __NOP(); + __NOP(); + __NOP(); + + __NOP(); + __NOP(); + __NOP(); + __NOP(); + + __NOP(); + __NOP(); + __NOP(); + __NOP(); +} + +static void i2c_100KHz_delay(void) +{ + /* + 1x u8g_MicroDelay() ca. 130KHz + 2x u8g_MicroDelay() ca. 80KHz + */ + u8g_MicroDelay(); + u8g_MicroDelay(); +} + + +uint32_t i2c_started = 0; +uint32_t i2c_scl_pin = 0; +uint32_t i2c_sda_pin = 0; +void (*i2c_delay)(void) = i2c_100KHz_delay; + +const PinDescription *i2c_scl_pin_desc; +const PinDescription *i2c_sda_pin_desc; + + +/* maybe this can be optimized */ +static void i2c_init(void) +{ + i2c_sda_pin_desc = &(g_APinDescription[i2c_sda_pin]); + i2c_scl_pin_desc = &(g_APinDescription[i2c_scl_pin]); + pinMode(i2c_sda_pin, OUTPUT); + digitalWrite(i2c_sda_pin, HIGH); + pinMode(i2c_scl_pin, OUTPUT); + digitalWrite(i2c_scl_pin, HIGH); + PIO_Configure( i2c_sda_pin_desc->pPort, PIO_OUTPUT_0, i2c_sda_pin_desc->ulPin, PIO_OPENDRAIN ); + PIO_Configure( i2c_scl_pin_desc->pPort, PIO_OUTPUT_0, i2c_scl_pin_desc->ulPin, PIO_OPENDRAIN ); + PIO_Clear( i2c_sda_pin_desc->pPort, i2c_sda_pin_desc->ulPin) ; + PIO_Clear( i2c_scl_pin_desc->pPort, i2c_scl_pin_desc->ulPin) ; + PIO_Configure( i2c_sda_pin_desc->pPort, PIO_INPUT, i2c_sda_pin_desc->ulPin, PIO_DEFAULT ) ; + PIO_Configure( i2c_scl_pin_desc->pPort, PIO_INPUT, i2c_scl_pin_desc->ulPin, PIO_DEFAULT ) ; + i2c_delay(); +} + +/* actually, the scl line is not observed, so this procedure does not return a value */ +static void i2c_read_scl_and_delay(void) +{ + uint32_t dwMask = i2c_scl_pin_desc->ulPin; + //PIO_Configure( i2c_scl_pin_desc->pPort, PIO_INPUT, i2c_scl_pin_desc->ulPin, PIO_DEFAULT ) ; + //PIO_SetInput( i2c_scl_pin_desc->pPort, i2c_scl_pin_desc->ulPin, PIO_DEFAULT ) ; + + /* set as input */ + i2c_scl_pin_desc->pPort->PIO_ODR = dwMask ; + i2c_scl_pin_desc->pPort->PIO_PER = dwMask ; + + i2c_delay(); +} + +static void i2c_clear_scl(void) +{ + uint32_t dwMask = i2c_scl_pin_desc->ulPin; + + /* set open collector and drive low */ + //PIO_Configure( i2c_scl_pin_desc->pPort, PIO_OUTPUT_0, i2c_scl_pin_desc->ulPin, PIO_OPENDRAIN ); + //PIO_SetOutput( i2c_scl_pin_desc->pPort, i2c_scl_pin_desc->ulPin, 0, 1, 0); + + /* open drain, zero default output */ + i2c_scl_pin_desc->pPort->PIO_MDER = dwMask; + i2c_scl_pin_desc->pPort->PIO_CODR = dwMask; + i2c_scl_pin_desc->pPort->PIO_OER = dwMask; + i2c_scl_pin_desc->pPort->PIO_PER = dwMask; + + //PIO_Clear( i2c_scl_pin_desc->pPort, i2c_scl_pin_desc->ulPin) ; +} + +static uint8_t i2c_read_sda(void) +{ + uint32_t dwMask = i2c_sda_pin_desc->ulPin; + //PIO_Configure( i2c_sda_pin_desc->pPort, PIO_INPUT, i2c_sda_pin_desc->ulPin, PIO_DEFAULT ) ; + //PIO_SetInput( i2c_sda_pin_desc->pPort, i2c_sda_pin_desc->ulPin, PIO_DEFAULT ) ; + + /* set as input */ + i2c_sda_pin_desc->pPort->PIO_ODR = dwMask ; + i2c_sda_pin_desc->pPort->PIO_PER = dwMask ; + + + return 1; +} + +static void i2c_clear_sda(void) +{ + uint32_t dwMask = i2c_sda_pin_desc->ulPin; + + /* set open collector and drive low */ + //PIO_Configure( i2c_sda_pin_desc->pPort, PIO_OUTPUT_0, i2c_sda_pin_desc->ulPin, PIO_OPENDRAIN ); + //PIO_SetOutput( i2c_sda_pin_desc->pPort, i2c_sda_pin_desc->ulPin, 0, 1, 0); + + /* open drain, zero default output */ + i2c_sda_pin_desc->pPort->PIO_MDER = dwMask ; + i2c_sda_pin_desc->pPort->PIO_CODR = dwMask ; + i2c_sda_pin_desc->pPort->PIO_OER = dwMask ; + i2c_sda_pin_desc->pPort->PIO_PER = dwMask ; + + //PIO_Clear( i2c_sda_pin_desc->pPort, i2c_sda_pin_desc->ulPin) ; +} + +static void i2c_start(void) +{ + if ( i2c_started != 0 ) + { + /* if already started: do restart */ + i2c_read_sda(); /* SDA = 1 */ + i2c_delay(); + i2c_read_scl_and_delay(); + } + i2c_read_sda(); + /* + if (i2c_read_sda() == 0) + { + // do something because arbitration is lost + } + */ + /* send the start condition, both lines go from 1 to 0 */ + i2c_clear_sda(); + i2c_delay(); + i2c_clear_scl(); + i2c_started = 1; +} + + +static void i2c_stop(void) +{ + /* set SDA to 0 */ + i2c_clear_sda(); + i2c_delay(); + + /* now release all lines */ + i2c_read_scl_and_delay(); + + /* set SDA to 1 */ + i2c_read_sda(); + i2c_delay(); + i2c_started = 0; +} + +static void i2c_write_bit(uint8_t val) +{ + if (val) + i2c_read_sda(); + else + i2c_clear_sda(); + + i2c_delay(); + i2c_read_scl_and_delay(); + i2c_clear_scl(); +} + +static uint8_t i2c_read_bit(void) +{ + uint8_t val; + /* do not drive SDA */ + i2c_read_sda(); + i2c_delay(); + i2c_read_scl_and_delay(); + val = i2c_read_sda(); + i2c_delay(); + i2c_clear_scl(); + return val; +} + +static uint8_t i2c_write_byte(uint8_t b) +{ + i2c_write_bit(b & 128); + i2c_write_bit(b & 64); + i2c_write_bit(b & 32); + i2c_write_bit(b & 16); + i2c_write_bit(b & 8); + i2c_write_bit(b & 4); + i2c_write_bit(b & 2); + i2c_write_bit(b & 1); + + /* read ack from client */ + /* 0: ack was given by client */ + /* 1: nothing happend during ack cycle */ + return i2c_read_bit(); +} + + + +void u8g_i2c_init(uint8_t options) +{ + u8g_i2c_opt = options; + u8g_i2c_clear_error(); + + if ( u8g_i2c_opt & U8G_I2C_OPT_FAST ) + { + i2c_delay = i2c_400KHz_delay; + } + else + { + i2c_delay = i2c_100KHz_delay; + } + + + if ( u8g_i2c_opt & U8G_I2C_OPT_DEV_1 ) + { + i2c_scl_pin = PIN_WIRE1_SCL; + i2c_sda_pin = PIN_WIRE1_SDA; + + //REG_PIOA_PDR = PIO_PB12A_TWD1 | PIO_PB13A_TWCK1; + } + else + { + + i2c_scl_pin = PIN_WIRE_SCL; + i2c_sda_pin = PIN_WIRE_SDA; + + //REG_PIOA_PDR = PIO_PA17A_TWD0 | PIO_PA18A_TWCK0; + } + + i2c_init(); + +} + +/* sla includes also the r/w bit */ +uint8_t u8g_i2c_start(uint8_t sla) +{ + i2c_start(); + i2c_write_byte(sla); + return 1; +} + +uint8_t u8g_i2c_send_byte(uint8_t data) +{ + return i2c_write_byte(data); +} + +void u8g_i2c_stop(void) +{ + i2c_stop(); +} + + +#elif defined(U8G_RASPBERRY_PI) + +#include +#include +#include +#include +#include + +#define I2C_SLA 0x3c + +static int fd=-1; +static uint8_t i2cMode = 0; + +void u8g_i2c_init(uint8_t options) { + u8g_i2c_clear_error(); + u8g_i2c_opt = options; + + if (wiringPiSetup() == -1) { + printf("wiringPi-Error\n"); + exit(1); + } + + fd = wiringPiI2CSetup(I2C_SLA); + if (fd < 0) { + printf ("Unable to open I2C device 0: %s\n", strerror (errno)) ; + exit (1) ; + } + //u8g_SetPIOutput(u8g, U8G_PI_RESET); + //u8g_SetPIOutput(u8g, U8G_PI_A0); +} +uint8_t u8g_i2c_start(uint8_t sla) { + u8g_i2c_send_mode(0); + + return 1; +} + +void u8g_i2c_stop(void) { +} + +uint8_t u8g_i2c_send_mode(uint8_t mode) { + i2cMode = mode; +} + +uint8_t u8g_i2c_send_byte(uint8_t data) { + wiringPiI2CWriteReg8(fd, i2cMode, data); + + return 1; +} + +uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos) +{ + return 1; +} + +#else + +/* empty interface */ + +void u8g_i2c_init(uint8_t options) +{ + u8g_i2c_clear_error(); +} + +uint8_t u8g_i2c_wait(uint8_t mask, uint8_t pos) +{ + return 1; +} + +uint8_t u8g_i2c_start(uint8_t sla) +{ + return 1; +} +uint8_t u8g_i2c_send_byte(uint8_t data) +{ + return 1; +} + +void u8g_i2c_stop(void) +{ +} + + +#endif +// ============== u8g_pb8v1.c =============== + +/* + + u8g_pb8v1.c + + 8bit height monochrom (1 bit) page buffer + byte has vertical orientation + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + +*/ + +void u8g_pb8v1_Init(u8g_pb_t *b, void *buf, u8g_uint_t width) U8G_NOINLINE; +void u8g_pb8v1_set_pixel(u8g_pb_t *b, u8g_uint_t x, u8g_uint_t y, uint8_t color_index) U8G_NOINLINE; +void u8g_pb8v1_SetPixel(u8g_pb_t *b, const u8g_dev_arg_pixel_t * const arg_pixel) U8G_NOINLINE ; +void u8g_pb8v1_Set8PixelStd(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) U8G_NOINLINE; + +/* Obsolete, usually set by the init of the structure */ +void u8g_pb8v1_Init(u8g_pb_t *b, void *buf, u8g_uint_t width) +{ + b->buf = buf; + b->width = width; + u8g_pb_Clear(b); +} + +void u8g_pb8v1_set_pixel(u8g_pb_t *b, u8g_uint_t x, u8g_uint_t y, uint8_t color_index) +{ + register uint8_t mask; + uint8_t *ptr = (uint8_t*)b->buf; + + y -= b->p.page_y0; + mask = 1; + y &= 0x07; + mask <<= y; + ptr += x; + if ( color_index ) + { + *ptr |= mask; + } + else + { + mask ^=0xff; + *ptr &= mask; + } +} + + +void u8g_pb8v1_SetPixel(u8g_pb_t *b, const u8g_dev_arg_pixel_t * const arg_pixel) +{ + if ( arg_pixel->y < b->p.page_y0 ) + return; + if ( arg_pixel->y > b->p.page_y1 ) + return; + if ( arg_pixel->x >= b->width ) + return; + u8g_pb8v1_set_pixel(b, arg_pixel->x, arg_pixel->y, arg_pixel->color); +} + +void u8g_pb8v1_Set8PixelStd(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) +{ + register uint8_t pixel = arg_pixel->pixel; + do + { + if ( pixel & 128 ) + { + u8g_pb8v1_SetPixel(b, arg_pixel); + } + switch( arg_pixel->dir ) + { + case 0: arg_pixel->x++; break; + case 1: arg_pixel->y++; break; + case 2: arg_pixel->x--; break; + case 3: arg_pixel->y--; break; + } + pixel <<= 1; + } while( pixel != 0 ); +} + + +void u8g_pb8v1_Set8PixelOpt2(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) +{ + register uint8_t pixel = arg_pixel->pixel; + u8g_uint_t dx = 0; + u8g_uint_t dy = 0; + + switch( arg_pixel->dir ) + { + case 0: dx++; break; + case 1: dy++; break; + case 2: dx--; break; + case 3: dy--; break; + } + + do + { + if ( pixel & 128 ) + u8g_pb8v1_SetPixel(b, arg_pixel); + arg_pixel->x += dx; + arg_pixel->y += dy; + pixel <<= 1; + } while( pixel != 0 ); + +} + +uint8_t u8g_dev_pb8v1_base_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + switch(msg) + { + case U8G_DEV_MSG_SET_8PIXEL: + if ( u8g_pb_Is8PixelVisible(pb, (u8g_dev_arg_pixel_t *)arg) ) + u8g_pb8v1_Set8PixelOpt2(pb, (u8g_dev_arg_pixel_t *)arg); + break; + case U8G_DEV_MSG_SET_PIXEL: + u8g_pb8v1_SetPixel(pb, (u8g_dev_arg_pixel_t *)arg); + break; + case U8G_DEV_MSG_INIT: + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_FIRST: + u8g_pb_Clear(pb); + u8g_page_First(&(pb->p)); + break; + case U8G_DEV_MSG_PAGE_NEXT: + if ( u8g_page_Next(&(pb->p)) == 0 ) + return 0; + u8g_pb_Clear(pb); + break; +#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION + case U8G_DEV_MSG_IS_BBX_INTERSECTION: + return u8g_pb_IsIntersection(pb, (u8g_dev_arg_bbx_t *)arg); +#endif + case U8G_DEV_MSG_GET_PAGE_BOX: + u8g_pb_GetPageBox(pb, (u8g_box_t *)arg); + break; + case U8G_DEV_MSG_GET_WIDTH: + *((u8g_uint_t *)arg) = pb->width; + break; + case U8G_DEV_MSG_GET_HEIGHT: + *((u8g_uint_t *)arg) = pb->p.total_height; + break; + case U8G_DEV_MSG_SET_COLOR_ENTRY: + break; + case U8G_DEV_MSG_SET_XY_CB: + break; + case U8G_DEV_MSG_GET_MODE: + return U8G_MODE_BW; + } + return 1; +} + + +// ============== u8g_pb16v1.c ================ + +/* + + u8g_pb16v1.c + + 16bit height monochrom (1 bit) page buffer + byte has vertical orientation + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + +*/ + +#include + +void u8g_pb16v1_Init(u8g_pb_t *b, void *buf, u8g_uint_t width) U8G_NOINLINE; +void u8g_pb16v1_set_pixel(u8g_pb_t *b, u8g_uint_t x, u8g_uint_t y, uint8_t color_index) U8G_NOINLINE; +void u8g_pb16v1_SetPixel(u8g_pb_t *b, const u8g_dev_arg_pixel_t * const arg_pixel) U8G_NOINLINE ; +void u8g_pb16v1_Set8PixelStd(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) U8G_NOINLINE; + + +void u8g_pb16v1_Clear(u8g_pb_t *b) +{ + uint8_t *ptr = (uint8_t *)b->buf; + uint8_t *end_ptr = ptr; + end_ptr += b->width*2; + do + { + *ptr++ = 0; + } while( ptr != end_ptr ); +} + +/* Obsolete, usually set by the init of the structure */ +void u8g_pb16v1_Init(u8g_pb_t *b, void *buf, u8g_uint_t width) +{ + b->buf = buf; + b->width = width; + u8g_pb16v1_Clear(b); +} + +void u8g_pb16v1_set_pixel(u8g_pb_t *b, u8g_uint_t x, u8g_uint_t y, uint8_t color_index) +{ + register uint8_t mask; + uint8_t *ptr = (uint8_t*)b->buf; + + y -= b->p.page_y0; + if ( y >= 8 ) + { + ptr += b->width; + y &= 0x07; + } + mask = 1; + mask <<= y; + ptr += x; + if ( color_index ) + { + *ptr |= mask; + } + else + { + mask ^=0xff; + *ptr &= mask; + } +} + + +void u8g_pb16v1_SetPixel(u8g_pb_t *b, const u8g_dev_arg_pixel_t * const arg_pixel) +{ + if ( arg_pixel->y < b->p.page_y0 ) + return; + if ( arg_pixel->y > b->p.page_y1 ) + return; + if ( arg_pixel->x >= b->width ) + return; + u8g_pb16v1_set_pixel(b, arg_pixel->x, arg_pixel->y, arg_pixel->color); +} + +void u8g_pb16v1_Set8PixelStd(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) +{ + register uint8_t pixel = arg_pixel->pixel; + do + { + if ( pixel & 128 ) + { + u8g_pb16v1_SetPixel(b, arg_pixel); + } + switch( arg_pixel->dir ) + { + case 0: arg_pixel->x++; break; + case 1: arg_pixel->y++; break; + case 2: arg_pixel->x--; break; + case 3: arg_pixel->y--; break; + } + pixel <<= 1; + } while( pixel != 0 ); +} + + +void u8g_pb16v1_Set8PixelOpt2(u8g_pb_t *b, u8g_dev_arg_pixel_t *arg_pixel) +{ + register uint8_t pixel = arg_pixel->pixel; + u8g_uint_t dx = 0; + u8g_uint_t dy = 0; + + switch( arg_pixel->dir ) + { + case 0: dx++; break; + case 1: dy++; break; + case 2: dx--; break; + case 3: dy--; break; + } + + do + { + if ( pixel & 128 ) + u8g_pb16v1_SetPixel(b, arg_pixel); + arg_pixel->x += dx; + arg_pixel->y += dy; + pixel <<= 1; + } while( pixel != 0 ); + +} + +uint8_t u8g_dev_pb16v1_base_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + switch(msg) + { + case U8G_DEV_MSG_SET_8PIXEL: + if ( u8g_pb_Is8PixelVisible(pb, (u8g_dev_arg_pixel_t *)arg) ) + u8g_pb16v1_Set8PixelOpt2(pb, (u8g_dev_arg_pixel_t *)arg); + break; + case U8G_DEV_MSG_SET_PIXEL: + u8g_pb16v1_SetPixel(pb, (u8g_dev_arg_pixel_t *)arg); + break; + case U8G_DEV_MSG_INIT: + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_FIRST: + u8g_pb16v1_Clear(pb); + u8g_page_First(&(pb->p)); + break; + case U8G_DEV_MSG_PAGE_NEXT: + if ( u8g_page_Next(&(pb->p)) == 0 ) + return 0; + u8g_pb16v1_Clear(pb); + break; +#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION + case U8G_DEV_MSG_IS_BBX_INTERSECTION: + return u8g_pb_IsIntersection(pb, (u8g_dev_arg_bbx_t *)arg); +#endif + case U8G_DEV_MSG_GET_PAGE_BOX: + u8g_pb_GetPageBox(pb, (u8g_box_t *)arg); + break; + case U8G_DEV_MSG_GET_WIDTH: + *((u8g_uint_t *)arg) = pb->width; + break; + case U8G_DEV_MSG_GET_HEIGHT: + *((u8g_uint_t *)arg) = pb->p.total_height; + break; + case U8G_DEV_MSG_SET_COLOR_ENTRY: + break; + case U8G_DEV_MSG_SET_XY_CB: + break; + case U8G_DEV_MSG_GET_MODE: + return U8G_MODE_BW; + } + return 1; +} + +// ========== u8g_arduino_sw_spi.c ================ + +/* + + u8g_arduino_sw_spi.c + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + Update for ATOMIC operation done (01 Jun 2013) + U8G_ATOMIC_OR(ptr, val) + U8G_ATOMIC_AND(ptr, val) + U8G_ATOMIC_START(); + U8G_ATOMIC_END(); + + +*/ + +#if defined(ARDUINO) + +/*=========================================================*/ +/* Arduino, AVR */ + +#if defined(__AVR__) + +//uint8_t u8g_bitData, u8g_bitNotData; +//uint8_t u8g_bitClock, u8g_bitNotClock; +//volatile uint8_t *u8g_outData; +//volatile uint8_t *u8g_outClock; + +/*static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) +{ + u8g_outData = portOutputRegister(digitalPinToPort(dataPin)); + u8g_outClock = portOutputRegister(digitalPinToPort(clockPin)); + u8g_bitData = digitalPinToBitMask(dataPin); + u8g_bitClock = digitalPinToBitMask(clockPin); + + u8g_bitNotClock = u8g_bitClock; + u8g_bitNotClock ^= 0x0ff; + + u8g_bitNotData = u8g_bitData; + u8g_bitNotData ^= 0x0ff; +} + +static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) U8G_NOINLINE; +static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) +{ + uint8_t cnt = 8; + uint8_t bitData = u8g_bitData; + uint8_t bitNotData = u8g_bitNotData; + uint8_t bitClock = u8g_bitClock; + uint8_t bitNotClock = u8g_bitNotClock; + volatile uint8_t *outData = u8g_outData; + volatile uint8_t *outClock = u8g_outClock; + U8G_ATOMIC_START(); + do + { + if ( val & 128 ) + *outData |= bitData; + else + *outData &= bitNotData; + + *outClock |= bitClock; + val <<= 1; + cnt--; + *outClock &= bitNotClock; + } while( cnt != 0 ); + U8G_ATOMIC_END(); +}*/ + +/*=========================================================*/ +/* Arduino, Chipkit */ +#elif defined(__18CXX) || defined(__PIC32MX) + +uint16_t dog_bitData, dog_bitNotData; +uint16_t dog_bitClock, dog_bitNotClock; +volatile uint32_t *dog_outData; +volatile uint32_t *dog_outClock; +volatile uint32_t dog_pic32_spi_tmp; + +static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) +{ + dog_outData = portOutputRegister(digitalPinToPort(dataPin)); + dog_outClock = portOutputRegister(digitalPinToPort(clockPin)); + dog_bitData = digitalPinToBitMask(dataPin); + dog_bitClock = digitalPinToBitMask(clockPin); + + dog_bitNotClock = dog_bitClock; + dog_bitNotClock ^= 0x0ffff; + + dog_bitNotData = dog_bitData; + dog_bitNotData ^= 0x0ffff; +} + +static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) +{ + uint8_t cnt = 8; + U8G_ATOMIC_START(); + do + { + if ( val & 128 ) + *dog_outData |= dog_bitData; + else + *dog_outData &= dog_bitNotData; + val <<= 1; + /* + There must be some delay here. However + fetching the adress dog_outClock is enough delay, so + do not place dog_outClock in a local variable. This will + break the procedure + */ + *dog_outClock |= dog_bitClock; + cnt--; + *dog_outClock &= dog_bitNotClock; + /* + little additional delay after clk pulse, done by 3x32bit reads + from I/O. Optimized for PIC32 with 80 MHz. + */ + dog_pic32_spi_tmp = *dog_outClock; + dog_pic32_spi_tmp = *dog_outClock; + dog_pic32_spi_tmp = *dog_outClock; + } while( cnt != 0 ); + U8G_ATOMIC_END(); +} + +/*=========================================================*/ +/* Arduino Due */ +#elif defined(__SAM3X8E__) + +/* Due */ + +void u8g_digital_write_sam_high(uint8_t pin) +{ + PIO_Set( g_APinDescription[pin].pPort, g_APinDescription[pin].ulPin) ; +} + +void u8g_digital_write_sam_low(uint8_t pin) +{ + PIO_Clear( g_APinDescription[pin].pPort, g_APinDescription[pin].ulPin) ; +} + +static uint8_t u8g_sam_data_pin; +static uint8_t u8g_sam_clock_pin; + +/*static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) +{ + u8g_sam_data_pin = dataPin; + u8g_sam_clock_pin = clockPin; +} + +static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) +{ + uint8_t i = 8; + do + { + if ( val & 128 ) + u8g_digital_write_sam_high(u8g_sam_data_pin); + else + u8g_digital_write_sam_low(u8g_sam_data_pin); + val <<= 1; + //u8g_MicroDelay(); + u8g_digital_write_sam_high(u8g_sam_clock_pin); + u8g_MicroDelay(); + u8g_digital_write_sam_low(u8g_sam_clock_pin); + u8g_MicroDelay(); + i--; + } while( i != 0 ); +} +*/ + +#else +/* empty interface */ + +static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) +{ +} + +static void u8g_com_arduino_do_shift_out_msb_first(uint8_t val) +{ +} + +#endif + + +uint8_t u8g_com_arduino_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + switch(msg) + { + case U8G_COM_MSG_INIT: + u8g_com_arduino_assign_pin_output_high(u8g); + u8g_com_arduino_digital_write(u8g, U8G_PI_SCK, LOW); + u8g_com_arduino_digital_write(u8g, U8G_PI_MOSI, LOW); + u8g_com_arduino_init_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK]); + break; + + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_RESET: + if ( u8g->pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) + u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); + break; + + case U8G_COM_MSG_CHIP_SELECT: + if ( arg_val == 0 ) + { + /* disable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS, HIGH); + } + else + { + /* enable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_SCK, LOW); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS, LOW); + /* issue 227 */ + u8g_com_arduino_init_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK]); + } + break; + + case U8G_COM_MSG_WRITE_BYTE: + u8g_com_arduino_do_shift_out_msb_first( arg_val ); + //u8g_arduino_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], arg_val); + break; + + case U8G_COM_MSG_WRITE_SEQ: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_com_arduino_do_shift_out_msb_first(*ptr++); + // u8g_arduino_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], *ptr++); + arg_val--; + } + } + break; + + case U8G_COM_MSG_WRITE_SEQ_P: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_com_arduino_do_shift_out_msb_first( u8g_pgm_read(ptr) ); + //u8g_arduino_sw_spi_shift_out(u8g->pin_list[U8G_PI_MOSI], u8g->pin_list[U8G_PI_SCK], u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } + break; + + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + u8g_com_arduino_digital_write(u8g, U8G_PI_A0, arg_val); + break; + } + return 1; +} + +#else /* ARDUINO */ + +uint8_t u8g_com_arduino_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + return 1; +} + +#endif /* ARDUINO */ + +// ================ u8g_dev_ks0108_128x64.c =================== + +/* + + u8g_dev_ks0108_128x64.c + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + + ADDRESS = 0 (Command Mode) + 0x03f Display On + 0x0c0 Start Display at line 0 + 0x040 | y write to y address (y:0..63) + 0x0b8 | x write to page [0..7] + + + u8g_Init8Bit(u8g, dev, d0, d1, d2, d3, d4, d5, d6, d7, en, cs1, cs2, di, rw, reset) + u8g_Init8Bit(u8g, dev, 8, 9, 10, 11, 4, 5, 6, 7, 18, 14, 15, 17, 16, U8G_PIN_NONE) + +*/ + +#define WIDTH 128 +#define HEIGHT 64 +#define PAGE_HEIGHT 8 + +static const uint8_t u8g_dev_ks0108_128x64_init_seq[] PROGMEM = { + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_RST(1), /* do reset low pulse with (1*16)+2 milliseconds */ + U8G_ESC_CS(1), /* enable chip 1 */ + 0x03f, /* display on */ + 0x0c0, /* start at line 0 */ + U8G_ESC_DLY(20), /* delay 20 ms */ + U8G_ESC_CS(2), /* enable chip 2 */ + 0x03f, /* display on */ + 0x0c0, /* start at line 0 */ + U8G_ESC_DLY(20), /* delay 20 ms */ + U8G_ESC_CS(0), /* disable all chips */ + U8G_ESC_END /* end of sequence */ +}; + + +uint8_t u8g_dev_ks0108_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + + switch(msg) + { + case U8G_DEV_MSG_INIT: + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_NONE); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_ks0108_128x64_init_seq); + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_NEXT: + { + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + + u8g_SetAddress(u8g, dev, 0); /* command mode */ + u8g_SetChipSelect(u8g, dev, 2); + u8g_WriteByte(u8g, dev, 0x0b8 | pb->p.page); /* select current page (KS0108b) */ + u8g_WriteByte(u8g, dev, 0x040 ); /* set address 0 */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + u8g_WriteSequence(u8g, dev, 64, (uint8_t*)pb->buf); + u8g_SetChipSelect(u8g, dev, 0); + + u8g_SetAddress(u8g, dev, 0); /* command mode */ + u8g_SetChipSelect(u8g, dev, 1); + u8g_WriteByte(u8g, dev, 0x0b8 | pb->p.page); /* select current page (KS0108b) */ + u8g_WriteByte(u8g, dev, 0x040 ); /* set address 0 */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + u8g_WriteSequence(u8g, dev, 64, 64+(uint8_t *)pb->buf); + u8g_SetChipSelect(u8g, dev, 0); + + } + break; + } + return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); +} + +U8G_PB_DEV(u8g_dev_ks0108_128x64, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ks0108_128x64_fn, U8G_COM_PARALLEL); +U8G_PB_DEV(u8g_dev_ks0108_128x64_fast, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_ks0108_128x64_fn, U8G_COM_FAST_PARALLEL); + +// ================= 8g_com_arduino_parallel.c ================== + +/* + + u8g_com_arduino_parallel.c + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + + PIN_D0 8 + PIN_D1 9 + PIN_D2 10 + PIN_D3 11 + PIN_D4 4 + PIN_D5 5 + PIN_D6 6 + PIN_D7 7 + + PIN_CS1 14 + PIN_CS2 15 + PIN_RW 16 + PIN_DI 17 + PIN_EN 18 + + u8g_Init8Bit(u8g, dev, d0, d1, d2, d3, d4, d5, d6, d7, en, cs1, cs2, di, rw, reset) + u8g_Init8Bit(u8g, dev, 8, 9, 10, 11, 4, 5, 6, 7, 18, 14, 15, 17, 16, U8G_PIN_NONE) + +*/ + +#if defined(ARDUINO) + + +void u8g_com_arduino_parallel_write(u8g_t *u8g, uint8_t val) +{ + u8g_com_arduino_digital_write(u8g, U8G_PI_D0, val&1); + val >>= 1; + u8g_com_arduino_digital_write(u8g, U8G_PI_D1, val&1); + val >>= 1; + u8g_com_arduino_digital_write(u8g, U8G_PI_D2, val&1); + val >>= 1; + u8g_com_arduino_digital_write(u8g, U8G_PI_D3, val&1); + val >>= 1; + u8g_com_arduino_digital_write(u8g, U8G_PI_D4, val&1); + val >>= 1; + u8g_com_arduino_digital_write(u8g, U8G_PI_D5, val&1); + val >>= 1; + u8g_com_arduino_digital_write(u8g, U8G_PI_D6, val&1); + val >>= 1; + u8g_com_arduino_digital_write(u8g, U8G_PI_D7, val&1); + + /* EN cycle time must be 1 micro second, digitalWrite is slow enough to do this */ + u8g_com_arduino_digital_write(u8g, U8G_PI_EN, HIGH); + u8g_MicroDelay(); /* delay by 1000ns, reference: ST7920: 140ns, SBN1661: 100ns */ + u8g_com_arduino_digital_write(u8g, U8G_PI_EN, LOW); + u8g_10MicroDelay(); /* ST7920 commands: 72us */ +} + + +uint8_t u8g_com_arduino_parallel_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + switch(msg) + { + case U8G_COM_MSG_INIT: + /* setup the RW pin as output and force it to low */ + if ( u8g->pin_list[U8G_PI_RW] != U8G_PIN_NONE ) + { + pinMode(u8g->pin_list[U8G_PI_RW], OUTPUT); + u8g_com_arduino_digital_write(u8g, U8G_PI_RW, LOW); + } + /* set all pins (except RW pin) */ + u8g_com_arduino_assign_pin_output_high(u8g); + break; + case U8G_COM_MSG_STOP: + break; + case U8G_COM_MSG_CHIP_SELECT: + if ( arg_val == 0 ) + { + /* disable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, HIGH); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, HIGH); + } + else if ( arg_val == 1 ) + { + /* enable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, LOW); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, HIGH); + } + else if ( arg_val == 2 ) + { + /* enable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, HIGH); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, LOW); + } + else + { + /* enable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, LOW); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, LOW); + } + break; + case U8G_COM_MSG_WRITE_BYTE: + u8g_com_arduino_parallel_write(u8g, arg_val); + break; + case U8G_COM_MSG_WRITE_SEQ: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_com_arduino_parallel_write(u8g, *ptr++); + arg_val--; + } + } + break; + case U8G_COM_MSG_WRITE_SEQ_P: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_com_arduino_parallel_write(u8g, u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } + break; + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + u8g_com_arduino_digital_write(u8g, U8G_PI_DI, arg_val); + break; + case U8G_COM_MSG_RESET: + if ( u8g->pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) + u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); + break; + + } + return 1; +} + +#else + + +uint8_t u8g_com_arduino_parallel_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + return 1; +} + +#endif /* ARDUINO */ + + +// =============== u8g_arduino_fast_parallel.c ================ +/* + + u8g_arduino_fast_parallel.c + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + PIN_D0 8 + PIN_D1 9 + PIN_D2 10 + PIN_D3 11 + PIN_D4 4 + PIN_D5 5 + PIN_D6 6 + PIN_D7 7 + + PIN_CS1 14 + PIN_CS2 15 + PIN_RW 16 + PIN_DI 17 + PIN_EN 18 + + u8g_Init8Bit(u8g, dev, d0, d1, d2, d3, d4, d5, d6, d7, en, cs1, cs2, di, rw, reset) + u8g_Init8Bit(u8g, dev, 8, 9, 10, 11, 4, 5, 6, 7, 18, 14, 15, 17, 16, U8G_PIN_NONE) + + Update for ATOMIC operation done (01 Jun 2013) + U8G_ATOMIC_OR(ptr, val) + U8G_ATOMIC_AND(ptr, val) + U8G_ATOMIC_START(); + U8G_ATOMIC_END(); + +*/ + +#if defined(ARDUINO) + +#define PIN_D0 UI_DISPLAY_D0_PIN +#define PIN_D1 UI_DISPLAY_D1_PIN +#define PIN_D2 UI_DISPLAY_D2_PIN +#define PIN_D3 UI_DISPLAY_D3_PIN +#define PIN_D4 UI_DISPLAY_D4_PIN +#define PIN_D5 UI_DISPLAY_D5_PIN +#define PIN_D6 UI_DISPLAY_D6_PIN +#define PIN_D7 UI_DISPLAY_D7_PIN + +#define PIN_CS1 UI_DISPLAY_CS1 +#define PIN_CS2 UI_DISPLAY_CS2 +#define PIN_RW UI_DISPLAY_RW_PIN +#define PIN_DI UI_DISPLAY_DI +#define PIN_EN UI_DISPLAY_ENABLE_PIN + +//#define PIN_RESET + + +#if defined(__PIC32MX) +/* CHIPKIT PIC32 */ +static volatile uint32_t *u8g_data_port[8]; +static uint32_t u8g_data_mask[8]; +#else +static volatile uint8_t *u8g_data_port[8]; +static uint8_t u8g_data_mask[8]; +#endif + + + +static void u8g_com_arduino_fast_parallel_init(u8g_t *u8g) +{ + u8g_data_port[0] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D0]));// added conversion for due to compile + u8g_data_mask[0] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D0]); + u8g_data_port[1] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D1]));// added conversion for due to compile + u8g_data_mask[1] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D1]); + u8g_data_port[2] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D2]));// added conversion for due to compile + u8g_data_mask[2] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D2]); + u8g_data_port[3] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D3]));// added conversion for due to compile + u8g_data_mask[3] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D3]); + + u8g_data_port[4] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D4])); // added conversion for due to compile + u8g_data_mask[4] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D4]); + u8g_data_port[5] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D5]));// added conversion for due to compile + u8g_data_mask[5] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D5]); + u8g_data_port[6] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D6]));// added conversion for due to compile + u8g_data_mask[6] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D6]); + u8g_data_port[7] = (volatile uint8_t*)portOutputRegister(digitalPinToPort(u8g->pin_list[U8G_PI_D7]));// added conversion for due to compile + u8g_data_mask[7] = digitalPinToBitMask(u8g->pin_list[U8G_PI_D7]); +} + +/* atomic protection must be done by calling function */ +static void u8g_com_arduino_fast_write_data_pin(uint8_t pin, uint8_t val) +{ + if ( val != 0 ) + *u8g_data_port[pin] |= u8g_data_mask[pin]; + else + *u8g_data_port[pin] &= ~u8g_data_mask[pin]; +} + + +void u8g_com_arduino_fast_parallel_write(u8g_t *u8g, uint8_t val) +{ + U8G_ATOMIC_START(); + u8g_com_arduino_fast_write_data_pin( 0, val&1 ); + val >>= 1; + u8g_com_arduino_fast_write_data_pin( 1, val&1 ); + val >>= 1; + u8g_com_arduino_fast_write_data_pin( 2, val&1 ); + val >>= 1; + u8g_com_arduino_fast_write_data_pin( 3, val&1 ); + val >>= 1; + + u8g_com_arduino_fast_write_data_pin( 4, val&1 ); + val >>= 1; + u8g_com_arduino_fast_write_data_pin( 5, val&1 ); + val >>= 1; + u8g_com_arduino_fast_write_data_pin( 6, val&1 ); + val >>= 1; + u8g_com_arduino_fast_write_data_pin( 7, val&1 ); + val >>= 1; + U8G_ATOMIC_END(); + + /* EN cycle time must be 1 micro second */ + u8g_com_arduino_digital_write(u8g, U8G_PI_EN, HIGH); + u8g_MicroDelay(); /* delay by 1000ns, reference: ST7920: 140ns, SBN1661: 100ns */ + u8g_com_arduino_digital_write(u8g, U8G_PI_EN, LOW); + u8g_10MicroDelay(); /* ST7920 commands: 72us */ + u8g_10MicroDelay(); /* ST7920 commands: 72us */ +} + + +uint8_t u8g_com_arduino_fast_parallel_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + switch(msg) + { + case U8G_COM_MSG_INIT: + u8g_com_arduino_fast_parallel_init(u8g); + /* setup the RW pin as output and force it to low */ + if ( u8g->pin_list[U8G_PI_RW] != U8G_PIN_NONE ) + { + pinMode(u8g->pin_list[U8G_PI_RW], OUTPUT); + u8g_com_arduino_digital_write(u8g, U8G_PI_RW, LOW); + } + /* set all pins (except RW pin) */ + u8g_com_arduino_assign_pin_output_high(u8g); + break; + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_CHIP_SELECT: + if ( arg_val == 0 ) + { + /* disable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, HIGH); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, HIGH); + } + else if ( arg_val == 1 ) + { + /* enable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, LOW); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, HIGH); + } + else if ( arg_val == 2 ) + { + /* enable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, HIGH); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, LOW); + } + else + { + /* enable */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS1, LOW); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS2, LOW); + } + break; + case U8G_COM_MSG_WRITE_BYTE: + u8g_com_arduino_fast_parallel_write(u8g, arg_val); + break; + case U8G_COM_MSG_WRITE_SEQ: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_com_arduino_fast_parallel_write(u8g, *ptr++); + arg_val--; + } + } + break; + case U8G_COM_MSG_WRITE_SEQ_P: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_com_arduino_fast_parallel_write(u8g, u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } + break; + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + u8g_com_arduino_digital_write(u8g, U8G_PI_DI, arg_val); + break; + case U8G_COM_MSG_RESET: + if ( u8g->pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) + u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); + break; + + } + return 1; +} + +#else + + +uint8_t u8g_com_arduino_fast_parallel_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + return 1; +} + + +#endif /* ARDUINO */ + + +/* + + u8g_dev_st7565_nhd_c12864.c + + Support for the NHD-C12864A1Z-FSB-FBW (Newhaven Display) + + Universal 8bit Graphics Library + + Copyright (c) 2012, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + +*/ + +#define WIDTH 128 +#define HEIGHT 64 +#define PAGE_HEIGHT 8 + +const uint8_t u8g_dev_st7565_nhd_c12864_init_seq[] PROGMEM = { + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_RST(10), /* do reset low pulse with (10*16)+2 milliseconds */ + U8G_ESC_CS(1), /* enable chip */ + + 0x040, /* set display start line */ + 0x0a1, /* ADC set to reverse */ + 0x0c0, /* common output mode: set scan direction normal operation */ + 0x0a6, /* display normal, bit val 0: LCD pixel off. */ + 0x0a2, /* LCD bias 1/9 */ + 0x02f, /* all power control circuits on */ + 0x0f8, /* set booster ratio to */ + 0x000, /* 4x */ + 0x027, /* set V0 voltage resistor ratio to large */ + 0x081, /* set contrast */ + 0x008, /* contrast: 0x008 is a good value for NHD C12864, Nov 2012: User reports that 0x1a is much better */ + 0x0ac, /* indicator */ + 0x000, /* disable */ + 0x0af, /* display on */ + + U8G_ESC_DLY(100), /* delay 100 ms */ + 0x0a5, /* display all points, ST7565 */ + U8G_ESC_DLY(100), /* delay 100 ms */ + U8G_ESC_DLY(100), /* delay 100 ms */ + 0x0a4, /* normal display */ + U8G_ESC_CS(0), /* disable chip */ + U8G_ESC_END /* end of sequence */ +}; + +static const uint8_t u8g_dev_st7565_nhd_c12864_data_start[] PROGMEM = { + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_CS(1), /* enable chip */ + 0x010, /* set upper 4 bit of the col adr to 0 */ + 0x004, /* set lower 4 bit of the col adr to 4 (NHD C12864) */ + U8G_ESC_END /* end of sequence */ +}; + +static const uint8_t u8g_dev_st7565_c12864_sleep_on[] PROGMEM = { + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_CS(1), /* enable chip */ + 0x0ac, /* static indicator off */ + 0x000, /* indicator register set (not sure if this is required) */ + 0x0ae, /* display off */ + 0x0a5, /* all points on */ + U8G_ESC_CS(0), /* disable chip, bugfix 12 nov 2014 */ + U8G_ESC_END /* end of sequence */ +}; + +static const uint8_t u8g_dev_st7565_c12864_sleep_off[] PROGMEM = { + U8G_ESC_ADR(0), /* instruction mode */ + U8G_ESC_CS(1), /* enable chip */ + 0x0a4, /* all points off */ + 0x0af, /* display on */ + U8G_ESC_DLY(50), /* delay 50 ms */ + U8G_ESC_CS(0), /* disable chip, bugfix 12 nov 2014 */ + U8G_ESC_END /* end of sequence */ +}; + +uint8_t u8g_dev_st7565_nhd_c12864_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + switch(msg) + { + case U8G_DEV_MSG_INIT: +#if defined(__SAM3X8E__) + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_400NS); +#else + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_400NS); +#endif + u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_init_seq); + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_NEXT: + { + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | pb->p.page); /* select current page (ST7565R) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + if ( u8g_pb_WriteBuffer(pb, u8g, dev) == 0 ) + return 0; + u8g_SetChipSelect(u8g, dev, 0); + } + break; + case U8G_DEV_MSG_CONTRAST: + u8g_SetChipSelect(u8g, dev, 1); + u8g_SetAddress(u8g, dev, 0); /* instruction mode */ + u8g_WriteByte(u8g, dev, 0x081); + u8g_WriteByte(u8g, dev, (*(uint8_t *)arg) >> 2); + u8g_SetChipSelect(u8g, dev, 0); + return 1; + case U8G_DEV_MSG_SLEEP_ON: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_c12864_sleep_on); + return 1; + case U8G_DEV_MSG_SLEEP_OFF: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_c12864_sleep_off); + return 1; + } + return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); +} + +uint8_t u8g_dev_st7565_nhd_c12864_2x_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + switch(msg) + { + case U8G_DEV_MSG_INIT: + u8g_InitCom(u8g, dev, U8G_SPI_CLK_CYCLE_400NS); + u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_init_seq); + break; + case U8G_DEV_MSG_STOP: + break; + case U8G_DEV_MSG_PAGE_NEXT: + { + u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem); + + u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | (2*pb->p.page)); /* select current page (ST7565R) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + u8g_WriteSequence(u8g, dev, pb->width, (uint8_t*)pb->buf); + u8g_SetChipSelect(u8g, dev, 0); + + u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_nhd_c12864_data_start); + u8g_WriteByte(u8g, dev, 0x0b0 | (2*pb->p.page+1)); /* select current page (ST7565R) */ + u8g_SetAddress(u8g, dev, 1); /* data mode */ + u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)(pb->buf)+pb->width); + u8g_SetChipSelect(u8g, dev, 0); + } + break; + case U8G_DEV_MSG_CONTRAST: + u8g_SetChipSelect(u8g, dev, 1); + u8g_SetAddress(u8g, dev, 0); /* instruction mode */ + u8g_WriteByte(u8g, dev, 0x081); + u8g_WriteByte(u8g, dev, (*(uint8_t *)arg) >> 2); + u8g_SetChipSelect(u8g, dev, 0); + return 1; + case U8G_DEV_MSG_SLEEP_ON: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_c12864_sleep_on); + return 1; + case U8G_DEV_MSG_SLEEP_OFF: + u8g_WriteEscSeqP(u8g, dev, u8g_dev_st7565_c12864_sleep_off); + return 1; + } + return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg); +} + +U8G_PB_DEV(u8g_dev_st7565_nhd_c12864_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_st7565_nhd_c12864_fn, U8G_COM_SW_SPI); +U8G_PB_DEV(u8g_dev_st7565_nhd_c12864_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_st7565_nhd_c12864_fn, U8G_COM_HW_SPI); + + +uint8_t u8g_dev_st7565_nhd_c12864_2x_buf[WIDTH*2] U8G_NOCOMMON ; +u8g_pb_t u8g_dev_st7565_nhd_c12864_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_st7565_nhd_c12864_2x_buf}; +u8g_dev_t u8g_dev_st7565_nhd_c12864_2x_sw_spi = { u8g_dev_st7565_nhd_c12864_2x_fn, &u8g_dev_st7565_nhd_c12864_2x_pb, U8G_COM_SW_SPI }; +u8g_dev_t u8g_dev_st7565_nhd_c12864_2x_hw_spi = { u8g_dev_st7565_nhd_c12864_2x_fn, &u8g_dev_st7565_nhd_c12864_2x_pb, U8G_COM_HW_SPI }; + +/* + + u8g_com_arduino_hw_spi.c + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + SPI Clock Cycle Type + + SSD1351 50ns 20 MHz + SSD1322 300ns 3.3 MHz + SSD1327 300ns + SSD1306 300ns + ST7565 400ns 2.5 MHz + ST7920 400ns + + Arduino DUE + + PA25 MISO + PA26 MOSI 75 + PA27 SCLK 76 + + +typedef struct { + WoReg SPI_CR; (Spi Offset: 0x00) Control Register + RwReg SPI_MR; (Spi Offset: 0x04) Mode Register + RoReg SPI_RDR; (Spi Offset: 0x08) Receive Data Register + WoReg SPI_TDR; (Spi Offset: 0x0C) Transmit Data Register + RoReg SPI_SR; (Spi Offset: 0x10) Status Register + WoReg SPI_IER; (Spi Offset: 0x14) Interrupt Enable Register + WoReg SPI_IDR; (Spi Offset: 0x18) Interrupt Disable Register + RoReg SPI_IMR; (Spi Offset: 0x1C) Interrupt Mask Register + RoReg Reserved1[4]; + RwReg SPI_CSR[4]; (Spi Offset: 0x30) Chip Select Register + RoReg Reserved2[41]; + RwReg SPI_WPMR; (Spi Offset: 0xE4) Write Protection Control Register + RoReg SPI_WPSR; (Spi Offset: 0xE8) Write Protection Status Register +} Spi; + + Power Management Controller (PMC) + arduino-1.5.2/hardware/arduino/sam/system/CMSIS/Device/ATMEL/sam3xa/include/instance/instance_pmc.h + - enable PIO + + REG_PMC_PCER0 = 1UL << ID_PIOA + - enable SPI + REG_PMC_PCER0 = 1UL << ID_SPI0 + + + - enable PIOA and SPI0 + REG_PMC_PCER0 = (1UL << ID_PIOA) | (1UL << ID_SPI0); + + Parallel Input/Output Controller (PIO) + arduino-1.5.2/hardware/arduino/sam/system/CMSIS/Device/ATMEL/sam3xa/include/instance/instance_pioa.h + - enable special function of the pin: disable PIO on A26 and A27: + REG_PIOA_PDR = 0x0c000000 + PIOA->PIO_PDR = 0x0c000000 + + SPI + SPI0->SPI_CR = SPI_CR_SPIDIS + SPI0->SPI_CR = SPI_CR_SWRST ; + SPI0->SPI_CR = SPI_CR_SWRST ; + SPI0->SPI_CR = SPI_CR_SPIEN + + Bit 0: Master Mode = 1 (active) + Bit 1: Peripheral Select = 0 (fixed) + Bit 2: Chip Select Decode Mode = 1 (4 to 16) + Bit 4: Mode Fault Detection = 1 (disabled) + Bit 5: Wait Data Read = 0 (disabled) + Bit 7: Loop Back Mode = 0 (disabled) + Bit 16-19: Peripheral Chip Select = 0 (chip select 0) + SPI0->SPI_MR = SPI_MR_MSTR | SPI_MR_PCSDEC | SPI_MR_MODFDIS + + Bit 0: Clock Polarity = 0 + Bit 1: Clock Phase = 0 + Bit 4-7: Bits = 0 (8 Bit) + Bit 8-15: SCBR = 1 + SPI0->SPI_CSR[0] = SPI_CSR_SCBR(x) Serial Baud Rate + SCBR / 84000000 > 50 / 1000000000 + SCBR / 84 > 5 / 100 + SCBR > 50 *84 / 1000 --> SCBR=5 + SCBR > 300*84 / 1000 --> SCBR=26 + SCBR > 400*84 / 1000 --> SCBR=34 + + Arduino Due test code: + REG_PMC_PCER0 = (1UL << ID_PIOA) | (1UL << ID_SPI0); + REG_PIOA_PDR = 0x0c000000; + SPI0->SPI_CR = SPI_CR_SPIDIS; + SPI0->SPI_CR = SPI_CR_SWRST; + SPI0->SPI_CR = SPI_CR_SWRST; + SPI0->SPI_CR = SPI_CR_SPIEN; + SPI0->SPI_MR = SPI_MR_MSTR | SPI_MR_PCSDEC | SPI_MR_MODFDIS; + SPI0->SPI_CSR[0] = SPI_CSR_SCBR(30); + + for(;;) + { + while( (SPI0->SPI_SR & SPI_SR_TDRE) == 0 ) + ; + SPI0->SPI_TDR = 0x050; + } + +*/ + +#if defined(ARDUINO) + +#if defined(__AVR__) +#define U8G_ARDUINO_ATMEGA_HW_SPI +/* remove the definition for attiny */ +#if __AVR_ARCH__ == 2 +#undef U8G_ARDUINO_ATMEGA_HW_SPI +#endif +#if __AVR_ARCH__ == 25 +#undef U8G_ARDUINO_ATMEGA_HW_SPI +#endif +#endif + +#if defined(U8G_ARDUINO_ATMEGA_HW_SPI) + +//#include +//#include + +#if ARDUINO < 100 + +/* fixed pins */ +#if defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__) // Sanguino.cc board +#define PIN_SCK 7 +#define PIN_MISO 6 +#define PIN_MOSI 5 +#define PIN_CS 4 +#else // Arduino Board +#define PIN_SCK 13 +#define PIN_MISO 12 +#define PIN_MOSI 11 +#define PIN_CS 10 +#endif // (__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__) + +#else + +/* use Arduino pin definitions */ +#define PIN_SCK SCK +#define PIN_MISO MISO_PIN +#define PIN_MOSI MOSI_PIN +#define PIN_CS SS + +#endif + + + +//static uint8_t u8g_spi_out(uint8_t data) U8G_NOINLINE; +static uint8_t u8g_spi_out(uint8_t data) +{ + /* unsigned char x = 100; */ + /* send data */ + SPDR = data; + /* wait for transmission */ + while (!(SPSR & (1<pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) + u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); + break; + + case U8G_COM_MSG_WRITE_BYTE: + u8g_spi_out(arg_val); + break; + + case U8G_COM_MSG_WRITE_SEQ: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_spi_out(*ptr++); + arg_val--; + } + } + break; + case U8G_COM_MSG_WRITE_SEQ_P: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_spi_out(u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } + break; + } + return 1; +} + +/* #elif defined(__18CXX) || defined(__PIC32MX) */ + +#elif defined(__SAM3X8E__) // Arduino Due, maybe we should better check for __SAM3X8E__ + +/* use Arduino pin definitions */ +#define PIN_SCK SCK +#define PIN_MISO MISO +#define PIN_MOSI MOSI +#define PIN_CS SS + + +static uint8_t u8g_spi_out(uint8_t data) +{ + /* wait until tx register is empty */ + while( (SPI0->SPI_SR & SPI_SR_TDRE) == 0 ) + ; + /* send data */ + SPI0->SPI_TDR = (uint32_t)data; + return data; +} + + +uint8_t u8g_com_arduino_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + switch(msg) + { + case U8G_COM_MSG_STOP: + break; + + case U8G_COM_MSG_INIT: + u8g_com_arduino_assign_pin_output_high(u8g); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS, HIGH); + + /* Arduino Due specific code */ + + /* enable PIOA and SPI0 */ + REG_PMC_PCER0 = (1UL << ID_PIOA) | (1UL << ID_SPI0); + + /* disable PIO on A26 and A27 */ + REG_PIOA_PDR = 0x0c000000; + + /* reset SPI0 (from sam lib) */ + SPI0->SPI_CR = SPI_CR_SPIDIS; + SPI0->SPI_CR = SPI_CR_SWRST; + SPI0->SPI_CR = SPI_CR_SWRST; + SPI0->SPI_CR = SPI_CR_SPIEN; + u8g_MicroDelay(); + + /* master mode, no fault detection, chip select 0 */ + SPI0->SPI_MR = SPI_MR_MSTR | SPI_MR_PCSDEC | SPI_MR_MODFDIS; + + /* Polarity, Phase, 8 Bit data transfer, baud rate */ + /* x * 1000 / 84 --> clock cycle in ns + 5 * 1000 / 84 = 58 ns + SCBR > 50 *84 / 1000 --> SCBR=5 + SCBR > 300*84 / 1000 --> SCBR=26 + SCBR > 400*84 / 1000 --> SCBR=34 + */ + + if ( arg_val <= U8G_SPI_CLK_CYCLE_50NS ) + { + SPI0->SPI_CSR[0] = SPI_CSR_SCBR(5) | 1; + } + else if ( arg_val <= U8G_SPI_CLK_CYCLE_300NS ) + { + SPI0->SPI_CSR[0] = SPI_CSR_SCBR(26) | 1; + } + else if ( arg_val <= U8G_SPI_CLK_CYCLE_400NS ) + { + SPI0->SPI_CSR[0] = SPI_CSR_SCBR(34) | 1; + } + else if ( arg_val <= U8G_SPI_CLK_CYCLE_500NS ) + { + SPI0->SPI_CSR[0] = SPI_CSR_SCBR(42) | 1; + } + else + { + SPI0->SPI_CSR[0] = SPI_CSR_SCBR(84) | 1; + } + + u8g_MicroDelay(); + break; + + case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ + u8g_com_arduino_digital_write(u8g, U8G_PI_A0, arg_val); + u8g_MicroDelay(); + break; + + case U8G_COM_MSG_CHIP_SELECT: + if ( arg_val == 0 ) + { + /* disable */ + u8g_MicroDelay(); /* this delay is required to avoid that the display is switched off too early --> DOGS102 with DUE */ + u8g_com_arduino_digital_write(u8g, U8G_PI_CS, HIGH); + u8g_MicroDelay(); + } + else + { + /* enable */ + //u8g_com_arduino_digital_write(u8g, U8G_PI_SCK, LOW); + u8g_com_arduino_digital_write(u8g, U8G_PI_CS, LOW); + u8g_MicroDelay(); + } + break; + + case U8G_COM_MSG_RESET: + if ( u8g->pin_list[U8G_PI_RESET] != U8G_PIN_NONE ) + u8g_com_arduino_digital_write(u8g, U8G_PI_RESET, arg_val); + break; + + case U8G_COM_MSG_WRITE_BYTE: + u8g_spi_out(arg_val); + u8g_MicroDelay(); + break; + + case U8G_COM_MSG_WRITE_SEQ: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_spi_out(*ptr++); + arg_val--; + } + } + break; + case U8G_COM_MSG_WRITE_SEQ_P: + { + register uint8_t *ptr = (uint8_t*)arg_ptr; + while( arg_val > 0 ) + { + u8g_spi_out(u8g_pgm_read(ptr)); + ptr++; + arg_val--; + } + } + break; + } + return 1; +} + + + +#else /* U8G_ARDUINO_ATMEGA_HW_SPI */ + +#endif /* U8G_ARDUINO_ATMEGA_HW_SPI */ + +#else /* ARDUINO */ + +uint8_t u8g_com_arduino_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) +{ + return 1; +} + +#endif /* ARDUINO */ + +/* + + u8g_rot.c + + Universal 8bit Graphics Library + + Copyright (c) 2011, olikraus@gmail.com + All rights reserved. + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this list + of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, this + list of conditions and the following disclaimer in the documentation and/or other + materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, + INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR + CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, + SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF + ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + +*/ + +uint8_t u8g_dev_rot90_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg); +uint8_t u8g_dev_rot180_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg); +uint8_t u8g_dev_rot270_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg); + +uint8_t u8g_dev_rot_dummy_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + return 0; +} + +u8g_dev_t u8g_dev_rot = { u8g_dev_rot_dummy_fn, NULL, NULL }; + + +void u8g_UndoRotation(u8g_t *u8g) +{ + if ( u8g->dev != &u8g_dev_rot ) + return; + u8g->dev = (u8g_dev_t*)u8g_dev_rot.dev_mem; + u8g_UpdateDimension(u8g); +} + +void u8g_SetRot90(u8g_t *u8g) +{ + if ( u8g->dev != &u8g_dev_rot ) + { + u8g_dev_rot.dev_mem = u8g->dev; + u8g->dev = &u8g_dev_rot; + } + u8g_dev_rot.dev_fn = u8g_dev_rot90_fn; + u8g_UpdateDimension(u8g); +} + +void u8g_SetRot180(u8g_t *u8g) +{ + if ( u8g->dev != &u8g_dev_rot ) + { + u8g_dev_rot.dev_mem = u8g->dev; + u8g->dev = &u8g_dev_rot; + } + u8g_dev_rot.dev_fn = u8g_dev_rot180_fn; + u8g_UpdateDimension(u8g); +} + +void u8g_SetRot270(u8g_t *u8g) +{ + if ( u8g->dev != &u8g_dev_rot ) + { + u8g_dev_rot.dev_mem = u8g->dev; + u8g->dev = &u8g_dev_rot; + } + u8g_dev_rot.dev_fn = u8g_dev_rot270_fn; + u8g_UpdateDimension(u8g); +} + +uint8_t u8g_dev_rot90_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + u8g_dev_t *rotation_chain = (u8g_dev_t *)(dev->dev_mem); + switch(msg) + { + default: + /* + case U8G_DEV_MSG_INIT: + case U8G_DEV_MSG_STOP: + case U8G_DEV_MSG_PAGE_FIRST: + case U8G_DEV_MSG_PAGE_NEXT: + case U8G_DEV_MSG_SET_COLOR_ENTRY: + case U8G_DEV_MSG_SET_XY_CB: + */ + return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); +#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION + case U8G_DEV_MSG_IS_BBX_INTERSECTION: + { + u8g_dev_arg_bbx_t *bbx = (u8g_dev_arg_bbx_t *)arg; + u8g_uint_t x, y, tmp; + + /* transform the reference point */ + y = bbx->x; + x = u8g->height; + /* x = u8g_GetWidthLL(u8g, rotation_chain); */ + x -= bbx->y; + x--; + + /* adjust point to be the uppler left corner again */ + x -= bbx->h; + x++; + + /* swap box dimensions */ + tmp = bbx->w; + bbx->w = bbx->h; + bbx->h = tmp; + + /* store x,y */ + bbx->x = x; + bbx->y = y; + } + return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); +#endif /* U8G_DEV_MSG_IS_BBX_INTERSECTION */ + case U8G_DEV_MSG_GET_PAGE_BOX: + /* get page size from next device in the chain */ + u8g_call_dev_fn(u8g, rotation_chain, msg, arg); + //printf("pre x: %3d..%3d y: %3d..%3d ", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); + { + u8g_box_t new_box; + //new_box.x0 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y1 - 1; + //new_box.x1 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y0 - 1; + + new_box.x0 = ((u8g_box_t *)arg)->y0; + new_box.x1 = ((u8g_box_t *)arg)->y1; + new_box.y0 = ((u8g_box_t *)arg)->x0; + new_box.y1 = ((u8g_box_t *)arg)->x1; + *((u8g_box_t *)arg) = new_box; + //printf("post x: %3d..%3d y: %3d..%3d\n", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); + } + break; + case U8G_DEV_MSG_GET_WIDTH: + *((u8g_uint_t *)arg) = u8g_GetHeightLL(u8g,rotation_chain); + break; + case U8G_DEV_MSG_GET_HEIGHT: + *((u8g_uint_t *)arg) = u8g_GetWidthLL(u8g, rotation_chain); + break; + case U8G_DEV_MSG_SET_PIXEL: + case U8G_DEV_MSG_SET_TPIXEL: + { + u8g_uint_t x, y; + y = ((u8g_dev_arg_pixel_t *)arg)->x; + x = u8g_GetWidthLL(u8g, rotation_chain); + x -= ((u8g_dev_arg_pixel_t *)arg)->y; + x--; + ((u8g_dev_arg_pixel_t *)arg)->x = x; + ((u8g_dev_arg_pixel_t *)arg)->y = y; + } + u8g_call_dev_fn(u8g, rotation_chain, msg, arg); + break; + case U8G_DEV_MSG_SET_8PIXEL: + case U8G_DEV_MSG_SET_4TPIXEL: + { + u8g_uint_t x, y; + //uint16_t x,y; + y = ((u8g_dev_arg_pixel_t *)arg)->x; + x = u8g_GetWidthLL(u8g, rotation_chain); + x -= ((u8g_dev_arg_pixel_t *)arg)->y; + x--; + ((u8g_dev_arg_pixel_t *)arg)->x = x; + ((u8g_dev_arg_pixel_t *)arg)->y = y; + ((u8g_dev_arg_pixel_t *)arg)->dir+=1; + ((u8g_dev_arg_pixel_t *)arg)->dir &= 3; + } + u8g_call_dev_fn(u8g, rotation_chain, msg, arg); + break; + } + return 1; +} + +uint8_t u8g_dev_rot180_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + u8g_dev_t *rotation_chain = (u8g_dev_t *)(dev->dev_mem); + switch(msg) + { + default: + /* + case U8G_DEV_MSG_INIT: + case U8G_DEV_MSG_STOP: + case U8G_DEV_MSG_PAGE_FIRST: + case U8G_DEV_MSG_PAGE_NEXT: + case U8G_DEV_MSG_SET_COLOR_ENTRY: + case U8G_DEV_MSG_SET_XY_CB: + */ + return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); +#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION + case U8G_DEV_MSG_IS_BBX_INTERSECTION: + { + u8g_dev_arg_bbx_t *bbx = (u8g_dev_arg_bbx_t *)arg; + u8g_uint_t x, y; + + /* transform the reference point */ + //y = u8g_GetHeightLL(u8g, rotation_chain); + y = u8g->height; + y -= bbx->y; + y--; + + //x = u8g_GetWidthLL(u8g, rotation_chain); + x = u8g->width; + x -= bbx->x; + x--; + + /* adjust point to be the uppler left corner again */ + y -= bbx->h; + y++; + + x -= bbx->w; + x++; + + /* store x,y */ + bbx->x = x; + bbx->y = y; + } + return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); +#endif /* U8G_DEV_MSG_IS_BBX_INTERSECTION */ + case U8G_DEV_MSG_GET_PAGE_BOX: + /* get page size from next device in the chain */ + u8g_call_dev_fn(u8g, rotation_chain, msg, arg); + //printf("pre x: %3d..%3d y: %3d..%3d ", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); + { + u8g_box_t new_box; + + new_box.x0 = u8g_GetWidthLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->x1 - 1; + new_box.x1 = u8g_GetWidthLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->x0 - 1; + new_box.y0 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y1 - 1; + new_box.y1 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y0 - 1; + *((u8g_box_t *)arg) = new_box; + //printf("post x: %3d..%3d y: %3d..%3d\n", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); + } + break; + case U8G_DEV_MSG_GET_WIDTH: + *((u8g_uint_t *)arg) = u8g_GetWidthLL(u8g,rotation_chain); + break; + case U8G_DEV_MSG_GET_HEIGHT: + *((u8g_uint_t *)arg) = u8g_GetHeightLL(u8g, rotation_chain); + break; + case U8G_DEV_MSG_SET_PIXEL: + case U8G_DEV_MSG_SET_TPIXEL: + { + u8g_uint_t x, y; + + y = u8g_GetHeightLL(u8g, rotation_chain); + y -= ((u8g_dev_arg_pixel_t *)arg)->y; + y--; + + x = u8g_GetWidthLL(u8g, rotation_chain); + x -= ((u8g_dev_arg_pixel_t *)arg)->x; + x--; + + ((u8g_dev_arg_pixel_t *)arg)->x = x; + ((u8g_dev_arg_pixel_t *)arg)->y = y; + } + u8g_call_dev_fn(u8g, rotation_chain, msg, arg); + break; + case U8G_DEV_MSG_SET_8PIXEL: + case U8G_DEV_MSG_SET_4TPIXEL: + { + u8g_uint_t x, y; + + y = u8g_GetHeightLL(u8g, rotation_chain); + y -= ((u8g_dev_arg_pixel_t *)arg)->y; + y--; + + x = u8g_GetWidthLL(u8g, rotation_chain); + x -= ((u8g_dev_arg_pixel_t *)arg)->x; + x--; + + ((u8g_dev_arg_pixel_t *)arg)->x = x; + ((u8g_dev_arg_pixel_t *)arg)->y = y; + ((u8g_dev_arg_pixel_t *)arg)->dir+=2; + ((u8g_dev_arg_pixel_t *)arg)->dir &= 3; + } + u8g_call_dev_fn(u8g, rotation_chain, msg, arg); + break; + } + return 1; +} + +uint8_t u8g_dev_rot270_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) +{ + u8g_dev_t *rotation_chain = (u8g_dev_t *)(dev->dev_mem); + switch(msg) + { + default: + /* + case U8G_DEV_MSG_INIT: + case U8G_DEV_MSG_STOP: + case U8G_DEV_MSG_PAGE_FIRST: + case U8G_DEV_MSG_PAGE_NEXT: + case U8G_DEV_MSG_SET_COLOR_ENTRY: + case U8G_DEV_MSG_SET_XY_CB: + */ + return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); +#ifdef U8G_DEV_MSG_IS_BBX_INTERSECTION + case U8G_DEV_MSG_IS_BBX_INTERSECTION: + { + u8g_dev_arg_bbx_t *bbx = (u8g_dev_arg_bbx_t *)arg; + u8g_uint_t x, y, tmp; + + /* transform the reference point */ + x = bbx->y; + + y = u8g->width; + /* y = u8g_GetHeightLL(u8g, rotation_chain); */ + y -= bbx->x; + y--; + + /* adjust point to be the uppler left corner again */ + y -= bbx->w; + y++; + + /* swap box dimensions */ + tmp = bbx->w; + bbx->w = bbx->h; + bbx->h = tmp; + + /* store x,y */ + bbx->x = x; + bbx->y = y; + } + return u8g_call_dev_fn(u8g, rotation_chain, msg, arg); +#endif /* U8G_DEV_MSG_IS_BBX_INTERSECTION */ + case U8G_DEV_MSG_GET_PAGE_BOX: + /* get page size from next device in the chain */ + u8g_call_dev_fn(u8g, rotation_chain, msg, arg); + //printf("pre x: %3d..%3d y: %3d..%3d ", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); + { + u8g_box_t new_box; + + new_box.x0 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y1 - 1; + new_box.x1 = u8g_GetHeightLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->y0 - 1; + new_box.y0 = u8g_GetWidthLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->x1 - 1; + new_box.y1 = u8g_GetWidthLL(u8g,rotation_chain) - ((u8g_box_t *)arg)->x0 - 1; + *((u8g_box_t *)arg) = new_box; + //printf("post x: %3d..%3d y: %3d..%3d\n", ((u8g_box_t *)arg)->x0, ((u8g_box_t *)arg)->x1, ((u8g_box_t *)arg)->y0, ((u8g_box_t *)arg)->y1); + } + break; + case U8G_DEV_MSG_GET_WIDTH: + *((u8g_uint_t *)arg) = u8g_GetHeightLL(u8g,rotation_chain); + break; + case U8G_DEV_MSG_GET_HEIGHT: + *((u8g_uint_t *)arg) = u8g_GetWidthLL(u8g, rotation_chain); + break; + case U8G_DEV_MSG_SET_PIXEL: + case U8G_DEV_MSG_SET_TPIXEL: + { + u8g_uint_t x, y; + x = ((u8g_dev_arg_pixel_t *)arg)->y; + + y = u8g_GetHeightLL(u8g, rotation_chain); + y -= ((u8g_dev_arg_pixel_t *)arg)->x; + y--; + + /* + x = u8g_GetWidthLL(u8g, rotation_chain); + x -= ((u8g_dev_arg_pixel_t *)arg)->y; + x--; + */ + ((u8g_dev_arg_pixel_t *)arg)->x = x; + ((u8g_dev_arg_pixel_t *)arg)->y = y; + } + u8g_call_dev_fn(u8g, rotation_chain, msg, arg); + break; + case U8G_DEV_MSG_SET_8PIXEL: + case U8G_DEV_MSG_SET_4TPIXEL: + { + u8g_uint_t x, y; + x = ((u8g_dev_arg_pixel_t *)arg)->y; + + y = u8g_GetHeightLL(u8g, rotation_chain); + y -= ((u8g_dev_arg_pixel_t *)arg)->x; + y--; + + /* + x = u8g_GetWidthLL(u8g, rotation_chain); + x -= ((u8g_dev_arg_pixel_t *)arg)->y; + x--; + */ + ((u8g_dev_arg_pixel_t *)arg)->x = x; + ((u8g_dev_arg_pixel_t *)arg)->y = y; + ((u8g_dev_arg_pixel_t *)arg)->dir+=3; + ((u8g_dev_arg_pixel_t *)arg)->dir &= 3; + } + u8g_call_dev_fn(u8g, rotation_chain, msg, arg); + break; + } + return 1; +} + + +#pragma GCC diagnostic push diff --git a/Repetier/ui.cpp b/Repetier/ui.cpp index 8892e1b..e2ab11c 100644 --- a/Repetier/ui.cpp +++ b/Repetier/ui.cpp @@ -52,8 +52,8 @@ uint16_t servoPosition = 1500; static TemperatureController *currHeaterForSetup; // pointer to extruder or heatbed temperature controller -#if UI_AUTORETURN_TO_MENU_AFTER!=0 -long ui_autoreturn_time=0; +#if UI_AUTORETURN_TO_MENU_AFTER != 0 +millis_t ui_autoreturn_time = 0; #endif #if FEATURE_BABYSTEPPING int zBabySteps = 0; @@ -466,8 +466,9 @@ void lcdWriteByte(uint8_t c,uint8_t rs) /* Fast repair function for displays loosing their settings. Do not call this if your display has no problems. */ -void repairLCD() { - // Now we pull both RS and R/W low to begin commands +void repairLCD() +{ + // Now we pull both RS and R/W low to begin commands WRITE(UI_DISPLAY_RS_PIN, LOW); WRITE(UI_DISPLAY_ENABLE_PIN, LOW); @@ -790,6 +791,9 @@ void initializeLCD() #endif #ifdef U8GLIB_ST7565_NHD_C2832_HW_SPI u8g_InitHWSPI(&u8g,&u8g_dev_st7565_nhd_c12864_hw_spi,UI_DISPLAY_RS_PIN,UI_DISPLAY_D5_PIN,U8G_PIN_NONE); +#endif +#ifdef U8GLIB_ST7565_NHD_C2832_SW_SPI +u8g_InitSPI(&u8g,&u8g_dev_st7565_nhd_c12864_sw_spi,UI_DISPLAY_D4_PIN,UI_DISPLAY_ENABLE_PIN,UI_DISPLAY_RS_PIN,UI_DISPLAY_D5_PIN,U8G_PIN_NONE); #endif u8g_Begin(&u8g); #ifdef UI_ROTATE_180 @@ -872,7 +876,7 @@ void UIDisplay::initialize() cwd[0] = '/'; cwd[1] = 0; folderLevel = 0; - UI_STATUS(UI_TEXT_PRINTER_READY); + UI_STATUS_F(Com::translatedF(UI_TEXT_PRINTER_READY_ID)); #if UI_DISPLAY_TYPE != NO_DISPLAY initializeLCD(); #if defined(USER_KEY1_PIN) && USER_KEY1_PIN > -1 @@ -915,13 +919,18 @@ void UIDisplay::initialize() u8g_FirstPage(&u8g); do { - u8g_DrawBitmapP(&u8g, 128 - LOGO_WIDTH, 0, ((LOGO_WIDTH + 8) / 8), LOGO_HEIGHT, logo); - for(uint8_t y = 0; y < UI_ROWS; y++) displayCache[y][0] = 0; + u8g_DrawBitmapP(&u8g, 128 - LOGO_WIDTH, 0, ((LOGO_WIDTH + 7) / 8), LOGO_HEIGHT, logo); + for(uint8_t y = 0; y < UI_ROWS; y++) displayCache[y][0] = 0; +#ifdef CUSTOM_LOGO + printRowP(4, PSTR("Repetier")); + printRowP(5, PSTR("Ver " REPETIER_VERSION)); +#else printRowP(0, PSTR("Repetier")); printRowP(1, PSTR("Ver " REPETIER_VERSION)); printRowP(3, PSTR("Machine:")); printRowP(4, PSTR(UI_PRINTER_NAME)); - printRowP(5, PSTR(UI_PRINTER_COMPANY)); + printRowP(5, PSTR(UI_PRINTER_COMPANY)); +#endif } while( u8g_NextPage(&u8g) ); //end picture loop #else // not DISPLAY_U8G @@ -945,7 +954,7 @@ void UIDisplay::initialize() #endif // gameduino2 HAL::delayMilliseconds(UI_START_SCREEN_DELAY); #endif -#if UI_DISPLAY_I2C_CHIPTYPE==0 && (BEEPER_TYPE==2 || defined(UI_HAS_I2C_KEYS)) +#if defined(UI_DISPLAY_I2C_CHIPTYPE) && UI_DISPLAY_I2C_CHIPTYPE==0 && (BEEPER_TYPE==2 || defined(UI_HAS_I2C_KEYS)) // Make sure the beeper is off HAL::i2cStartWait(UI_I2C_KEY_ADDRESS+I2C_WRITE); HAL::i2cWrite(255); // Disable beeper, enable read for other pins. @@ -953,7 +962,7 @@ void UIDisplay::initialize() #endif } #if UI_DISPLAY_TYPE == DISPLAY_4BIT || UI_DISPLAY_TYPE == DISPLAY_8BIT || UI_DISPLAY_TYPE == DISPLAY_I2C -void UIDisplay::createChar(uint8_t location,const uint8_t PROGMEM charmap[]) +void UIDisplay::createChar(uint8_t location,const uint8_t charmap[]) { location &= 0x7; // we only have 8 locations 0-7 lcdCommand(LCD_SETCGRAMADDR | (location << 3)); @@ -965,7 +974,7 @@ void UIDisplay::createChar(uint8_t location,const uint8_t PROGMEM charmap[]) #endif void UIDisplay::waitForKey() { - int nextAction = 0; + uint16_t nextAction = 0; lastButtonAction = 0; while(lastButtonAction == nextAction) @@ -1017,7 +1026,7 @@ void UIDisplay::addInt(int value,uint8_t digits,char fillChar) str++; } } -void UIDisplay::addLong(long value,char digits) +void UIDisplay::addLong(long value,int8_t digits) { uint8_t dig = 0,neg = 0; byte addspaces = digits > 0; @@ -1057,15 +1066,8 @@ void UIDisplay::addLong(long value,char digits) const float roundingTable[] PROGMEM = {0.5, 0.05, 0.005, 0.0005}; -UI_STRING(ui_text_on,UI_TEXT_ON); -UI_STRING(ui_text_off,UI_TEXT_OFF); -UI_STRING(ui_text_na,UI_TEXT_NA); -UI_STRING(ui_yes,UI_TEXT_YES); -UI_STRING(ui_no,UI_TEXT_NO); -UI_STRING(ui_print_pos,UI_TEXT_PRINT_POS); UI_STRING(ui_selected,UI_TEXT_SEL); UI_STRING(ui_unselected,UI_TEXT_NOSEL); -UI_STRING(ui_action,UI_TEXT_STRING_ACTION); void UIDisplay::addFloat(float number, char fixdigits, uint8_t digits) { @@ -1113,7 +1115,7 @@ void UIDisplay::addStringP(FSTRINGPARAM(text)) void UIDisplay::addStringOnOff(uint8_t on) { - addStringP(on ? ui_text_on : ui_text_off); + addStringP(on ? Com::translatedF(UI_TEXT_ON_ID) : Com::translatedF(UI_TEXT_OFF_ID)); } void UIDisplay::addChar(const char c) @@ -1245,36 +1247,57 @@ void UIDisplay::parse(const char *txt,bool ram) if(c2 >= 'x' && c2 <= 'z') addFloat(Printer::maxAccelerationMMPerSquareSecond[c2 - 'x'], 5, 0); else if(c2 >= 'X' && c2 <= 'Z') addFloat(Printer::maxTravelAccelerationMMPerSquareSecond[c2-'X'], 5, 0); else if(c2 == 'j') addFloat(Printer::maxJerk, 3, 1); -#if DRIVE_SYSTEM!=DELTA +#if DRIVE_SYSTEM != DELTA else if(c2 == 'J') addFloat(Printer::maxZJerk, 3, 1); #endif break; - + case 'B': + if(c2 == 'C') //Custom coating + { + addFloat(Printer::zBedOffset, 3, 2); + break; + } + break; case 'd': if(c2 == 'o') addStringOnOff(Printer::debugEcho()); else if(c2 == 'i') addStringOnOff(Printer::debugInfo()); else if(c2 == 'e') addStringOnOff(Printer::debugErrors()); else if(c2 == 'd') addStringOnOff(Printer::debugDryrun()); break; - + case 'D': +#if FEATURE_DITTO_PRINTING + if(c2>='0' && c2<='9') + { + addStringP(Extruder::dittoMode==c2-'0'?ui_selected:ui_unselected); + } +#endif + break; case 'e': // Extruder temperature { if(c2 == 'I') { //give integer display - char c2=(ram ? *(txt++) : pgm_read_byte(txt++)); - ivalue=0; + //char c2 = (ram ? *(txt++) : pgm_read_byte(txt++)); + txt++; // just skip c sign + ivalue = 0; } else ivalue = UI_TEMP_PRECISION; if(c2 == 'r') // Extruder relative mode { - addStringP(Printer::relativeExtruderCoordinateMode ? ui_yes : ui_no); + addStringP(Printer::relativeExtruderCoordinateMode ? Com::translatedF(UI_TEXT_YES_ID) : Com::translatedF(UI_TEXT_NO_ID)); break; - } + } +#if FEATURE_DITTO_PRINTING + if(c2 == 'd') { // ditto copy mode + addInt(Extruder::dittoMode,1,' '); + break; + } +#endif uint8_t eid = NUM_EXTRUDER; // default = BED if c2 not specified extruder number if(c2 == 'c') eid = Extruder::current->id; else if(c2 >= '0' && c2 <= '9') eid = c2 - '0'; +#if NUM_TEMPERATURE_LOOPS > 0 if(Printer::isAnyTempsensorDefect()) { if(eid == 0 && ++beepdelay > 30) beepdelay = 0; // beep every 30 seconds @@ -1298,6 +1321,7 @@ void UIDisplay::parse(const char *txt,bool ram) addStringP(PSTR(" jam ")); break; } +#endif #endif if(c2 == 'c') fvalue = Extruder::current->tempControl.currentTemperatureC; else if(c2 >= '0' && c2 <= '9') fvalue=extruder[c2 - '0'].tempControl.currentTemperatureC; @@ -1349,12 +1373,12 @@ void UIDisplay::parse(const char *txt,bool ram) #if SDSUPPORT if(sd.sdactive && sd.sdmode) { - addStringP(PSTR( UI_TEXT_PRINT_POS)); + addStringP(Com::translatedF(UI_TEXT_PRINT_POS_ID)); float percent; if(sd.filesize < 2000000) percent = sd.sdpos * 100.0 / sd.filesize; else percent = (sd.sdpos >> 8) * 100.0 / (sd.filesize >> 8); addFloat(percent, 3, 1); - if(col -1) && MIN_HARDWARE_ENDSTOP_X addStringOnOff(Endstops::xMin()); #else - addStringP(ui_text_na); + addStringP(Com::translatedF(UI_TEXT_NA_ID)); #endif } if(c2 == 'X') #if (X_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_X addStringOnOff(Endstops::xMax()); #else - addStringP(ui_text_na); + addStringP(Com::translatedF(UI_TEXT_NA_ID)); #endif if(c2 == 'y') #if (Y_MIN_PIN > -1)&& MIN_HARDWARE_ENDSTOP_Y addStringOnOff(Endstops::yMin()); #else - addStringP(ui_text_na); + addStringP(Com::translatedF(UI_TEXT_NA_ID)); #endif if(c2 == 'Y') #if (Y_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_Y addStringOnOff(Endstops::yMax()); #else - addStringP(ui_text_na); + addStringP(Com::translatedF(UI_TEXT_NA_ID)); #endif if(c2 == 'z') #if (Z_MIN_PIN > -1) && MIN_HARDWARE_ENDSTOP_Z addStringOnOff(Endstops::zMin()); #else - addStringP(ui_text_na); + addStringP(Com::translatedF(UI_TEXT_NA_ID)); #endif if(c2=='Z') #if (Z_MAX_PIN > -1) && MAX_HARDWARE_ENDSTOP_Z addStringOnOff(Endstops::zMax()); #else - addStringP(ui_text_na); + addStringP(Com::translatedF(UI_TEXT_NA_ID)); #endif if(c2=='P') #if (Z_PROBE_PIN > -1) addStringOnOff(Endstops::zProbe()); #else - addStringP(ui_text_na); + addStringP(Com::translatedF(UI_TEXT_NA_ID)); #endif break; case 'S': if(c2 >= 'x' && c2 <= 'z') addFloat(Printer::axisStepsPerMM[c2 - 'x'], 3, 1); if(c2 == 'e') addFloat(Extruder::current->stepsPerMM, 3, 1); break; - + case 'T': // Print offsets + if(c2=='2') + addFloat(-Printer::coordinateOffset[Z_AXIS],2,2); + else + addFloat(-Printer::coordinateOffset[c2-'0'],4,0); + break; case 'U': if(c2 == 't') // Printing time { #if EEPROM_MODE bool alloff = true; +#if NUM_TEMPERATURE_LOOPS > 0 for(uint8_t i = 0; i < NUM_EXTRUDER; i++) if(tempController[i]->targetTemperatureC > 15) alloff = false; - +#endif long seconds = (alloff ? 0 : (HAL::timeInMilliseconds() - Printer::msecondsPrinting) / 1000) + HAL::eprGetInt32(EPR_PRINTING_TIME); long tmp = seconds / 86400; seconds -= tmp * 86400; addInt(tmp, 5); - addStringP(PSTR(UI_TEXT_PRINTTIME_DAYS)); + addStringP(Com::translatedF(UI_TEXT_PRINTTIME_DAYS_ID)); tmp = seconds / 3600; addInt(tmp,2); - addStringP(PSTR(UI_TEXT_PRINTTIME_HOURS)); + addStringP(Com::translatedF(UI_TEXT_PRINTTIME_HOURS_ID)); seconds -= tmp * 3600; tmp = seconds / 60; addInt(tmp,2,'0'); - addStringP(PSTR(UI_TEXT_PRINTTIME_MINUTES)); + addStringP(Com::translatedF(UI_TEXT_PRINTTIME_MINUTES_ID)); #endif } else if(c2 == 'f') // Filament usage @@ -1572,13 +1602,13 @@ void UIDisplay::parse(const char *txt,bool ram) { uint8_t hm = currHeaterForSetup->heatManager; if(hm == HTR_PID) - addStringP(PSTR(UI_TEXT_STRING_HM_PID)); + addStringP(Com::translatedF(UI_TEXT_STRING_HM_PID_ID)); else if(hm == HTR_DEADTIME) - addStringP(PSTR(UI_TEXT_STRING_HM_DEADTIME)); + addStringP(Com::translatedF(UI_TEXT_STRING_HM_DEADTIME_ID)); else if(hm == HTR_SLOWBANG) - addStringP(PSTR(UI_TEXT_STRING_HM_SLOWBANG)); + addStringP(Com::translatedF(UI_TEXT_STRING_HM_SLOWBANG_ID)); else - addStringP(PSTR(UI_TEXT_STRING_HM_BANGBANG)); + addStringP(Com::translatedF(UI_TEXT_STRING_HM_BANGBANG_ID)); } #if USE_ADVANCE #if ENABLE_QUADRATIC_ADVANCE @@ -1615,15 +1645,32 @@ void UIDisplay::parse(const char *txt,bool ram) #endif break; case 'y': -#if DRIVE_SYSTEM==DELTA - if(c2>='0' && c2<='3') fvalue = (float)Printer::currentDeltaPositionSteps[c2-'0']*Printer::invAxisStepsPerMM[c2-'0']; +#if DRIVE_SYSTEM == DELTA + if(c2 >= '0' && c2 <= '3') fvalue = (float)Printer::currentDeltaPositionSteps[c2 - '0']*Printer::invAxisStepsPerMM[c2-'0']; addFloat(fvalue,3,2); #endif + break; + case 'z': +#if EEPROM_MODE != 0 && FEATURE_Z_PROBE + if(c2 == 'h') { // write z probe height + addFloat(EEPROM::zProbeHeight(),3,2); + break; + } +#endif + if(c2=='2') + addFloat(-Printer::coordinateOffset[Z_AXIS],2,2); + else + addFloat(-Printer::coordinateOffset[c2-'0'],4,0); break; } } uid.printCols[col] = 0; } +void UIDisplay::showLanguageSelectionWizard() { +#if EEPROM_MODE != 0 + pushMenu(&ui_menu_languages_wiz,true); +#endif +} void UIDisplay::setStatusP(PGM_P txt,bool error) { if(!error && Printer::isUIErrorMessage()) return; @@ -1655,7 +1702,6 @@ void UIDisplay::updateSDFileCount() { #if SDSUPPORT dir_t* p = NULL; - byte offset = menuTop[menuLevel]; SdBaseFile *root = sd.fat.vwd(); root->rewind(); @@ -1676,11 +1722,11 @@ void UIDisplay::updateSDFileCount() void getSDFilenameAt(uint16_t filePos,char *filename) { #if SDSUPPORT - dir_t* p; + dir_t* p = NULL; SdBaseFile *root = sd.fat.vwd(); root->rewind(); - while ((p = root->getLongFilename(p, tempLongFilename, 0, NULL))) + while ((p = root->getLongFilename(p, tempLongFilename, 0, NULL)) != NULL) { HAL::pingWatchdog(); if (!DIR_IS_FILE(p) && !DIR_IS_SUBDIR(p)) continue; @@ -1727,7 +1773,7 @@ void UIDisplay::goDir(char *name) updateSDFileCount(); #endif } - +/** write file names at current position to lcd */ void sdrefresh(uint16_t &r,char cache[UI_ROWS][MAX_COLS+1]) { #if SDSUPPORT @@ -1802,26 +1848,29 @@ void UIDisplay::refreshPage() { UIMenuEntry *ent = (UIMenuEntry *)pgm_read_word(&(entries[r])); col = 0; - parse((char*)pgm_read_word(&(ent->text)),false); + char *text = (char*)pgm_read_word(&(ent->text)); + if(text == NULL) + text = (char*)Com::translatedF(pgm_read_word(&(ent->translation))); + parse(text,false); strcpy(cache[r],uid.printCols); } } else { UIMenu *men = (UIMenu*)menu[menuLevel]; - uint16_t nr = pgm_read_word_near((void*)&(men->numEntries)); + uint16_t nr = pgm_read_word_near(&(men->numEntries)); mtype = pgm_read_byte((void*)&(men->menuType)); uint16_t offset = menuTop[menuLevel]; UIMenuEntry **entries = (UIMenuEntry**)pgm_read_word(&(men->entries)); for(r = 0; r + offset < nr && r < UI_ROWS; ) { - UIMenuEntry *ent =(UIMenuEntry *)pgm_read_word(&(entries[r+offset])); + UIMenuEntry *ent =(UIMenuEntry *)pgm_read_word(&(entries[r + offset])); if(!ent->showEntry()) { offset++; continue; } - uint8_t entType = pgm_read_byte(&(ent->menuType)); + uint8_t entType = pgm_read_byte(&(ent->entryType)) & 127; uint16_t entAction = pgm_read_word(&(ent->action)); col = 0; if(entType >= 2 && entType <= 4) @@ -1833,13 +1882,16 @@ void UIDisplay::refreshPage() else uid.printCols[col++]=' '; } - parse((char*)pgm_read_word(&(ent->text)),false); + char *text = (char*)pgm_read_word(&(ent->text)); + if(text == NULL) + text = (char*)Com::translatedF(pgm_read_word(&(ent->translation))); + parse(text,false); if(entType == 2) // Draw submenu marker at the right side { while(colUI_COLS) { - uid.printCols[RMath::min(UI_COLS-1,col)] = CHAR_RIGHT; + uid.printCols[RMath::min(UI_COLS - 1,col)] = CHAR_RIGHT; } else uid.printCols[col] = CHAR_RIGHT; // Arrow right @@ -1944,28 +1996,34 @@ void UIDisplay::refreshPage() u8g_DrawBox(&u8g,x+1,y+p, width-2, (height-p));} #if UI_DISPLAY_TYPE == DISPLAY_U8G #if SDSUPPORT - unsigned long sdPercent; + unsigned long sdPercent = 0; #endif //fan - int fanPercent; +#if FAN_PIN>-1 && FEATURE_FAN_CONTROL + int fanPercent = 0; char fanString[2]; +#endif if(menuLevel == 0 && menuPos[0] == 0 ) // Main menu with special graphics { -//ext1 and ext2 animation symbols - if(pwm_pos[extruder[0].tempControl.pwmIndex] > 0) +//ext1 and ext2 animation symbols +#if NUM_EXTRUDER < 3 + if(extruder[0].tempControl.targetTemperatureC > 30) +#else + if(Extruder::current->tempControl.targetTemperatureC > 30) +#endif cache[0][0] = Printer::isAnimation()?'\x08':'\x09'; else cache[0][0] = '\x0a'; //off -#if NUM_EXTRUDER>1 - if(pwm_pos[extruder[1].tempControl.pwmIndex] > 0) +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + if(extruder[1].tempControl.targetTemperatureC > 30) cache[1][0] = Printer::isAnimation()?'\x08':'\x09'; else - cache[1][0] = '\x0a'; //off + cache[1][0] = '\x0a'; //off #endif #if HAVE_HEATED_BED //heatbed animated icons - uint8_t lin = 2 - ((NUM_EXTRUDER < 2) ? 1 : 0); - if(pwm_pos[heatedBedController.pwmIndex] > 0) + uint8_t lin = 2 - ((NUM_EXTRUDER != 2) ? 1 : 0); + if(heatedBedController.targetTemperatureC > 30) cache[lin][0] = Printer::isAnimation() ? '\x0c' : '\x0d'; else cache[lin][0] = '\x0b'; @@ -2032,7 +2090,7 @@ void UIDisplay::refreshPage() //SD Card if(sd.sdactive && u8g_IsBBXIntersection(&u8g, 66, 52 - UI_FONT_SMALL_HEIGHT, 1, UI_FONT_SMALL_HEIGHT)) { - printU8GRow(66,52,"SD"); + printU8GRow(66,52,const_cast("SD")); drawHProgressBar(79,46, 46, 6, sdPercent); } #endif @@ -2174,7 +2232,11 @@ void UIDisplay::pushMenu(const UIMenu *men, bool refresh) // With or without SDCARD, being here means the menu is not a files list // Reset menu to top menuTop[menuLevel] = 0; - menuPos[menuLevel] = UI_MENU_BACKCNT; // if top entry is back, default to next useful item + + UIMenuEntry **entries = (UIMenuEntry**)pgm_read_word(&(men->entries)); + UIMenuEntry *ent =(UIMenuEntry *)pgm_read_word(&(entries[0])); + uint16_t entAction = pgm_read_word(&(ent->action)); + menuPos[menuLevel] = entAction == UI_ACTION_BACK ? 1 : 0; // if top entry is back, default to next useful item } if(refresh) refreshPage(); @@ -2204,13 +2266,13 @@ int UIDisplay::okAction(bool allowMoves) menu[1] = &ui_menu_main; return 0; } - UIMenu *men = (UIMenu*)menu[menuLevel]; + const UIMenu *men = (const UIMenu*)menu[menuLevel]; //uint8_t nr = pgm_read_word_near(&(menu->numEntries)); uint8_t mtype = pgm_read_byte(&(men->menuType)); UIMenuEntry **entries; UIMenuEntry *ent; unsigned char entType; - int action; + unsigned int action; #if SDSUPPORT if(mtype == UI_MENU_TYPE_FILE_SELECTOR) { @@ -2283,7 +2345,7 @@ int UIDisplay::okAction(bool allowMoves) #endif entries = (UIMenuEntry**)pgm_read_word(&(men->entries)); ent =(UIMenuEntry *)pgm_read_word(&(entries[menuPos[menuLevel]])); - entType = pgm_read_byte(&(ent->menuType));// 0 = Info, 1 = Headline, 2 = submenu ref, 3 = direct action command, 4 = modify action + entType = pgm_read_byte(&(ent->entryType));// 0 = Info, 1 = Headline, 2 = submenu ref, 3 = direct action command, 4 = modify action action = pgm_read_word(&(ent->action)); if(mtype == UI_MENU_TYPE_MODIFICATION_MENU) // action menu { @@ -2380,14 +2442,14 @@ void UIDisplay::adjustMenuPos() if(menuLevel == 0) return; UIMenu *men = (UIMenu*)menu[menuLevel]; UIMenuEntry **entries = (UIMenuEntry**)pgm_read_word(&(men->entries)); - uint8_t mtype = HAL::readFlashByte((PGM_P)&(men->menuType)); - int numEntries = pgm_read_word(&(men->numEntries)); + uint8_t mtype = HAL::readFlashByte((PGM_P)&(men->menuType)) & 127; + uint16_t numEntries = pgm_read_word(&(men->numEntries)); if(mtype != 2) return; UIMenuEntry *entry; while(menuPos[menuLevel] > 0) // Go up until we reach visible position { entry = (UIMenuEntry *)pgm_read_word(&(entries[menuPos[menuLevel]])); - if(pgm_read_byte((void*)&(entry->menuType)) == 1) // skip headlines + if(pgm_read_byte((void*)&(entry->entryType)) == 1) // skip headlines menuPos[menuLevel]--; else if(entry->showEntry()) break; @@ -2399,7 +2461,7 @@ void UIDisplay::adjustMenuPos() while(menuPos[menuLevel] < numEntries - 1) // Go down until we reach visible position { entry = (UIMenuEntry *)pgm_read_word(&(entries[menuPos[menuLevel]])); - if(pgm_read_byte((void*)&(entry->menuType)) == 1) // skip headlines + if(pgm_read_byte((void*)&(entry->entryType)) == 1) // skip headlines menuPos[menuLevel]++; else if(entry->showEntry()) break; @@ -2433,7 +2495,12 @@ void UIDisplay::adjustMenuPos() bool UIDisplay::isWizardActive() { UIMenu *men = (UIMenu*)menu[menuLevel]; - return HAL::readFlashByte((PGM_P)&(men->menuType)) == 5; + return (HAL::readFlashByte((PGM_P)&(men->menuType)) & 127) == 5; +} +bool UIDisplay::isSticky() { + UIMenu *men = (UIMenu*)menu[menuLevel]; + uint8_t mt = HAL::readFlashByte((PGM_P)&(men->menuType)); + return ((mt & 128) == 128) || mt == 5; } bool UIDisplay::nextPreviousAction(int16_t next, bool allowMoves) @@ -2456,7 +2523,7 @@ bool UIDisplay::nextPreviousAction(int16_t next, bool allowMoves) float f = (float)(SPEED_MIN_MILLIS - dt) / (float)(SPEED_MIN_MILLIS - SPEED_MAX_MILLIS); lastNextAccumul = 1.0f + (float)SPEED_MAGNIFICATION * f * f; #if UI_DYNAMIC_ENCODER_SPEED - uint16_t dynSp = lastNextAccumul / 16; + int16_t dynSp = lastNextAccumul / 16; if(dynSp < 1) dynSp = 1; if(dynSp > 30) dynSp = 30; next *= dynSp; @@ -2480,13 +2547,13 @@ bool UIDisplay::nextPreviousAction(int16_t next, bool allowMoves) } UIMenu *men = (UIMenu*)menu[menuLevel]; uint8_t nr = pgm_read_word_near(&(men->numEntries)); - uint8_t mtype = HAL::readFlashByte((PGM_P)&(men->menuType)); + uint8_t mtype = HAL::readFlashByte((PGM_P)&(men->menuType)) & 127; UIMenuEntry **entries = (UIMenuEntry**)pgm_read_word(&(men->entries)); UIMenuEntry *ent =(UIMenuEntry *)pgm_read_word(&(entries[menuPos[menuLevel]])); UIMenuEntry *testEnt; // 0 = Info, 1 = Headline, 2 = submenu ref, 3 = direct action command - uint8_t entType = HAL::readFlashByte((PGM_P)&(ent->menuType)); - int action = pgm_read_word(&(ent->action)); + //uint8_t entType = HAL::readFlashByte((PGM_P)&(ent->entryType)); + unsigned int action = pgm_read_word(&(ent->action)); if(mtype == UI_MENU_TYPE_SUBMENU && activeAction == 0) // browse through menu items { if((UI_INVERT_MENU_DIRECTION && next < 0) || (!UI_INVERT_MENU_DIRECTION && next > 0)) @@ -2538,12 +2605,12 @@ bool UIDisplay::nextPreviousAction(int16_t next, bool allowMoves) #endif if(mtype == UI_MENU_TYPE_MODIFICATION_MENU || mtype == UI_MENU_TYPE_WIZARD) action = pgm_read_word(&(men->id)); else action = activeAction; - int8_t increment = next; + int16_t increment = next; EVENT_START_NEXTPREVIOUS(action,increment); switch(action) { case UI_ACTION_FANSPEED: - Commands::setFanSpeed(Printer::getFanSpeed() + increment * 3,false); + Commands::setFanSpeed(Printer::getFanSpeed() + increment * 3, true); break; case UI_ACTION_XPOSITION: if(!allowMoves) return false; @@ -2554,10 +2621,10 @@ bool UIDisplay::nextPreviousAction(int16_t next, bool allowMoves) d *= Printer::maxFeedrate[X_AXIS]*dtReal / (1000 * fabs(d)); long steps = (long)(d * Printer::axisStepsPerMM[X_AXIS]); steps = ( increment < 0 ? RMath::min(steps,(long)increment) : RMath::max(steps,(long)increment)); - PrintLine::moveRelativeDistanceInStepsReal(steps,0,0,0,Printer::maxFeedrate[X_AXIS],false); + PrintLine::moveRelativeDistanceInStepsReal(steps,0,0,0,Printer::maxFeedrate[X_AXIS],false,false); } #else - PrintLine::moveRelativeDistanceInStepsReal(increment,0,0,0,Printer::homingFeedrate[X_AXIS],false); + PrintLine::moveRelativeDistanceInStepsReal(increment,0,0,0,Printer::homingFeedrate[X_AXIS],false,false); #endif Commands::printCurrentPosition(PSTR("UI_ACTION_XPOSITION ")); break; @@ -2570,17 +2637,17 @@ bool UIDisplay::nextPreviousAction(int16_t next, bool allowMoves) d *= Printer::maxFeedrate[Y_AXIS] * dtReal / (1000 * fabs(d)); long steps = (long)(d * Printer::axisStepsPerMM[Y_AXIS]); steps = ( increment < 0 ? RMath::min(steps,(long)increment) : RMath::max(steps,(long)increment)); - PrintLine::moveRelativeDistanceInStepsReal(0,steps,0,0,Printer::maxFeedrate[Y_AXIS],false); + PrintLine::moveRelativeDistanceInStepsReal(0,steps,0,0,Printer::maxFeedrate[Y_AXIS],false,false); } #else - PrintLine::moveRelativeDistanceInStepsReal(0,increment,0,0,Printer::homingFeedrate[Y_AXIS],false); + PrintLine::moveRelativeDistanceInStepsReal(0,increment,0,0,Printer::homingFeedrate[Y_AXIS],false,false); #endif Commands::printCurrentPosition(PSTR("UI_ACTION_YPOSITION ")); break; case UI_ACTION_ZPOSITION_NOTEST: if(!allowMoves) return false; Printer::setNoDestinationCheck(true); - goto ZPOS1; + goto ZPOS1; case UI_ACTION_ZPOSITION: if(!allowMoves) return false; ZPOS1: @@ -2591,38 +2658,38 @@ ZPOS1: d *= Printer::maxFeedrate[Z_AXIS] * dtReal / (1000 * fabs(d)); long steps = (long)(d * Printer::axisStepsPerMM[Z_AXIS]); steps = ( increment<0 ? RMath::min(steps,(long)increment) : RMath::max(steps,(long)increment)); - PrintLine::moveRelativeDistanceInStepsReal(0,0,steps,0,Printer::maxFeedrate[Z_AXIS],false); + PrintLine::moveRelativeDistanceInStepsReal(0,0,steps,0,Printer::maxFeedrate[Z_AXIS],false,false); } #else - PrintLine::moveRelativeDistanceInStepsReal(0, 0, ((long)increment * Printer::axisStepsPerMM[Z_AXIS]) / 100, 0, Printer::homingFeedrate[Z_AXIS],false); + PrintLine::moveRelativeDistanceInStepsReal(0, 0, ((long)increment * Printer::axisStepsPerMM[Z_AXIS]) / 100, 0, Printer::homingFeedrate[Z_AXIS],false,false); #endif Printer::setNoDestinationCheck(false); Commands::printCurrentPosition(PSTR("UI_ACTION_ZPOSITION ")); break; case UI_ACTION_XPOSITION_FAST: if(!allowMoves) return false; - PrintLine::moveRelativeDistanceInStepsReal(Printer::axisStepsPerMM[X_AXIS] * increment,0,0,0,Printer::homingFeedrate[X_AXIS],true); + PrintLine::moveRelativeDistanceInStepsReal(Printer::axisStepsPerMM[X_AXIS] * increment,0,0,0,Printer::homingFeedrate[X_AXIS],true,false); Commands::printCurrentPosition(PSTR("UI_ACTION_XPOSITION_FAST ")); break; case UI_ACTION_YPOSITION_FAST: if(!allowMoves) return false; - PrintLine::moveRelativeDistanceInStepsReal(0,Printer::axisStepsPerMM[Y_AXIS] * increment,0,0,Printer::homingFeedrate[Y_AXIS],true); + PrintLine::moveRelativeDistanceInStepsReal(0,Printer::axisStepsPerMM[Y_AXIS] * increment,0,0,Printer::homingFeedrate[Y_AXIS],true,false); Commands::printCurrentPosition(PSTR("UI_ACTION_YPOSITION_FAST ")); break; case UI_ACTION_ZPOSITION_FAST_NOTEST: if(!allowMoves) return false; Printer::setNoDestinationCheck(true); - goto ZPOS2; + goto ZPOS2; case UI_ACTION_ZPOSITION_FAST: if(!allowMoves) return false; ZPOS2: - PrintLine::moveRelativeDistanceInStepsReal(0,0,Printer::axisStepsPerMM[Z_AXIS] * increment,0,Printer::homingFeedrate[Z_AXIS],true); + PrintLine::moveRelativeDistanceInStepsReal(0,0,Printer::axisStepsPerMM[Z_AXIS] * increment,0,Printer::homingFeedrate[Z_AXIS],true,false); Printer::setNoDestinationCheck(false); Commands::printCurrentPosition(PSTR("UI_ACTION_ZPOSITION_FAST ")); break; case UI_ACTION_EPOSITION: if(!allowMoves) return false; - PrintLine::moveRelativeDistanceInSteps(0,0,0,Printer::axisStepsPerMM[E_AXIS]*increment / Printer::extrusionFactor,UI_SET_EXTRUDER_FEEDRATE,true,false); + PrintLine::moveRelativeDistanceInSteps(0,0,0,Printer::axisStepsPerMM[E_AXIS]*increment / Printer::extrusionFactor,UI_SET_EXTRUDER_FEEDRATE,true,false,false); Commands::printCurrentPosition(PSTR("UI_ACTION_EPOSITION ")); break; #if FEATURE_RETRACTION @@ -2636,8 +2703,12 @@ ZPOS2: #if FEATURE_BABYSTEPPING { previousMillisCmd = HAL::timeInMilliseconds(); - if((abs((int)Printer::zBabystepsMissing + (increment * BABYSTEP_MULTIPLICATOR))) < 127) +#if UI_DYNAMIC_ENCODER_SPEED + increment /= dynSp; // we need fixed speeds or we get in trouble here! +#endif + if((abs((int)Printer::zBabystepsMissing + (increment * BABYSTEP_MULTIPLICATOR))) < 20000) { + InterruptProtectedBlock noint; Printer::zBabystepsMissing += increment * BABYSTEP_MULTIPLICATOR; zBabySteps += increment * BABYSTEP_MULTIPLICATOR; } @@ -2658,13 +2729,22 @@ ZPOS2: #endif break; -#if NUM_EXTRUDER>2 - case UI_ACTION_EXTRUDER2_TEMP: -#endif -#if NUM_EXTRUDER>1 + case UI_ACTION_EXTRUDER0_TEMP: +#if NUM_EXTRUDER > 1 case UI_ACTION_EXTRUDER1_TEMP: #endif - case UI_ACTION_EXTRUDER0_TEMP: +#if NUM_EXTRUDER > 2 + case UI_ACTION_EXTRUDER2_TEMP: +#endif +#if NUM_EXTRUDER > 3 + case UI_ACTION_EXTRUDER3_TEMP: +#endif +#if NUM_EXTRUDER > 4 + case UI_ACTION_EXTRUDER4_TEMP: +#endif +#if NUM_EXTRUDER > 5 + case UI_ACTION_EXTRUDER5_TEMP: +#endif { int tmp = (int)extruder[action - UI_ACTION_EXTRUDER0_TEMP].tempControl.targetTemperatureC; if(tmp < UI_SET_MIN_EXTRUDER_TEMP) tmp = 0; @@ -2688,6 +2768,11 @@ ZPOS2: Commands::changeFlowrateMultiply(Printer::extrudeMultiply); } break; +#if UI_BED_COATING + case UI_ACTION_COATING_CUSTOM: + INCREMENT_MIN_MAX(Printer::zBedOffset,0.01,-1.0,199.0); + break; +#endif case UI_ACTION_STEPPER_INACTIVE: { uint8_t inactT = stepperInactiveTime / 60000; @@ -2705,7 +2790,7 @@ ZPOS2: case UI_ACTION_PRINT_ACCEL_X: case UI_ACTION_PRINT_ACCEL_Y: case UI_ACTION_PRINT_ACCEL_Z: -#if DRIVE_SYSTEM!=DELTA +#if DRIVE_SYSTEM != DELTA INCREMENT_MIN_MAX(Printer::maxAccelerationMMPerSquareSecond[action - UI_ACTION_PRINT_ACCEL_X],((action == UI_ACTION_PRINT_ACCEL_Z) ? 1 : 100),0,10000); #else INCREMENT_MIN_MAX(Printer::maxAccelerationMMPerSquareSecond[action - UI_ACTION_PRINT_ACCEL_X],100,0,10000); @@ -2748,14 +2833,31 @@ ZPOS2: INCREMENT_MIN_MAX(Printer::axisStepsPerMM[action - UI_ACTION_STEPS_X], 0.1, 0, 999); Printer::updateDerivedParameter(); break; + + case UI_ACTION_XOFF: + case UI_ACTION_YOFF: + { + float tmp = -Printer::coordinateOffset[action - UI_ACTION_XOFF]; + INCREMENT_MIN_MAX(tmp, 1, -999, 999); + Printer::coordinateOffset[action - UI_ACTION_XOFF] = -tmp; + } + break; + case UI_ACTION_ZOFF: + { + float tmp = -Printer::coordinateOffset[Z_AXIS]; + INCREMENT_MIN_MAX(tmp, 0.01, -9.99, 9.99); + Printer::coordinateOffset[Z_AXIS] = -tmp; + } + break; + case UI_ACTION_BAUDRATE: #if EEPROM_MODE != 0 { - char p = 0; + int16_t p = 0; int32_t rate; do { - rate = pgm_read_dword(&(baudrates[p])); + rate = pgm_read_dword(&(baudrates[(uint8_t)p])); if(rate == baudrate) break; p++; } @@ -2763,7 +2865,8 @@ ZPOS2: if(rate == 0) p -= 2; p += increment; if(p < 0) p = 0; - if(p > sizeof(baudrates)/4 - 2) p = sizeof(baudrates)/4 - 2; + if(p > static_cast(sizeof(baudrates)/4) - 2) + p = sizeof(baudrates)/4 - 2; baudrate = pgm_read_dword(&(baudrates[p])); } #endif @@ -2854,23 +2957,52 @@ ZPOS2: return true; } -void UIDisplay::finishAction(int action) +#if UI_BED_COATING +void UIDisplay::menuAdjustHeight(const UIMenu *men,float offset) { +#if EEPROM_MODE != 0 + //If there is something to change + if (EEPROM::zProbeZOffset() != offset) + { + HAL::eprSetFloat(EPR_Z_PROBE_Z_OFFSET, offset); + EEPROM::storeDataIntoEEPROM(false); + } +#endif + Printer::zBedOffset = offset; + //Display message + pushMenu(men, false); + BEEP_SHORT; + Printer::homeAxis(true, true, true); + Commands::printCurrentPosition(PSTR("UI_ACTION_HOMEALL ")); + menuLevel = 0; + activeAction = 0; + UI_STATUS_UPD_F(Com::translatedF(UI_TEXT_PRINTER_READY_ID)); +} +#endif + +void UIDisplay::finishAction(unsigned int action) +{ +#if UI_BED_COATING + if (action == UI_ACTION_COATING_CUSTOM) + { + menuAdjustHeight(&ui_menu_coating_custom,Printer::zBedOffset); + } +#endif } // Actions are events from user input. Depending on the current state, each // action can behave differently. Other actions do always the same like home, disable extruder etc. -int UIDisplay::executeAction(int action, bool allowMoves) +int UIDisplay::executeAction(unsigned int action, bool allowMoves) { int ret = 0; #if UI_HAS_KEYS == 1 if(action & UI_ACTION_TOPMENU) // Go to start menu { - action -= UI_ACTION_TOPMENU; menuLevel = 0; } + action &= 8191; // strip out higher level flags if(action >= 2000 && action < 3000) { - setStatusP(ui_action); + setStatusP(Com::translatedF(UI_TEXT_STRING_ACTION_ID)); } else switch(action) @@ -2924,25 +3056,20 @@ int UIDisplay::executeAction(int action, bool allowMoves) Printer::setOrigin(0, 0, 0); break; case UI_ACTION_DEBUG_ECHO: - Printer::debugLevel ^= 1; + Printer::toggleEcho(); break; case UI_ACTION_DEBUG_INFO: - Printer::debugLevel ^= 2; + Printer::toggleInfo(); break; case UI_ACTION_DEBUG_ERROR: - Printer::debugLevel ^= 4; + Printer::toggleErrors(); break; case UI_ACTION_DEBUG_DRYRUN: - Printer::debugLevel ^= 8; + Printer::toggleDryRun(); if(Printer::debugDryrun()) // simulate movements without printing { - Extruder::setTemperatureForExtruder(0, 0); -#if NUM_EXTRUDER > 1 - Extruder::setTemperatureForExtruder(0, 1); -#endif -#if NUM_EXTRUDER > 2 - Extruder::setTemperatureForExtruder(0, 2); -#endif + for(int i = 0;i < NUM_EXTRUDER; i++) + Extruder::setTemperatureForExtruder(0, i); #if HAVE_HEATED_BED Extruder::setHeatedBedTemperature(0); #endif @@ -2958,12 +3085,15 @@ int UIDisplay::executeAction(int action, bool allowMoves) #if CASE_LIGHTS_PIN >= 0 case UI_ACTION_LIGHTS_ONOFF: TOGGLE(CASE_LIGHTS_PIN); +#ifdef CASE_LIGHTS2_PIN + TOGGLE(CASE_LIGHTS2_PIN); +#endif Printer::reportCaseLightStatus(); - UI_STATUS(UI_TEXT_LIGHTS_ONOFF); + UI_STATUS_F(Com::translatedF(UI_TEXT_LIGHTS_ONOFF_ID)); break; #endif case UI_ACTION_PREHEAT_PLA: - UI_STATUS(UI_TEXT_PREHEAT_PLA); + UI_STATUS_F(Com::translatedF(UI_TEXT_PREHEAT_PLA_ID)); Extruder::setTemperatureForExtruder(UI_SET_PRESET_EXTRUDER_TEMP_PLA,0); #if NUM_EXTRUDER > 1 Extruder::setTemperatureForExtruder(UI_SET_PRESET_EXTRUDER_TEMP_PLA,1); @@ -2976,7 +3106,7 @@ int UIDisplay::executeAction(int action, bool allowMoves) #endif break; case UI_ACTION_PREHEAT_ABS: - UI_STATUS(UI_TEXT_PREHEAT_ABS); + UI_STATUS_F(Com::translatedF(UI_TEXT_PREHEAT_ABS_ID)); Extruder::setTemperatureForExtruder(UI_SET_PRESET_EXTRUDER_TEMP_ABS,0); #if NUM_EXTRUDER > 1 Extruder::setTemperatureForExtruder(UI_SET_PRESET_EXTRUDER_TEMP_ABS,1); @@ -2989,14 +3119,9 @@ int UIDisplay::executeAction(int action, bool allowMoves) #endif break; case UI_ACTION_COOLDOWN: - UI_STATUS(UI_TEXT_COOLDOWN); - Extruder::setTemperatureForExtruder(0, 0); -#if NUM_EXTRUDER > 1 - Extruder::setTemperatureForExtruder(0, 1); -#endif -#if NUM_EXTRUDER > 2 - Extruder::setTemperatureForExtruder(0, 2); -#endif + UI_STATUS_F(Com::translatedF(UI_TEXT_COOLDOWN_ID)); + for(int i = 0;i < NUM_EXTRUDER; i++) + Extruder::setTemperatureForExtruder(0, i); #if HAVE_HEATED_BED Extruder::setHeatedBedTemperature(0); #endif @@ -3010,8 +3135,17 @@ int UIDisplay::executeAction(int action, bool allowMoves) #if NUM_EXTRUDER > 1 case UI_ACTION_EXTRUDER1_OFF: #endif -#if NUM_EXTRUDER>2 +#if NUM_EXTRUDER > 2 case UI_ACTION_EXTRUDER2_OFF: +#endif +#if NUM_EXTRUDER > 3 + case UI_ACTION_EXTRUDER3_OFF: +#endif +#if NUM_EXTRUDER > 4 + case UI_ACTION_EXTRUDER4_OFF: +#endif +#if NUM_EXTRUDER > 5 + case UI_ACTION_EXTRUDER5_OFF: #endif Extruder::setTemperatureForExtruder(0, action - UI_ACTION_EXTRUDER0_OFF); break; @@ -3030,13 +3164,30 @@ int UIDisplay::executeAction(int action, bool allowMoves) #endif #if NUM_EXTRUDER > 2 case UI_ACTION_SELECT_EXTRUDER2: +#endif +#if NUM_EXTRUDER > 3 + case UI_ACTION_SELECT_EXTRUDER3: +#endif +#if NUM_EXTRUDER > 4 + case UI_ACTION_SELECT_EXTRUDER4: +#endif +#if NUM_EXTRUDER > 5 + case UI_ACTION_SELECT_EXTRUDER5: #endif if(!allowMoves) return action; Extruder::selectExtruderById(action - UI_ACTION_SELECT_EXTRUDER0); currHeaterForSetup = &(Extruder::current->tempControl); Printer::setMenuMode(MENU_MODE_FULL_PID, currHeaterForSetup->heatManager == 1); Printer::setMenuMode(MENU_MODE_DEADTIME, currHeaterForSetup->heatManager == 3); - break; + break; +#if FEATURE_DITTO_PRINTING + case UI_DITTO_0: + case UI_DITTO_1: + case UI_DITTO_2: + case UI_DITTO_3: + Extruder::dittoMode = action - UI_DITTO_0; + break; +#endif #if EEPROM_MODE != 0 case UI_ACTION_STORE_EEPROM: EEPROM::storeDataIntoEEPROM(false); @@ -3058,7 +3209,7 @@ int UIDisplay::executeAction(int action, bool allowMoves) } else { - UI_ERROR(UI_TEXT_NOSDCARD); + UI_ERROR_P(Com::translatedF(UI_TEXT_NOSDCARD_ID)); } break; case UI_ACTION_SD_PRINT: @@ -3108,20 +3259,20 @@ int UIDisplay::executeAction(int action, bool allowMoves) case UI_ACTION_FAN_25: case UI_ACTION_FAN_50: case UI_ACTION_FAN_75: - Commands::setFanSpeed((action - UI_ACTION_FAN_OFF) * 64, false); + Commands::setFanSpeed((action - UI_ACTION_FAN_OFF) * 64, true); break; case UI_ACTION_FAN_FULL: - Commands::setFanSpeed(255, false); + Commands::setFanSpeed(255, true); break; case UI_ACTION_FAN_SUSPEND: { static uint8_t lastFanSpeed = 255; if(Printer::getFanSpeed()==0) - Commands::setFanSpeed(lastFanSpeed,false); + Commands::setFanSpeed(lastFanSpeed, true); else { lastFanSpeed = Printer::getFanSpeed(); - Commands::setFanSpeed(0,false); + Commands::setFanSpeed(0, true); } } break; @@ -3259,22 +3410,22 @@ int UIDisplay::executeAction(int action, bool allowMoves) case UI_ACTION_X_UP: case UI_ACTION_X_DOWN: if(!allowMoves) return action; - PrintLine::moveRelativeDistanceInStepsReal(((action == UI_ACTION_X_UP) ? 1.0 : -1.0) * Printer::axisStepsPerMM[X_AXIS], 0, 0, 0, Printer::homingFeedrate[X_AXIS], false); + PrintLine::moveRelativeDistanceInStepsReal(((action == UI_ACTION_X_UP) ? 1.0 : -1.0) * Printer::axisStepsPerMM[X_AXIS], 0, 0, 0, Printer::homingFeedrate[X_AXIS], false,false); break; case UI_ACTION_Y_UP: case UI_ACTION_Y_DOWN: if(!allowMoves) return action; - PrintLine::moveRelativeDistanceInStepsReal(0, ((action == UI_ACTION_Y_UP) ? 1.0 : -1.0) * Printer::axisStepsPerMM[Y_AXIS], 0, 0, Printer::homingFeedrate[Y_AXIS], false); + PrintLine::moveRelativeDistanceInStepsReal(0, ((action == UI_ACTION_Y_UP) ? 1.0 : -1.0) * Printer::axisStepsPerMM[Y_AXIS], 0, 0, Printer::homingFeedrate[Y_AXIS], false,false); break; case UI_ACTION_Z_UP: case UI_ACTION_Z_DOWN: if(!allowMoves) return action; - PrintLine::moveRelativeDistanceInStepsReal(0, 0, ((action == UI_ACTION_Z_UP) ? 1.0 : -1.0) * Printer::axisStepsPerMM[Z_AXIS], 0, Printer::homingFeedrate[Z_AXIS], false); + PrintLine::moveRelativeDistanceInStepsReal(0, 0, ((action == UI_ACTION_Z_UP) ? 1.0 : -1.0) * Printer::axisStepsPerMM[Z_AXIS], 0, Printer::homingFeedrate[Z_AXIS], false,false); break; case UI_ACTION_EXTRUDER_UP: case UI_ACTION_EXTRUDER_DOWN: if(!allowMoves) return action; - PrintLine::moveRelativeDistanceInStepsReal(0, 0, 0, ((action == UI_ACTION_EXTRUDER_UP) ? 1.0 : -1.0) * Printer::axisStepsPerMM[E_AXIS], UI_SET_EXTRUDER_FEEDRATE, false); + PrintLine::moveRelativeDistanceInStepsReal(0, 0, 0, ((action == UI_ACTION_EXTRUDER_UP) ? 1.0 : -1.0) * Printer::axisStepsPerMM[E_AXIS], UI_SET_EXTRUDER_FEEDRATE, false,false); break; case UI_ACTION_EXTRUDER_TEMP_UP: { @@ -3365,10 +3516,10 @@ int UIDisplay::executeAction(int action, bool allowMoves) #endif break; case UI_ACTION_FAN_UP: - Commands::setFanSpeed(Printer::getFanSpeed() + 32,false); + Commands::setFanSpeed(Printer::getFanSpeed() + 32, true); break; case UI_ACTION_FAN_DOWN: - Commands::setFanSpeed(Printer::getFanSpeed() - 32,false); + Commands::setFanSpeed(Printer::getFanSpeed() - 32, true); break; case UI_ACTION_KILL: Commands::emergencyStop(); @@ -3379,6 +3530,26 @@ int UIDisplay::executeAction(int action, bool allowMoves) case UI_ACTION_PAUSE: Com::printFLN(PSTR("RequestPause:")); break; +#if UI_BED_COATING + case UI_ACTION_NOCOATING: + menuAdjustHeight(&ui_menu_nocoating_action,0); + break; + case UI_ACTION_BUILDTAK: + menuAdjustHeight(&ui_menu_buildtak_action,0.4); + break; + case UI_ACTION_KAPTON: + menuAdjustHeight(&ui_menu_kapton_action,0.04); + break; + case UI_ACTION_GLUESTICK: + menuAdjustHeight(&ui_menu_gluestick_action,0.04); + break; + case UI_ACTION_BLUETAPE: + menuAdjustHeight(&ui_menu_bluetape_action,0.15); + break; + case UI_ACTION_PETTAPE: + menuAdjustHeight(&ui_menu_pettape_action,0.09); + break; +#endif #if FEATURE_AUTOLEVEL case UI_ACTION_AUTOLEVEL_ONOFF: Printer::setAutolevelActive(!Printer::isAutolevelActive()); @@ -3406,6 +3577,21 @@ int UIDisplay::executeAction(int action, bool allowMoves) case UI_ACTION_TEMP_DEFECT: Printer::setAnyTempsensorDefect(); break; + case UI_ACTION_LANGUAGE_EN: + case UI_ACTION_LANGUAGE_DE: + case UI_ACTION_LANGUAGE_NL: + case UI_ACTION_LANGUAGE_PT: + case UI_ACTION_LANGUAGE_IT: + case UI_ACTION_LANGUAGE_ES: + case UI_ACTION_LANGUAGE_SE: + case UI_ACTION_LANGUAGE_FR: + case UI_ACTION_LANGUAGE_CZ: + case UI_ACTION_LANGUAGE_PL: + Com::selectLanguage(action - UI_ACTION_LANGUAGE_EN); +#if EEPROM_MODE != 0 + EEPROM::storeDataIntoEEPROM(0); // remember for next start +#endif + break; } refreshPage(); #if UI_AUTORETURN_TO_MENU_AFTER!=0 @@ -3457,9 +3643,11 @@ void UIDisplay::slowAction(bool allowMoves) uid.outputMask= ~led & (UI_I2C_HEATBED_LED | UI_I2C_HOTEND_LED | UI_I2C_FAN_LED); } #endif - int nextAction = 0; + uint16_t nextAction = 0; uiCheckSlowKeys(nextAction); +#ifdef HAS_USER_KEYS ui_check_Ukeys(nextAction); +#endif if(lastButtonAction != nextAction) { lastButtonStart = time; @@ -3532,7 +3720,7 @@ void UIDisplay::slowAction(bool allowMoves) noInts.unprotect(); #endif #if UI_AUTORETURN_TO_MENU_AFTER != 0 - if(menuLevel > 0 && ui_autoreturn_time < time && !uid.isWizardActive()) // Go to top menu after x seoonds + if(menuLevel > 0 && ui_autoreturn_time < time && !uid.isSticky()) // Go to top menu after x seoonds { lastSwitch = time; menuLevel = 0; @@ -3557,8 +3745,8 @@ void UIDisplay::slowAction(bool allowMoves) } else if(time - lastRefresh >= 800) { - UIMenu *men = (UIMenu*)menu[menuLevel]; - uint8_t mtype = pgm_read_byte((void*)&(men->menuType)); + //UIMenu *men = (UIMenu*)menu[menuLevel]; + //uint8_t mtype = pgm_read_byte((void*)&(men->menuType)); //if(mtype!=1) refresh = 1; } @@ -3568,7 +3756,7 @@ void UIDisplay::slowAction(bool allowMoves) #if defined(HAS_AUTOREPAIR) repairLCD(); #else - #error TRY_AUTOREPAIR_LCD_ERRORS is not supported for your display type! +#error TRY_AUTOREPAIR_LCD_ERRORS is not supported for your display type! #endif #endif @@ -3596,7 +3784,7 @@ void UIDisplay::fastAction() if((flags & (UI_FLAG_KEY_TEST_RUNNING + UI_FLAG_SLOW_KEY_ACTION)) == 0) { flags |= UI_FLAG_KEY_TEST_RUNNING; - int nextAction = 0; + uint16_t nextAction = 0; uiCheckKeys(nextAction); // ui_check_Ukeys(nextAction); if(lastButtonAction != nextAction) @@ -3631,5 +3819,3 @@ const int8_t encoder_table[16] PROGMEM = {0,0,0,0,0,0,0,0,0,0,0,-1,0,0,1,0}; // #endif #endif - - diff --git a/Repetier/ui.h b/Repetier/ui.h index 972cf7e..4fa6aca 100644 --- a/Repetier/ui.h +++ b/Repetier/ui.h @@ -49,9 +49,11 @@ What display type do you use? // 4000-4999 : Show menu // 5000-5999 : Wizard pages // Add UI_ACTION_TOPMENU to show a menu as top menu +// Add UI_ACTION_NO_AUTORETURN to prevent autoreturn to start display // ---------------------------------------------------------------------------- #define UI_ACTION_TOPMENU 8192 +#define UI_ACTION_NO_AUTORETURN 16384 #define UI_ACTION_NEXT 1 #define UI_ACTION_PREVIOUS 2 @@ -96,9 +98,6 @@ What display type do you use? #define UI_ACTION_HOME_X 1022 #define UI_ACTION_HOME_Y 1023 #define UI_ACTION_HOME_Z 1024 -#define UI_ACTION_SELECT_EXTRUDER0 1025 -#define UI_ACTION_SELECT_EXTRUDER1 1026 -#define UI_ACTION_SELECT_EXTRUDER2 1027 #define UI_ACTION_STORE_EEPROM 1030 #define UI_ACTION_LOAD_EEPROM 1031 #define UI_ACTION_PRINT_ACCEL_X 1032 @@ -152,10 +151,10 @@ What display type do you use? #define UI_ACTION_HEATED_BED_OFF 1081 #define UI_ACTION_EXTRUDER0_OFF 1082 #define UI_ACTION_EXTRUDER1_OFF 1083 -#define UI_ACTION_EXTRUDER2_OFF 1184 -#define UI_ACTION_HEATED_BED_TEMP 1085 -#define UI_ACTION_EXTRUDER0_TEMP 1086 -#define UI_ACTION_EXTRUDER1_TEMP 1087 +#define UI_ACTION_EXTRUDER2_OFF 1084 +#define UI_ACTION_EXTRUDER3_OFF 1085 +#define UI_ACTION_EXTRUDER4_OFF 1086 +#define UI_ACTION_EXTRUDER5_OFF 1087 #define UI_ACTION_OPS_OFF 1088 #define UI_ACTION_OPS_CLASSIC 1089 #define UI_ACTION_OPS_FAST 1090 @@ -170,7 +169,6 @@ What display type do you use? #define UI_ACTION_PAUSE 1099 #define UI_ACTION_EXTR_WAIT_RETRACT_TEMP 1100 #define UI_ACTION_EXTR_WAIT_RETRACT_UNITS 1101 -#define UI_ACTION_EXTRUDER2_TEMP 1103 #define UI_ACTION_WRITE_DEBUG 1105 #define UI_ACTION_FANSPEED 1106 #define UI_ACTION_LIGHTS_ONOFF 1107 @@ -186,13 +184,55 @@ What display type do you use? #define UI_ACTION_BED_DGAIN 1117 #define UI_ACTION_BED_DRIVE_MIN 1118 #define UI_ACTION_BED_DRIVE_MAX 1119 -#define UI_ACTION_BED_MAX 1120 +#define UI_ACTION_BED_MAX 1120 +#define UI_ACTION_HEATED_BED_TEMP 1121 +#define UI_ACTION_EXTRUDER0_TEMP 1122 +#define UI_ACTION_EXTRUDER1_TEMP 1123 +#define UI_ACTION_EXTRUDER2_TEMP 1124 +#define UI_ACTION_EXTRUDER3_TEMP 1125 +#define UI_ACTION_EXTRUDER4_TEMP 1126 +#define UI_ACTION_EXTRUDER5_TEMP 1127 +#define UI_ACTION_SELECT_EXTRUDER0 1128 +#define UI_ACTION_SELECT_EXTRUDER1 1129 +#define UI_ACTION_SELECT_EXTRUDER2 1130 +#define UI_ACTION_SELECT_EXTRUDER3 1131 +#define UI_ACTION_SELECT_EXTRUDER4 1132 +#define UI_ACTION_SELECT_EXTRUDER5 1133 +#define UI_DITTO_0 1134 +#define UI_DITTO_1 1135 +#define UI_DITTO_2 1136 +#define UI_DITTO_3 1137 + #define UI_ACTION_SD_PRI_PAU_CONT 1200 #define UI_ACTION_FAN_SUSPEND 1201 #define UI_ACTION_AUTOLEVEL_ONOFF 1202 #define UI_ACTION_SERVOPOS 1203 #define UI_ACTION_IGNORE_M106 1204 +#define UI_ACTION_KAPTON 1205 +#define UI_ACTION_BLUETAPE 1206 +#define UI_ACTION_NOCOATING 1207 +#define UI_ACTION_PETTAPE 1208 +#define UI_ACTION_GLUESTICK 1209 +#define UI_ACTION_RESET_MATRIX 1210 +#define UI_ACTION_CALIBRATE 1211 +#define UI_ACTION_BED_LED_CHANGE 1212 +#define UI_ACTION_COATING_CUSTOM 1213 +#define UI_ACTION_BUILDTAK 1214 + +// 1700-1956 language selectors + +#define UI_ACTION_LANGUAGE_EN 1700 +#define UI_ACTION_LANGUAGE_DE 1701 +#define UI_ACTION_LANGUAGE_NL 1702 +#define UI_ACTION_LANGUAGE_PT 1703 +#define UI_ACTION_LANGUAGE_IT 1704 +#define UI_ACTION_LANGUAGE_ES 1705 +#define UI_ACTION_LANGUAGE_SE 1706 +#define UI_ACTION_LANGUAGE_FR 1707 +#define UI_ACTION_LANGUAGE_CZ 1708 +#define UI_ACTION_LANGUAGE_PL 1709 + #define UI_ACTION_MENU_XPOS 4000 #define UI_ACTION_MENU_YPOS 4001 #define UI_ACTION_MENU_ZPOS 4002 @@ -210,6 +250,9 @@ What display type do you use? #define UI_ACTION_SET_P2 4014 #define UI_ACTION_SET_P3 4015 #define UI_ACTION_CALC_LEVEL 4016 +#define UI_ACTION_XOFF 4020 +#define UI_ACTION_YOFF 4021 +#define UI_ACTION_ZOFF 4022 #define UI_ACTION_SHOW_USERMENU1 4101 #define UI_ACTION_SHOW_USERMENU2 4102 @@ -228,7 +271,7 @@ What display type do you use? #define UI_ACTION_WIZARD_JAM_EOF 5003 // Load basic language definition to make sure all values are defined -#include "uilang.h" +//#include "uilang.h" #define UI_MENU_TYPE_INFO 0 #define UI_MENU_TYPE_FILE_SELECTOR 1 @@ -236,26 +279,31 @@ What display type do you use? #define UI_MENU_TYPE_MODIFICATION_MENU 3 #define UI_MENU_TYPE_WIZARD 5 -typedef struct { +struct UIMenuEntry_s { const char *text; // Menu text - uint8_t menuType; // 0 = Info, 1 = Headline, 2 = submenu ref, 3 = direct action command, 4 = modify action command, + uint8_t entryType; // 0 = Info, 1 = Headline, 2 = submenu ref, 3 = direct action command, 4 = modify action command, unsigned int action; // must be int so it gets 32 bit on arm! uint8_t filter; // allows dynamic menu filtering based on Printer::menuMode bits set. uint8_t nofilter; // Hide if one of these bits are set + int translation; // Translation id bool showEntry() const; -} const UIMenuEntry; +} ; +typedef const UIMenuEntry_s UIMenuEntry; -typedef struct UIMenu_struct { +struct UIMenu_s { // 0 = info page // 1 = file selector // 2 = submenu // 3 = modififaction menu // 5 = Wizard menu + // +128 = sticky -> no autoreturn to main menuü after timeout uint8_t menuType; int id; // Type of modification int numEntries; const UIMenuEntry * const * entries; -} const UIMenu; +}; +typedef const UIMenu_s UIMenu; + extern const int8_t encoder_table[16] PROGMEM ; //#ifdef COMPILE_I2C_DRIVER @@ -331,68 +379,130 @@ extern const int8_t encoder_table[16] PROGMEM ; #define UI_STRING(name,text) const char PROGMEM name[] = text #define UI_PAGE6(name,row1,row2,row3,row4,row5,row6) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);UI_STRING(name ## _3txt,row3);UI_STRING(name ## _4txt,row4);UI_STRING(name ## _5txt,row5);UI_STRING(name ## _6txt,row6);\ - UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0};\ - UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0};\ - UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0};\ - UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0};\ - UIMenuEntry name ## _5 PROGMEM ={name ## _5txt,0,0,0,0};\ - UIMenuEntry name ## _6 PROGMEM ={name ## _6txt,0,0,0,0};\ + UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\ + UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\ + UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0,0};\ + UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0,0};\ + UIMenuEntry name ## _5 PROGMEM ={name ## _5txt,0,0,0,0,0};\ + UIMenuEntry name ## _6 PROGMEM ={name ## _6txt,0,0,0,0,0};\ + const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4,&name ## _5,&name ## _6};\ + const UIMenu name PROGMEM = {0,0,6,name ## _entries}; +#define UI_PAGE6_T(name,row1,row2,row3,row4,row5,row6) \ + UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\ + UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\ + UIMenuEntry name ## _3 PROGMEM ={0,0,0,0,0,row3};\ + UIMenuEntry name ## _4 PROGMEM ={0,0,0,0,0,row4};\ + UIMenuEntry name ## _5 PROGMEM ={0,0,0,0,0,row5};\ + UIMenuEntry name ## _6 PROGMEM ={0,0,0,0,0,row6};\ const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4,&name ## _5,&name ## _6};\ const UIMenu name PROGMEM = {0,0,6,name ## _entries}; #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,0,0};\ - UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0};\ - UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0};\ - UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0};\ + UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\ + UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\ + UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0,0};\ + UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,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_PAGE4_T(name,row1,row2,row3,row4) \ + UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\ + UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\ + UIMenuEntry name ## _3 PROGMEM ={0,0,0,0,0,row3};\ + UIMenuEntry name ## _4 PROGMEM ={0,0,0,0,0,row4};\ 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,0,0};\ - UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0};\ + UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\ + UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\ + const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\ + const UIMenu name PROGMEM = {0,0,2,name ## _entries}; +#define UI_PAGE2_T(name,row1,row2) \ + UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\ + UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\ const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\ const UIMenu name PROGMEM = {0,0,2,name ## _entries}; #define UI_WIZARD4(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,0,0};\ - UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0};\ - UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0};\ - UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0};\ + UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\ + UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\ + UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0,0};\ + UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0,0};\ + const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\ + const UIMenu name PROGMEM = {5,action,4,name ## _entries}; +#define UI_WIZARD4_T(name,action,row1,row2,row3,row4) \ + UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\ + UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\ + UIMenuEntry name ## _3 PROGMEM ={0,0,0,0,0,row3};\ + UIMenuEntry name ## _4 PROGMEM ={0,0,0,0,0,row4};\ const UIMenuEntry * const name ## _entries [] PROGMEM = {&name ## _1,&name ## _2,&name ## _3,&name ## _4};\ const UIMenu name PROGMEM = {5,action,4,name ## _entries}; #define UI_WIZARD2(name,action,row1,row2) UI_STRING(name ## _1txt,row1);UI_STRING(name ## _2txt,row2);\ - UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0};\ - UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0};\ + UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\ + UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\ + const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\ + const UIMenu name PROGMEM = {5,action,2,name ## _entries}; +#define UI_WIZARD2_T(name,action,row1,row2) \ + UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\ + UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\ const UIMenuEntry * const name ## _entries[] PROGMEM = {&name ## _1,&name ## _2};\ const UIMenu name PROGMEM = {5,action,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_ACTION4C_T(name,action,rows) UI_MENU_ACTION4_T(name,action,rows) +#define UI_MENU_ACTION2C_T(name,action,rows) UI_MENU_ACTION2_T(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,0,0};\ - UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0};\ - UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0};\ - UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,0};\ + UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\ + UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0,0};\ + UIMenuEntry name ## _3 PROGMEM ={name ## _3txt,0,0,0,0,0};\ + UIMenuEntry name ## _4 PROGMEM ={name ## _4txt,0,0,0,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_ACTION4_T(name,action,row1,row2,row3,row4) \ + UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\ + UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\ + UIMenuEntry name ## _3 PROGMEM ={0,0,0,0,0,row3};\ + UIMenuEntry name ## _4 PROGMEM ={0,0,0,0,0,row4};\ 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,0,0};\ - UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,0};\ + UIMenuEntry name ## _1 PROGMEM ={name ## _1txt,0,0,0,0,0};\ + UIMenuEntry name ## _2 PROGMEM ={name ## _2txt,0,0,0,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,0,0}; -#define UI_MENU_CHANGEACTION(name,row,action) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,4,action,0,0}; -#define UI_MENU_ACTIONCOMMAND(name,row,action) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,3,action,0,0}; -#define UI_MENU_ACTIONSELECTOR(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,0,0}; -#define UI_MENU_SUBMENU(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,0,0}; -#define UI_MENU_WIZARD(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,5,(unsigned int)&entries,0,0}; -#define UI_MENU_CHANGEACTION_FILTER(name,row,action,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,4,action,filter,nofilter}; -#define UI_MENU_ACTIONCOMMAND_FILTER(name,row,action,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,3,action,filter,nofilter}; -#define UI_MENU_ACTIONSELECTOR_FILTER(name,row,entries,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,filter,nofilter}; -#define UI_MENU_SUBMENU_FILTER(name,row,entries,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,filter,nofilter}; +#define UI_MENU_ACTION2_T(name,action,row1,row2) \ + UIMenuEntry name ## _1 PROGMEM ={0,0,0,0,0,row1};\ + UIMenuEntry name ## _2 PROGMEM ={0,0,0,0,0,row2};\ + 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,0,0,0}; +#define UI_MENU_HEADLINE_T(name,text) UIMenuEntry name PROGMEM = {0,1,0,0,0,text}; +#define UI_MENU_CHANGEACTION(name,row,action) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,4,action,0,0,0}; +#define UI_MENU_CHANGEACTION_T(name,row,action) UIMenuEntry name PROGMEM = {0,4,action,0,0,row}; +#define UI_MENU_ACTIONCOMMAND(name,row,action) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,3,action,0,0,0}; +#define UI_MENU_ACTIONCOMMAND_T(name,rowId,action) UIMenuEntry name PROGMEM = {0,3,action,0,0,rowId}; +#define UI_MENU_ACTIONSELECTOR(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,0,0,0}; +#define UI_MENU_ACTIONSELECTOR_T(name,row,entries) UIMenuEntry name PROGMEM = {0,2,(unsigned int)&entries,0,0,row}; +#define UI_MENU_SUBMENU(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,0,0,0}; +#define UI_MENU_SUBMENU_T(name,row,entries) UIMenuEntry name PROGMEM = {0,2,(unsigned int)&entries,0,0,row}; +#define UI_MENU_WIZARD(name,row,entries) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,5,(unsigned int)&entries,0,0,0}; +#define UI_MENU_WIZARD_T(name,row,entries) UIMenuEntry name PROGMEM = {0,5,(unsigned int)&entries,0,0,row}; +#define UI_MENU_CHANGEACTION_FILTER(name,row,action,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,4,action,filter,nofilter,0}; +#define UI_MENU_CHANGEACTION_FILTER_T(name,row,action,filter,nofilter) UIMenuEntry name PROGMEM = {0,4,action,filter,nofilter,row}; +#define UI_MENU_ACTIONCOMMAND_FILTER(name,row,action,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,3,action,filter,nofilter,0}; +#define UI_MENU_ACTIONCOMMAND_FILTER_T(name,row,action,filter,nofilter) UIMenuEntry name PROGMEM = {0,3,action,filter,nofilter,row}; +#define UI_MENU_ACTIONSELECTOR_FILTER(name,row,entries,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,filter,nofilter,0}; +#define UI_MENU_ACTIONSELECTOR_FILTER_T(name,row,entries,filter,nofilter) UIMenuEntry name PROGMEM = {0,2,(unsigned int)&entries,filter,nofilter,row}; +#define UI_MENU_SUBMENU_FILTER(name,row,entries,filter,nofilter) UI_STRING(name ## _txt,row);UIMenuEntry name PROGMEM = {name ## _txt,2,(unsigned int)&entries,filter,nofilter,0}; +#define UI_MENU_SUBMENU_FILTER_T(name,row,entries,filter,nofilter) UIMenuEntry name PROGMEM = {0,2,(unsigned int)&entries,filter,nofilter,row}; #define UI_MENU(name,items,itemsCnt) const UIMenuEntry * const name ## _entries[] PROGMEM = items;const UIMenu name PROGMEM = {2,0,itemsCnt,name ## _entries}; +#define UI_STICKYMENU(name,items,itemsCnt) const UIMenuEntry * const name ## _entries[] PROGMEM = items;const UIMenu name PROGMEM = {2+128,0,itemsCnt,name ## _entries}; #define UI_MENU_FILESELECT(name,items,itemsCnt) const UIMenuEntry * const name ## _entries[] PROGMEM = items;const UIMenu name PROGMEM = {1,0,itemsCnt,name ## _entries}; #if FEATURE_CONTROLLER == CONTROLLER_SMARTRAMPS || FEATURE_CONTROLLER == CONTROLLER_GADGETS3D_SHIELD || FEATURE_CONTROLLER == CONTROLLER_BAM_DICE_DUE || (FEATURE_CONTROLLER == CONTROLLER_REPRAPDISCOUNT_GLCD && MOTHERBOARD != CONTROLLER_FELIX_DUE) #undef SDCARDDETECT +#if MOTHERBOARD == 37 +#define SDCARDDETECT ORIG_SDCARDDETECT +#else #define SDCARDDETECT 49 +#endif #undef SDCARDDETECTINVERTED #define SDCARDDETECTINVERTED 0 #undef SDSUPPORT @@ -417,7 +527,7 @@ extern const int8_t encoder_table[16] PROGMEM ; // Maximum size of a row - if row is larger, text gets scrolled -#if UI_DISPLAY_TYPE == DISPLAY_GAMEDUINO2 +#if defined(UI_DISPLAY_TYPE) && UI_DISPLAY_TYPE == DISPLAY_GAMEDUINO2 #define MAX_COLS 50 #else #define MAX_COLS 28 @@ -456,7 +566,7 @@ class UIDisplay { uint8_t encoderStartScreen; char printCols[MAX_COLS+1]; void addInt(int value,uint8_t digits,char fillChar=' '); // Print int into printCols - void addLong(long value,char digits); + void addLong(long value,int8_t digits); inline void addLong(long value) {addLong(value, -11);}; void addFloat(float number, char fixdigits,uint8_t digits); inline void addFloat(float number) {addFloat(number, -9,2);}; @@ -477,8 +587,8 @@ class UIDisplay { void printRowP(uint8_t r,PGM_P txt); void parse(const char *txt,bool ram); /// Parse output and write to printCols; void refreshPage(); - int executeAction(int action, bool allowMoves); - void finishAction(int action); + int executeAction(unsigned int action, bool allowMoves); + void finishAction(unsigned int action); void slowAction(bool allowMoves); void fastAction(); void mediumAction(); @@ -493,6 +603,11 @@ class UIDisplay { void goDir(char *name); bool isDirname(char *name); bool isWizardActive(); + bool isSticky(); + void showLanguageSelectionWizard(); +#if UI_BED_COATING + void menuAdjustHeight(const UIMenu *men,float offset); +#endif char cwd[SD_MAX_FOLDER_DEPTH*LONG_FILENAME_LENGTH+2]; uint8_t folderLevel; }; @@ -506,11 +621,11 @@ extern UIDisplay uid; #if FEATURE_CONTROLLER == NO_CONTROLLER #define UI_HAS_KEYS 0 #define UI_DISPLAY_TYPE NO_DISPLAY -#if UI_MAIN +#ifdef UI_MAIN void uiInitKeys() {} -void uiCheckKeys(int &action) {} +void uiCheckKeys(uint16_t &action) {} inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif // UI_MAIN #endif // NO_CONTROLLER #if (FEATURE_CONTROLLER == CONTROLLER_SMARTRAMPS) || (FEATURE_CONTROLLER == CONTROLLER_GADGETS3D_SHIELD) || (FEATURE_CONTROLLER == CONTROLLER_REPRAPDISCOUNT_GLCD) || (FEATURE_CONTROLLER == CONTROLLER_BAM_DICE_DUE) @@ -529,7 +644,8 @@ void uiCheckSlowKeys(int &action) {} #define UI_FONT_SMALL_HEIGHT 7 #define UI_FONT_DEFAULT repetier_6x10 #define UI_FONT_SMALL repetier_5x7 -#define UI_FONT_SMALL_WIDTH 5 //smaller font for status display +#define UI_FONT_SMALL_WIDTH 5 //smaller font for status display +#undef UI_ANIMATION #define UI_ANIMATION 0 // Animations are too slow #endif @@ -548,6 +664,7 @@ void uiCheckSlowKeys(int &action) {} #if FEATURE_CONTROLLER == CONTROLLER_GADGETS3D_SHIELD // Gadgets3d shield +#undef BEEPER_PIN #define BEEPER_PIN 33 #define UI_DISPLAY_RS_PIN 16 #define UI_DISPLAY_RW_PIN -1 @@ -581,9 +698,24 @@ void uiCheckSlowKeys(int &action) {} #define UI_ENCODER_CLICK 43 #define UI_RESET_PIN 66 // was 41 //AE3 was here and added this line 1/25/2014 (Note pin 41 is Y- endstop!) #define UI_INVERT_MENU_DIRECTION 1 + +#elif MOTHERBOARD == 703 // Megatronics v3.0 + +#define UI_DISPLAY_RS_PIN 32 +#define UI_DISPLAY_RW_PIN -1 +#define UI_DISPLAY_ENABLE_PIN 31 +#define UI_DISPLAY_D4_PIN 14 +#define UI_DISPLAY_D5_PIN 30 +#define UI_DISPLAY_D6_PIN 39 +#define UI_DISPLAY_D7_PIN 15 +#define UI_ENCODER_A 45 +#define UI_ENCODER_B 44 +#define UI_ENCODER_CLICK 33 +#define UI_INVERT_MENU_DIRECTION 1 #elif MOTHERBOARD == 80 // Rumba has different pins as RAMPS! +#undef BEEPER_PIN #define BEEPER_PIN 44 #define UI_DISPLAY_RS_PIN 19 #define UI_DISPLAY_RW_PIN -1 @@ -601,8 +733,28 @@ void uiCheckSlowKeys(int &action) {} #define UI_ENCODER_CLICK 43 #define UI_RESET_PIN 46 +#elif MOTHERBOARD == 37 // UltiMaker 1.5.7 +#undef BEEPER_PIN +#define BEEPER_PIN 18 +#define UI_DISPLAY_RS_PIN 20 +#define UI_DISPLAY_RW_PIN -1 +#define UI_DISPLAY_ENABLE_PIN 17 +#define UI_DISPLAY_D0_PIN -1 +#define UI_DISPLAY_D1_PIN -1 +#define UI_DISPLAY_D2_PIN -1 +#define UI_DISPLAY_D3_PIN -1 +#define UI_DISPLAY_D4_PIN 16 +#define UI_DISPLAY_D5_PIN 21 +#define UI_DISPLAY_D6_PIN 5 +#define UI_DISPLAY_D7_PIN 6 +#define UI_ENCODER_A 42 +#define UI_ENCODER_B 40 +#define UI_ENCODER_CLICK 19 +#define UI_RESET_PIN -1 + #elif MOTHERBOARD == 301 // Rambo has own pins layout +#undef BEEPER_PIN #define BEEPER_PIN 79 #define UI_DISPLAY_RS_PIN 70 #define UI_DISPLAY_RW_PIN -1 @@ -628,6 +780,7 @@ void uiCheckSlowKeys(int &action) {} #elif MOTHERBOARD == 501 // Alligator has own pins layout +#undef BEEPER_PIN #define BEEPER_PIN 64 #define UI_DISPLAY_RS_PIN 18 #define UI_DISPLAY_ENABLE_PIN 15 @@ -646,6 +799,7 @@ void uiCheckSlowKeys(int &action) {} #elif MOTHERBOARD == CONTROLLER_FELIX_DUE +#undef BEEPER_PIN #define BEEPER_PIN -1 #define UI_DISPLAY_RS_PIN 42 #define UI_DISPLAY_ENABLE_PIN 44 @@ -656,6 +810,7 @@ void uiCheckSlowKeys(int &action) {} #define UI_RESET_PIN -1 #else // RAMPS +#undef BEEPER_PIN #define BEEPER_PIN 37 #define UI_DISPLAY_RS_PIN 16 #define UI_DISPLAY_RW_PIN -1 @@ -680,7 +835,7 @@ void uiCheckSlowKeys(int &action) {} #endif #define UI_INVERT_MENU_DIRECTION 0 -#if UI_MAIN +#ifdef UI_MAIN void uiInitKeys() { 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 @@ -688,7 +843,7 @@ void uiInitKeys() { UI_KEYS_INIT_BUTTON_LOW(UI_RESET_PIN); // Kill pin #endif } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { #if FEATURE_CONTROLLER == CONTROLLER_BAM_DICE_DUE UI_KEYS_CLICKENCODER_LOW_REV(UI_ENCODER_B,UI_ENCODER_A); // click encoder on pins 47 and 45. Phase is connected with gnd for signals. #else @@ -700,7 +855,7 @@ void uiCheckKeys(int &action) { #endif } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif #endif // Controller 2 and 10 @@ -734,22 +889,22 @@ void uiCheckSlowKeys(int &action) {} #define UI_I2C_KEY_ADDRESS 0x40 #ifdef UI_MAIN void uiInitKeys() {} -void uiCheckKeys(int &action) {} +void uiCheckKeys(uint16_t &action) {} inline void uiCheckSlowEncoder() { HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_WRITE); HAL::i2cWrite(0x12); // GIOA HAL::i2cStop(); HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_READ); - unsigned int keymask = HAL::i2cReadAck(); + uint16_t keymask = HAL::i2cReadAck(); keymask = keymask + (HAL::i2cReadNak()<<8); HAL::i2cStop(); } -void uiCheckSlowKeys(int &action) { +void uiCheckSlowKeys(uint16_t &action) { HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_WRITE); HAL::i2cWrite(0x12); // GPIOA HAL::i2cStop(); HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_READ); - unsigned int keymask = HAL::i2cReadAck(); + uint16_t keymask = HAL::i2cReadAck(); keymask = keymask + (HAL::i2cReadNak()<<8); HAL::i2cStop(); UI_KEYS_I2C_BUTTON_LOW(4,UI_ACTION_PREVIOUS); // Up button @@ -768,20 +923,30 @@ void uiCheckSlowKeys(int &action) { #define UI_DISPLAY_CHARSET 2 #define UI_COLS 20 #define UI_ROWS 4 -#define UI_DISPLAY_RS_PIN 63 // PINK.1, 88, D_RS +// PINK.1, 88, D_RS +#define UI_DISPLAY_RS_PIN 63 #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 +// PINK.3, 86, D_E +#define UI_DISPLAY_ENABLE_PIN 65 +// PINF.5, 92, D_D4 +#define UI_DISPLAY_D0_PIN 59 +// PINK.2, 87, D_D5 +#define UI_DISPLAY_D1_PIN 64 +// PINL.5, 40, D_D6 +#define UI_DISPLAY_D2_PIN 44 +// PINK.4, 85, D_D7 +#define UI_DISPLAY_D3_PIN 66 +// PINF.5, 92, D_D4 +#define UI_DISPLAY_D4_PIN 59 +// PINK.2, 87, D_D5 +#define UI_DISPLAY_D5_PIN 64 +// PINL.5, 40, D_D6 +#define UI_DISPLAY_D6_PIN 44 +// PINK.4, 85, D_D7 +#define UI_DISPLAY_D7_PIN 66 #define UI_DELAYPERCHAR 50 #define UI_INVERT_MENU_DIRECTION 0 -#if UI_MAIN +#ifdef UI_MAIN void uiInitKeys() { UI_KEYS_INIT_BUTTON_LOW(4); // push button, connects gnd to pin UI_KEYS_INIT_BUTTON_LOW(5); @@ -789,7 +954,7 @@ void uiInitKeys() { UI_KEYS_INIT_BUTTON_LOW(11); UI_KEYS_INIT_BUTTON_LOW(42); } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &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 @@ -797,7 +962,7 @@ void uiCheckKeys(int &action) { UI_KEYS_BUTTON_LOW(42,UI_ACTION_SD_PRINT ); // push button, connects gnd to pin } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif #endif // Controller 4 @@ -806,11 +971,12 @@ void uiCheckSlowKeys(int &action) {} // You need to change these 3 button according to the positions // where you put them into your board! -#define UI_ENCODER_A 7 // pins the click encoder are connected to +#define UI_ENCODER_A 7 #define UI_ENCODER_B 22 -#define UI_RESET_PIN 32 // single button for reset -#define SDCARDDETECT 49 // Set to -1 if you have not connected that pin -#define SDSS 53 // Chip select pin +#define UI_RESET_PIN 32 +// Set to -1 if you have not connected that pin +#define SDCARDDETECT 49 +#define SDSS 53 #define SDSUPPORT 1 #define SDCARDDETECTINVERTED 0 @@ -841,6 +1007,7 @@ void uiCheckSlowKeys(int &action) {} #define UI_DISPLAY_D7_PIN _BV(9) +#undef BEEPER_PIN #define BEEPER_PIN _BV(5) #define BEEPER_TYPE 2 #define BEEPER_ADDRESS UI_DISPLAY_I2C_ADDRESS // I2C address of the chip with the beeper pin @@ -857,12 +1024,12 @@ void uiInitKeys() { UI_KEYS_INIT_CLICKENCODER_LOW(UI_ENCODER_A,UI_ENCODER_B); // click encoder on real pins. Phase is connected with gnd for signals. UI_KEYS_INIT_BUTTON_LOW(UI_RESET_PIN); // Kill pin } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { UI_KEYS_CLICKENCODER_LOW_REV(UI_ENCODER_A,UI_ENCODER_B); // click encoder on real pins UI_KEYS_BUTTON_LOW(UI_RESET_PIN,UI_ACTION_RESET); } inline void uiCheckSlowEncoder() { }// not used in Viki -void uiCheckSlowKeys(int &action) { +void uiCheckSlowKeys(uint16_t &action) { HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_WRITE); HAL::i2cWrite(0x12); // GPIOA HAL::i2cStop(); @@ -923,7 +1090,7 @@ void uiCheckSlowKeys(int &action) { #define UI_DELAYPERCHAR 50 #define UI_INVERT_MENU_DIRECTION 1 -#if UI_MAIN +#ifdef UI_MAIN void uiInitKeys() { UI_KEYS_INIT_CLICKENCODER_LOW(UI_ENCODER_A,UI_ENCODER_B); UI_KEYS_INIT_BUTTON_LOW(UI_ENCODER_CLICK); @@ -936,14 +1103,14 @@ void uiInitKeys() { WRITE(UI_SHIFT_LD,HIGH); } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { UI_KEYS_CLICKENCODER_LOW_REV(UI_ENCODER_A,UI_ENCODER_B); UI_KEYS_BUTTON_LOW(UI_ENCODER_CLICK,UI_ACTION_OK); } inline void uiCheckSlowEncoder() {} // not used -void uiCheckSlowKeys(int &action) { +void uiCheckSlowKeys(uint16_t &action) { WRITE(UI_SHIFT_LD,LOW); WRITE(UI_SHIFT_LD,HIGH); @@ -969,8 +1136,11 @@ void uiCheckSlowKeys(int &action) { #endif #endif // Controller 6 #if FEATURE_CONTROLLER == CONTROLLER_RADDS +#undef SDSS #define SDSS 10 +#undef SPI_PIN #define SPI_PIN 77 +#undef SPI_CHAN #define SPI_CHAN 0 #define UI_HAS_KEYS 1 #define UI_HAS_BACK_KEY 1 @@ -979,6 +1149,7 @@ void uiCheckSlowKeys(int &action) { #define BEEPER_TYPE 1 #define UI_COLS 20 #define UI_ROWS 4 +#undef BEEPER_PIN #define BEEPER_PIN 41 #define UI_DISPLAY_RS_PIN 42 #define UI_DISPLAY_RW_PIN -1 @@ -1004,13 +1175,13 @@ void uiInitKeys() { UI_KEYS_INIT_BUTTON_LOW(UI_ENCODER_CLICK); // push button, connects gnd to pin UI_KEYS_INIT_BUTTON_LOW(UI_BUTTON_BACK); } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { UI_KEYS_CLICKENCODER_LOW(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_BUTTON_BACK,UI_ACTION_BACK); } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif #endif // Controller 7 @@ -1036,6 +1207,7 @@ void uiCheckSlowKeys(int &action) {} #endif #ifdef PiBot_V_1_4 +#undef BEEPER_PIN #define BEEPER_PIN 31 #define UI_DISPLAY_RS_PIN 45 #define UI_DISPLAY_RW_PIN -1 @@ -1061,6 +1233,7 @@ void uiCheckSlowKeys(int &action) {} #endif #if PiBot_V_1_4==true || PiBot_V_1_6==true +#undef BEEPER_PIN #define BEEPER_PIN 37 #define UI_DISPLAY_RS_PIN 16 #define UI_DISPLAY_RW_PIN -1 @@ -1086,6 +1259,7 @@ void uiCheckSlowKeys(int &action) {} #endif #if PiBot_V_2_0 +#undef BEEPER_PIN #define BEEPER_PIN 16 #define UI_DISPLAY_RS_PIN 43 #define UI_DISPLAY_RW_PIN -1 @@ -1101,15 +1275,18 @@ void uiCheckSlowKeys(int &action) {} #define UI_ENCODER_A 37 #define UI_ENCODER_B 36 -#define UI_ENCODER_CLICK 69 ////***Vick BTN -#define UI_RESET_PIN -1 ////**** if you want, you can get the CNC Pin used 11 +// Vick BTN +#define UI_ENCODER_CLICK 69 +// if you want, you can get the CNC Pin used 11 +#define UI_RESET_PIN -1 #define UI_DELAYPERCHAR 320 #define UI_BUTTON_OK 47 #define UI_BUTTON_NEXT 46 #define UI_BUTTON_PREVIOUS 45 #define UI_BUTTON_BACK 44 -#define UI_BUTTON_SD_PRINT 70 ////**** if you want, you can get the CNC Pin used 10 +// if you want, you can get the CNC Pin used 10 +#define UI_BUTTON_SD_PRINT 70 #endif #ifdef UI_MAIN @@ -1120,7 +1297,7 @@ void uiInitKeys() { UI_KEYS_INIT_BUTTON_LOW(UI_BUTTON_BACK); UI_KEYS_INIT_BUTTON_LOW(UI_BUTTON_SD_PRINT); } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { UI_KEYS_BUTTON_LOW(UI_BUTTON_OK,UI_ACTION_OK); // push button, connects gnd to pin UI_KEYS_BUTTON_LOW(UI_BUTTON_NEXT,UI_ACTION_NEXT); // push button, connects gnd to pin UI_KEYS_BUTTON_LOW(UI_BUTTON_PREVIOUS,UI_ACTION_PREVIOUS); // push button, connects gnd to pin @@ -1128,7 +1305,7 @@ void uiCheckKeys(int &action) { UI_KEYS_BUTTON_LOW(UI_BUTTON_SD_PRINT,UI_ACTION_SD_PRINT ); // push button, connects gnd to pin } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif #endif @@ -1139,8 +1316,10 @@ void uiCheckSlowKeys(int &action) {} #define UI_DISPLAY_CHARSET 1 #define UI_COLS 20 #define UI_ROWS 4 -#define UI_ENCODER_SPEED 2 +#define UI_ENCODER_SPEED 2 +#undef BEEPER_TYPE #define BEEPER_TYPE 0 +#undef BEEPER_PIN #define BEEPER_PIN -1 #define UI_DISPLAY_RS_PIN 16 #define UI_DISPLAY_RW_PIN -1 @@ -1158,17 +1337,17 @@ void uiCheckSlowKeys(int &action) {} #define UI_ENCODER_CLICK 31 #define UI_DELAYPERCHAR 50 #define UI_INVERT_MENU_DIRECTION 0 -#if UI_MAIN +#ifdef UI_MAIN void uiInitKeys() { 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 } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &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 } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif #endif // Controller 12 @@ -1180,6 +1359,7 @@ void uiCheckSlowKeys(int &action) {} #define UI_COLS 20 #define UI_ROWS 4 #define BEEPER_TYPE 1 +#undef BEEPER_PIN #define BEEPER_PIN 79 #define UI_DISPLAY_RS_PIN 70 #define UI_DISPLAY_RW_PIN -1 @@ -1198,19 +1378,19 @@ void uiCheckSlowKeys(int &action) {} #define UI_KILL_PIN 80 #define UI_DELAYPERCHAR 50 #define UI_INVERT_MENU_DIRECTION 0 -#if UI_MAIN +#ifdef UI_MAIN void uiInitKeys() { UI_KEYS_INIT_CLICKENCODER_LOW(UI_ENCODER_A,UI_ENCODER_B); UI_KEYS_INIT_BUTTON_LOW(UI_ENCODER_CLICK); UI_KEYS_INIT_BUTTON_LOW(UI_KILL_PIN); } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { UI_KEYS_CLICKENCODER_LOW_REV(UI_ENCODER_A,UI_ENCODER_B); UI_KEYS_BUTTON_LOW(UI_ENCODER_CLICK,UI_ACTION_OK); UI_KEYS_BUTTON_LOW(UI_KILL_PIN,UI_ACTION_KILL); } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif #endif // Controller 13 @@ -1247,22 +1427,22 @@ void uiCheckSlowKeys(int &action) {} #ifdef UI_MAIN void uiInitKeys() {} -void uiCheckKeys(int &action) {} +void uiCheckKeys(uint16_t &action) {} inline void uiCheckSlowEncoder() { HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_WRITE); HAL::i2cWrite(0x12); // GIOA HAL::i2cStop(); HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_READ); -unsigned int keymask = HAL::i2cReadAck(); +uint16_t keymask = HAL::i2cReadAck(); keymask = keymask + (HAL::i2cReadNak()<<8); HAL::i2cStop(); } -void uiCheckSlowKeys(int &action) { +void uiCheckSlowKeys(uint16_t &action) { HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_WRITE); HAL::i2cWrite(0x12); // GPIOA HAL::i2cStop(); HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_READ); -unsigned int keymask = HAL::i2cReadAck(); +uint16_t keymask = HAL::i2cReadAck(); keymask = keymask + (HAL::i2cReadNak()<<8); HAL::i2cStop(); UI_KEYS_I2C_BUTTON_LOW(_BV(4),UI_ACTION_OK); // push button, connects gnd to pin @@ -1311,6 +1491,7 @@ UI_KEYS_I2C_BUTTON_LOW(_BV(2),UI_ACTION_NEXT); // down button #define UI_DISPLAY_D5_PIN _BV(11) #define UI_DISPLAY_D6_PIN _BV(10) #define UI_DISPLAY_D7_PIN _BV(9) +#undef BEEPER_PIN #define BEEPER_PIN _BV(5) #define UI_I2C_HEATBED_LED _BV(8) #define UI_I2C_HOTEND_LED _BV(7) @@ -1322,14 +1503,14 @@ void uiInitKeys() { UI_KEYS_INIT_BUTTON_LOW(30); // push button, connects gnd to pin } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { UI_KEYS_CLICKENCODER_LOW_REV(10,11); // click encoder on pins 47 and 45. Phase is connected with gnd for signals. UI_KEYS_BUTTON_LOW(30,UI_ACTION_OK); // push button, connects gnd to pin } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif // UI_MAIN #endif // Controller 15 @@ -1381,8 +1562,9 @@ void uiCheckSlowKeys(int &action) {} #define UI_FONT_SMALL_HEIGHT 7 #define UI_FONT_DEFAULT repetier_6x10 #define UI_FONT_SMALL repetier_5x7 -#define UI_FONT_SMALL_WIDTH 5 //smaller font for status display -#define UI_ANIMATION false // Animations are too slow +#define UI_FONT_SMALL_WIDTH 5 //smaller font for status display +#undef UI_ANIMATION +#define UI_ANIMATION 0 // Animations are too slow #endif #ifdef UI_MAIN @@ -1408,6 +1590,7 @@ void ui_check_slow_keys(int &action) {} #define UI_COLS 20 #define UI_ROWS 4 #define BEEPER_TYPE 1 +#undef BEEPER_PIN #define BEEPER_PIN -1 #define UI_DISPLAY_RS_PIN 1 #define UI_DISPLAY_RW_PIN -1 @@ -1435,21 +1618,21 @@ void ui_check_slow_keys(int &action) {} #define USER_KEY4_PIN -1 #define USER_KEY4_ACTION UI_ACTION_DUMMY -#if UI_MAIN +#ifdef UI_MAIN void uiInitKeys() { UI_KEYS_INIT_CLICKENCODER_LOW(UI_ENCODER_A,UI_ENCODER_B); UI_KEYS_INIT_BUTTON_LOW(UI_ENCODER_CLICK); } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { UI_KEYS_CLICKENCODER_LOW_REV(UI_ENCODER_A,UI_ENCODER_B); UI_KEYS_BUTTON_LOW(UI_ENCODER_CLICK,UI_ACTION_OK); } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif #endif // CONTROLLER_GATE_3NOVATICA -#if FEATURE_CONTROLLER == CONTROLLER_SPARKLCD +#if FEATURE_CONTROLLER == CONTROLLER_SPARKLCD || FEATURE_CONTROLLER == CONTROLLER_SPARKLCD_ADAPTER #if MOTHERBOARD != 402 #error This config only works with RADDS motherboard! #endif @@ -1461,51 +1644,67 @@ void uiCheckSlowKeys(int &action) {} //select font size #define UI_FONT_6X10 //default font -#ifdef UI_FONT_6X10 #define UI_FONT_WIDTH 6 #define UI_FONT_HEIGHT 10 #define UI_FONT_SMALL_HEIGHT 7 #define UI_FONT_DEFAULT repetier_6x10 #define UI_FONT_SMALL repetier_5x7 -#define UI_FONT_SMALL_WIDTH 5 //smaller font for status display -#define UI_ANIMATION false // Animations are too slow -#endif +#define UI_FONT_SMALL_WIDTH 5 //smaller font for status display +#undef UI_ANIMATION +#define UI_ANIMATION 0 // Animations are too slow +#define UI_DELAYPERCHAR 50 +#define UI_HAS_KEYS 1 +#define UI_HAS_BACK_KEY 0 +#define UI_INVERT_MENU_DIRECTION 0 +#define UI_HAS_I2C_ENCODER 0 +#define UI_ENCODER_SPEED 2 //calculate rows and cols available with current font #define UI_COLS (UI_LCD_WIDTH/UI_FONT_WIDTH) #define UI_ROWS (UI_LCD_HEIGHT/UI_FONT_HEIGHT) -#define UI_DISPLAY_RS_PIN 25 // PINK.1, 88, D_RS +#define UI_DISPLAY_D0_PIN -1 +#define UI_DISPLAY_D1_PIN -1 +#define UI_DISPLAY_D2_PIN -1 +#define UI_DISPLAY_D3_PIN -1 +#define UI_DISPLAY_D5_PIN -1 +#define UI_DISPLAY_D6_PIN -1 +#define UI_DISPLAY_D7_PIN -1 + +#if FEATURE_CONTROLLER == CONTROLLER_SPARKLCD +// PINK.1, 88, D_RS +#define UI_DISPLAY_RS_PIN 25 #define UI_DISPLAY_RW_PIN -1 -#define UI_DISPLAY_ENABLE_PIN 27 // PINK.3, 86, D_E -#define UI_DISPLAY_D0_PIN -1 // PINF.5, 92, D_D4 -#define UI_DISPLAY_D1_PIN -1 // PINK.2, 87, D_D5 -#define UI_DISPLAY_D2_PIN -1 // PINL.5, 40, D_D6 -#define UI_DISPLAY_D3_PIN -1 // PINK.4, 85, D_D7 -#define UI_DISPLAY_D4_PIN 29 // PINF.5, 92, D_D4 -#define UI_DISPLAY_D5_PIN -1 // PINK.2, 87, D_D5 -#define UI_DISPLAY_D6_PIN -1 // PINL.5, 40, D_D6 -#define UI_DISPLAY_D7_PIN -1 // PINK.4, 85, D_D7 -#define UI_DELAYPERCHAR 50 -#define UI_HAS_KEYS 1 -#define UI_HAS_BACK_KEY 0 -#define UI_INVERT_MENU_DIRECTION 0 -#define UI_HAS_I2C_ENCODER 0 -#define UI_ENCODER_SPEED 1 +// PINK.3, 86, D_E +#define UI_DISPLAY_ENABLE_PIN 27 +// PINF.5, 92, D_D4 + // PINF.5, 92, D_D4 +#define UI_DISPLAY_D4_PIN 29 #define UI_ENCODER_A 35 #define UI_ENCODER_B 33 #define UI_ENCODER_CLICK 37 +#else +// PINK.1, 88, D_RS +#define UI_DISPLAY_RS_PIN 44 +#define UI_DISPLAY_RW_PIN -1 +// PINK.3, 86, D_E +#define UI_DISPLAY_ENABLE_PIN 45 +#define UI_DISPLAY_D4_PIN 46 +#define UI_ENCODER_A 52 +#define UI_ENCODER_B 50 +#define UI_ENCODER_CLICK 48 +#endif #ifdef UI_MAIN void uiInitKeys() { 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; } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { UI_KEYS_CLICKENCODER_LOW(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 } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif #endif // CONTROLLER_sparkLCD @@ -1525,7 +1724,8 @@ void uiCheckSlowKeys(int &action) {} #define UI_FONT_SMALL_HEIGHT 7 #define UI_FONT_DEFAULT repetier_6x10 #define UI_FONT_SMALL repetier_5x7 -#define UI_FONT_SMALL_WIDTH 5 //smaller font for status display +#define UI_FONT_SMALL_WIDTH 5 //smaller font for status display +#undef UI_ANIMATION #define UI_ANIMATION 0 // Animations are too slow //calculate rows and cols available with current font @@ -1533,6 +1733,7 @@ void uiCheckSlowKeys(int &action) {} #define UI_ROWS (UI_LCD_HEIGHT/UI_FONT_HEIGHT) #define UI_DISPLAY_CHARSET 3 #define UI_INVERT_MENU_DIRECTION 0 +#undef UI_ENCODER_SPEED #define UI_ENCODER_SPEED 2 #define SDCARDDETECT -1 #define UI_DISPLAY_RW_PIN -1 @@ -1547,9 +1748,12 @@ void uiCheckSlowKeys(int &action) {} #if MOTHERBOARD == 34 // Azteeg X3 #define SDCARDDETECT 49 // sd card detect as shown on drawing +#undef BEEPER_PIN #define BEEPER_PIN 33 -#define UI_DISPLAY_D5_PIN 31 // Display A0 -#define UI_DISPLAY_RS_PIN 32 // Display CS +// Display A0 +#define UI_DISPLAY_D5_PIN 31 +// Display CS +#define UI_DISPLAY_RS_PIN 32 #define UI_ENCODER_A 22 #define UI_ENCODER_B 7 #define UI_ENCODER_CLICK 12 @@ -1561,10 +1765,15 @@ void uiCheckSlowKeys(int &action) {} #elif MOTHERBOARD == 35 // Azteeg X3 Pro #undef SDCARDDETECT -#define SDCARDDETECT 49 // sd card detect as shown on drawing -#define BEEPER_PIN 47 // 33 is the on board beeper -#define UI_DISPLAY_D5_PIN 44 // Display A0 -#define UI_DISPLAY_RS_PIN 45 // Display CS +// sd card detect as shown on drawing +#define SDCARDDETECT 49 +#undef BEEPER_PIN +// 33 is the on board beeper +#define BEEPER_PIN 47 +// Display A0 +#define UI_DISPLAY_D5_PIN 44 +// Display CS +#define UI_DISPLAY_RS_PIN 45 #define UI_ENCODER_A 22 #define UI_ENCODER_B 7 #define UI_ENCODER_CLICK 39 @@ -1576,9 +1785,12 @@ void uiCheckSlowKeys(int &action) {} #elif MOTHERBOARD == 301 // RAMBO #define SDCARDDETECT 72 // sd card detect as shown on drawing +#undef BEEPER_PIN #define BEEPER_PIN 33 -#define UI_DISPLAY_D5_PIN 70 // Display A0 -#define UI_DISPLAY_RS_PIN 71 // Display CS +// Display A0 +#define UI_DISPLAY_D5_PIN 70 +// Display CS +#define UI_DISPLAY_RS_PIN 71 #define UI_ENCODER_A 85 #define UI_ENCODER_B 84 #define UI_ENCODER_CLICK 83 @@ -1588,12 +1800,15 @@ void uiCheckSlowKeys(int &action) {} #define BLUE_STATUS_LED 32 #elif MOTHERBOARD == 9 || MOTHERBOARD == 92 // Printboard - -#define SDCARDDETECT 72 // sd card detect as shown on drawing +// sd card detect as shown on drawing +#define SDCARDDETECT 72 #define SDSS 45 +#undef BEEPER_PIN #define BEEPER_PIN 32 -#define UI_DISPLAY_D5_PIN 42 // Display A0 -#define UI_DISPLAY_RS_PIN 43 // Display CS +// Display A0 +#define UI_DISPLAY_D5_PIN 42 +// Display CS +#define UI_DISPLAY_RS_PIN 43 #define UI_ENCODER_A 26 #define UI_ENCODER_B 27 #define UI_ENCODER_CLICK 47 @@ -1602,12 +1817,54 @@ void uiCheckSlowKeys(int &action) {} #define RED_STATUS_LED 12 #define BLUE_STATUS_LED 10 +#elif MOTHERBOARD == 402 // RADDS + +#undef SDCARDDETECT +#define SDCARDDETECT 14 // sd card detect as shown on drawing +//#undef SDSS +//#define SDSS 4 +//#define SPI_PIN 87 +//#define SPI_CHAN 1 +/*#define SDSS 10 +#undef SPI_PIN +#define SPI_PIN 77 +#undef SPI_CHAN +#define SPI_CHAN 0 + +#undef SDSUPPORT +#define SDSUPPORT 0 // sd card does not work reliable due to spi charing +*/ + +#undef BEEPER_PIN +#define BEEPER_PIN 41 +// Hardware SPI creates artifacts on display, so we use software SPI +#undef U8GLIB_ST7565_NHD_C2832_HW_SPI +#define U8GLIB_ST7565_NHD_C2832_SW_SPI +// MOSI 43 +#define UI_DISPLAY_ENABLE_PIN 31 +//#define UI_DISPLAY_ENABLE_PIN 75 +//76 // SCK pin +#define UI_DISPLAY_D4_PIN 33 //44 +// Display A0 => LCD RS +#define UI_DISPLAY_D5_PIN 42 +// Display CS => CS0 //4 //10 +#define UI_DISPLAY_RS_PIN 35 //10 +#define UI_ENCODER_A 50 +#define UI_ENCODER_B 52 +#define UI_ENCODER_CLICK 48 +#define UI_RESET_PIN -1 +#define RED_BLUE_STATUS_LEDS +// PWM2 Pin +#define RED_STATUS_LED 6 +// PWM1 Pin +#define BLUE_STATUS_LED 5 + #else #error No predefined Viki 2 mapping for your board available #endif -#if UI_MAIN +#ifdef UI_MAIN void uiInitKeys() { 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 @@ -1615,7 +1872,7 @@ void uiInitKeys() { UI_KEYS_INIT_BUTTON_LOW(UI_RESET_PIN); // Kill pin #endif } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { UI_KEYS_CLICKENCODER_LOW_REV(UI_ENCODER_B,UI_ENCODER_A); UI_KEYS_BUTTON_LOW(UI_ENCODER_CLICK,UI_ACTION_OK); #if UI_RESET_PIN > -1 @@ -1623,28 +1880,76 @@ void uiCheckKeys(int &action) { #endif } inline void uiCheckSlowEncoder() {} -void uiCheckSlowKeys(int &action) {} +void uiCheckSlowKeys(uint16_t &action) {} #endif #endif // Controller VIKI 2 +#if FEATURE_CONTROLLER == CONTROLLER_LCD_MP_PHARAOH_DUE +#define UI_DISPLAY_TYPE 1 +#define UI_COLS 20 +#define UI_ROWS 4 +#define UI_HAS_KEYS 1 +#define UI_HAS_BACK_KEY 0 +#define UI_INVERT_MENU_DIRECTION 1 +#define UI_DISPLAY_CHARSET 1 +#define UI_DISPLAY_RS_PIN 42 // PINK.1, 88, D_RS +#define UI_DISPLAY_RW_PIN -1 +#define UI_DISPLAY_ENABLE_PIN 43 // PINK.3, 86, D_E +#define UI_DISPLAY_D0_PIN 44 // PINF.5, 92, D_D4 +#define UI_DISPLAY_D1_PIN 45 // PINK.2, 87, D_D5 +#define UI_DISPLAY_D2_PIN 46 // PINL.5, 40, D_D6 +#define UI_DISPLAY_D3_PIN 47 // PINK.4, 85, D_D7 +#define UI_DISPLAY_D4_PIN 44 // PINF.5, 92, D_D4 +#define UI_DISPLAY_D5_PIN 45 // PINK.2, 87, D_D5 +#define UI_DISPLAY_D6_PIN 46 // PINL.5, 40, D_D6 +#define UI_DISPLAY_D7_PIN 47 // PINK.4, 85, D_D7 +#define UI_DELAYPERCHAR 50 + +#ifdef UI_MAIN +void uiInitKeys() { + UI_KEYS_INIT_BUTTON_LOW(33); // push button, connects gnd to pin + UI_KEYS_INIT_BUTTON_LOW(31); + UI_KEYS_INIT_BUTTON_LOW(29); + UI_KEYS_INIT_BUTTON_LOW(37); + UI_KEYS_INIT_BUTTON_LOW(35); + UI_KEYS_INIT_BUTTON_LOW(X_MIN_PIN); +} +void uiCheckKeys(uint16_t &action) { + UI_KEYS_BUTTON_LOW(33,UI_ACTION_OK); //35 push button, connects gnd to pin + UI_KEYS_BUTTON_LOW(35,UI_ACTION_PREVIOUS); //34 push button, connects gnd to pin + UI_KEYS_BUTTON_LOW(31,UI_ACTION_NEXT); //43 push button, connects gnd to pin + UI_KEYS_BUTTON_LOW(29,UI_ACTION_BACK); //44 push button, connects gnd to pin + UI_KEYS_BUTTON_LOW(37,UI_ACTION_MENU_SDCARD ); //33 push button, connects gnd to pin + UI_KEYS_BUTTON_LOW(X_MIN_PIN,UI_ACTION_RESET /*UI_ACTION_PAUSE*/); +} +inline void uiCheckSlowEncoder() {} +void uiCheckSlowKeys(uint16_t &action) {} + +#endif +#endif // CONTROLLER_LCD_MP_PHARAOH_DUE + +#ifndef UI_HAS_I2C_ENCODER +#define UI_HAS_I2C_ENCODER 0 +#endif + #if FEATURE_CONTROLLER != NO_CONTROLLER -#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 -#if UI_DISPLAY_TYPE!=DISPLAY_GAMEDUINO2 -#error Unknown combination off rows/columns - define UI_LINE_OFFSETS manually. -#else -#define UI_LINE_OFFSETS {} // dummy never used -#endif -#endif -#else -#define UI_LINE_OFFSETS {0,0x40,0x10,0x50} // 2x16, 2x20, 2x24 -#endif -#include "uilang.h" + #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 + #if UI_DISPLAY_TYPE!=DISPLAY_GAMEDUINO2 + #error Unknown combination off rows/columns - define UI_LINE_OFFSETS manually. + #else + #define UI_LINE_OFFSETS {} // dummy never used + #endif + #endif + #else + #define UI_LINE_OFFSETS {0,0x40,0x10,0x50} // 2x16, 2x20, 2x24 + #endif + #include "uilang.h" #endif #define UI_VERSION_STRING "Repetier " REPETIER_VERSION @@ -1673,7 +1978,9 @@ void uiCheckSlowKeys(int &action) {} #define UI_MEDIUM uid.mediumAction(); #define UI_SLOW(allowMoves) uid.slowAction(allowMoves); #define UI_STATUS(status) uid.setStatusP(PSTR(status)); +#define UI_STATUS_F(status) uid.setStatusP(status); #define UI_STATUS_UPD(status) {uid.setStatusP(PSTR(status));uid.refreshPage();} +#define UI_STATUS_UPD_F(status) {uid.setStatusP(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(status) uid.setStatusP(PSTR(status),true); @@ -1689,8 +1996,10 @@ void uiCheckSlowKeys(int &action) {} #define UI_MEDIUM {} #define UI_SLOW(allowMoves) {} #define UI_STATUS(status) {} +#define UI_STATUS_F(status) {} #define UI_STATUS_RAM(status) {} #define UI_STATUS_UPD(status) {} +#define UI_STATUS_UPD_F(status) {} #define UI_STATUS_UPD_RAM(status) {} #define UI_CLEAR_STATUS {} #define UI_ERROR(msg) {} @@ -1711,8 +2020,9 @@ void uiCheckSlowKeys(int &action) {} extern void beep(uint8_t duration,uint8_t count); - -static void ui_check_Ukeys(int &action) { +#if (defined(USER_KEY1_PIN) && USER_KEY1_PIN > -1 && defined(USER_KEY1_ACTION)) || (defined(USER_KEY2_PIN) && USER_KEY2_PIN > -1 && defined(USER_KEY2_ACTION)) || (defined(USER_KEY3_PIN) && USER_KEY3_PIN > -1 && defined(USER_KEY3_ACTION)) || (defined(USER_KEY4_PIN) && USER_KEY4_PIN > -1 && defined(USER_KEY4_ACTION)) +#define HAS_USER_KEYS +static void ui_check_Ukeys(uint16_t &action) { #if defined(USER_KEY1_PIN) && USER_KEY1_PIN > -1 && defined(USER_KEY1_ACTION) UI_KEYS_BUTTON_LOW(USER_KEY1_PIN, USER_KEY1_ACTION); #endif @@ -1726,8 +2036,7 @@ static void ui_check_Ukeys(int &action) { UI_KEYS_BUTTON_LOW(USER_KEY4_PIN, USER_KEY4_ACTION); #endif } +#endif #endif - - diff --git a/Repetier/uiconfig.h b/Repetier/uiconfig.h index 6997a5f..693393d 100644 --- a/Repetier/uiconfig.h +++ b/Repetier/uiconfig.h @@ -101,30 +101,30 @@ What display type do you use? #define UI_DISPLAY_TYPE 5 #if UI_DISPLAY_TYPE == DISPLAY_U8G // Special case for graphic displays - -// You need to define which controller you use and set pins accodringly - -// For software spi assign these definitions + +// You need to define which controller you use and set pins accodringly + +// For software spi assign these definitions // SCK Pin: UI_DISPLAY_D4_PIN // Mosi Pin: UI_DISPLAY_ENABLE_PIN // CD Pin: UI_DISPLAY_RS_PIN - -// ST7920 with software SPI -#define U8GLIB_ST7920 -// SSD1306 with software SPI -//#define U8GLIB_SSD1306_SW_SPI -// SSD1306 over I2C using hardware I2C pins -//#define U8GLIB_SSD1306_I2C -// For the 8 bit ks0108 display you need to set these pins -// UI_DISPLAY_D0_PIN,UI_DISPLAY_D1_PIN,UI_DISPLAY_D2_PIN,UI_DISPLAY_D3_PIN,UI_DISPLAY_D4_PIN,UI_DISPLAY_D5_PIN,UI_DISPLAY_D6_PIN,UI_DISPLAY_D7_PIN -// UI_DISPLAY_ENABLE_PIN,UI_DISPLAY_CS1,UI_DISPLAY_CS2, -// UI_DISPLAY_DI,UI_DISPLAY_RW_PIN,UI_DISPLAY_RESET_PIN + +// ST7920 with software SPI +#define U8GLIB_ST7920 +// SSD1306 with software SPI +//#define U8GLIB_SSD1306_SW_SPI +// SSD1306 over I2C using hardware I2C pins +//#define U8GLIB_SSD1306_I2C +// For the 8 bit ks0108 display you need to set these pins +// UI_DISPLAY_D0_PIN,UI_DISPLAY_D1_PIN,UI_DISPLAY_D2_PIN,UI_DISPLAY_D3_PIN,UI_DISPLAY_D4_PIN,UI_DISPLAY_D5_PIN,UI_DISPLAY_D6_PIN,UI_DISPLAY_D7_PIN +// UI_DISPLAY_ENABLE_PIN,UI_DISPLAY_CS1,UI_DISPLAY_CS2, +// UI_DISPLAY_DI,UI_DISPLAY_RW_PIN,UI_DISPLAY_RESET_PIN //#define U8GLIB_KS0108 -//#define U8GLIB_KS0108_FAST -// UI_DISPLAY_RS_PIN = CS +//#define U8GLIB_KS0108_FAST +// UI_DISPLAY_RS_PIN = CS // UI_DISPLAY_D5_PIN = A0 -//#define U8GLIB_ST7565_NHD_C2832_HW_SPI - +//#define U8GLIB_ST7565_NHD_C2832_HW_SPI + #define UI_LCD_WIDTH 128 #define UI_LCD_HEIGHT 64 @@ -225,13 +225,13 @@ Define the pin #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 50 - -// Special pins for some u8g driven display - -#define UI_DISPLAY_CS1 59 -#define UI_DISPLAY_CS2 59 -#define UI_DISPLAY_DI 59 -#define UI_DISPLAY_RW_PIN 59 + +// Special pins for some u8g driven display + +#define UI_DISPLAY_CS1 59 +#define UI_DISPLAY_CS2 59 +#define UI_DISPLAY_DI 59 +#define UI_DISPLAY_RW_PIN 59 #define UI_DISPLAY_RESET_PIN 59 #endif @@ -378,7 +378,7 @@ void uiInitKeys() { // UI_KEYS_INIT_MATRIX(32,47,45,43,41,39,37,35); #endif } -void uiCheckKeys(int &action) { +void uiCheckKeys(uint16_t &action) { #if UI_HAS_KEYS!=0 //UI_KEYS_CLICKENCODER_LOW_REV(33,31); // click encoder on pins 47 and 45. Phase is connected with gnd for signals. @@ -402,7 +402,7 @@ inline void uiCheckSlowEncoder() { HAL::i2cWrite(0x12); // GIOA HAL::i2cStop(); HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_READ); - unsigned int keymask = HAL::i2cReadAck(); + uint16_t keymask = HAL::i2cReadAck(); keymask = keymask + (HAL::i2cReadNak()<<8); #endif HAL::i2cStop(); @@ -410,7 +410,7 @@ inline void uiCheckSlowEncoder() { 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 uiCheckSlowKeys(int &action) { +void uiCheckSlowKeys(uint16_t &action) { #if defined(UI_HAS_I2C_KEYS) && UI_HAS_KEYS!=0 #if UI_DISPLAY_I2C_CHIPTYPE==0 HAL::i2cStartWait(UI_I2C_KEY_ADDRESS+I2C_READ); @@ -421,7 +421,7 @@ void uiCheckSlowKeys(int &action) { HAL::i2cWrite(0x12); // GPIOA HAL::i2cStop(); HAL::i2cStartWait(UI_DISPLAY_I2C_ADDRESS+I2C_READ); - unsigned int keymask = HAL::i2cReadAck(); + uint16_t keymask = HAL::i2cReadAck(); keymask = keymask + (HAL::i2cReadNak()<<8); #endif HAL::i2cStop(); @@ -447,9 +447,7 @@ void uiCheckSlowKeys(int &action) { } #endif -#endif - - - - +#endif + + diff --git a/Repetier/uilang.cpp b/Repetier/uilang.cpp new file mode 100644 index 0000000..b1e94fa --- /dev/null +++ b/Repetier/uilang.cpp @@ -0,0 +1,6065 @@ +/* + 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 . + + 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 "Repetier.h" + +#if UI_DISPLAY_TYPE != NO_DISPLAY + +#if LANGUAGE_EN_ACTIVE+LANGUAGE_DE_ACTIVE+LANGUAGE_ES_ACTIVE+LANGUAGE_PT_ACTIVE+LANGUAGE_FR_ACTIVE+LANGUAGE_NL_ACTIVE+LANGUAGE_IT_ACTIVE+LANGUAGE_SE_ACTIVE+LANGUAGE_CZ_ACTIVE+LANGUAGE_PL_ACTIVE+LANGUAGE_TR_ACTIVE < 1 +#error No language for diplay selected +#endif // LANGUAGE_EN_ACTIVE + +#define TRANS(x) UI_STRING(F ## x,x) + +// Translations of ui + +#if LANGUAGE_EN_ACTIVE +TRANS(UI_TEXT_ON_EN); +TRANS(UI_TEXT_OFF_EN); +TRANS(UI_TEXT_NA_EN); +TRANS(UI_TEXT_YES_EN); +TRANS(UI_TEXT_NO_EN); +TRANS(UI_TEXT_PRINT_POS_EN); +TRANS(UI_TEXT_PRINTING_EN); +TRANS(UI_TEXT_IDLE_EN); +TRANS(UI_TEXT_NOSDCARD_EN); +TRANS(UI_TEXT_ERROR_EN); +TRANS(UI_TEXT_BACK_EN); +TRANS(UI_TEXT_QUICK_SETTINGS_EN); +TRANS(UI_TEXT_ERRORMSG_EN); +TRANS(UI_TEXT_CONFIGURATION_EN); +TRANS(UI_TEXT_POSITION_EN); +TRANS(UI_TEXT_EXTRUDER_EN); +TRANS(UI_TEXT_SD_CARD_EN); +TRANS(UI_TEXT_DEBUGGING_EN); +TRANS(UI_TEXT_HOME_DELTA_EN); +TRANS(UI_TEXT_HOME_ALL_EN); +TRANS(UI_TEXT_HOME_X_EN); +TRANS(UI_TEXT_HOME_Y_EN); +TRANS(UI_TEXT_HOME_Z_EN); +TRANS(UI_TEXT_PREHEAT_PLA_EN); +TRANS(UI_TEXT_PREHEAT_ABS_EN); +TRANS(UI_TEXT_LIGHTS_ONOFF_EN); +TRANS(UI_TEXT_COOLDOWN_EN); +TRANS(UI_TEXT_SET_TO_ORIGIN_EN); +TRANS(UI_TEXT_DISABLE_STEPPER_EN); +TRANS(UI_TEXT_X_POSITION_EN); +TRANS(UI_TEXT_X_POS_FAST_EN); +TRANS(UI_TEXT_Y_POSITION_EN); +TRANS(UI_TEXT_Y_POS_FAST_EN); +TRANS(UI_TEXT_Z_POSITION_EN); +TRANS(UI_TEXT_Z_POS_FAST_EN); +TRANS(UI_TEXT_E_POSITION_EN); +TRANS(UI_TEXT_BED_TEMP_EN); +TRANS(UI_TEXT_EXTR0_TEMP_EN); +TRANS(UI_TEXT_EXTR1_TEMP_EN); +TRANS(UI_TEXT_EXTR2_TEMP_EN); +TRANS(UI_TEXT_EXTR0_OFF_EN); +TRANS(UI_TEXT_EXTR1_OFF_EN); +TRANS(UI_TEXT_EXTR2_OFF_EN); +TRANS(UI_TEXT_EXTR0_SELECT_EN); +TRANS(UI_TEXT_EXTR1_SELECT_EN); +TRANS(UI_TEXT_EXTR2_SELECT_EN); +TRANS(UI_TEXT_EXTR_ORIGIN_EN); +TRANS(UI_TEXT_PRINT_X_EN); +TRANS(UI_TEXT_PRINT_Y_EN); +TRANS(UI_TEXT_PRINT_Z_EN); +TRANS(UI_TEXT_PRINT_Z_DELTA_EN); +TRANS(UI_TEXT_MOVE_X_EN); +TRANS(UI_TEXT_MOVE_Y_EN); +TRANS(UI_TEXT_MOVE_Z_EN); +TRANS(UI_TEXT_MOVE_Z_DELTA_EN); +TRANS(UI_TEXT_JERK_EN); +TRANS(UI_TEXT_ZJERK_EN); +TRANS(UI_TEXT_ACCELERATION_EN); +TRANS(UI_TEXT_STORE_TO_EEPROM_EN); +TRANS(UI_TEXT_LOAD_EEPROM_EN); +TRANS(UI_TEXT_DBG_ECHO_EN); +TRANS(UI_TEXT_DBG_INFO_EN); +TRANS(UI_TEXT_DBG_ERROR_EN); +TRANS(UI_TEXT_DBG_DRYRUN_EN); +TRANS(UI_TEXT_OPS_OFF_EN); +TRANS(UI_TEXT_OPS_CLASSIC_EN); +TRANS(UI_TEXT_OPS_FAST_EN); +TRANS(UI_TEXT_OPS_RETRACT_EN); +TRANS(UI_TEXT_OPS_BACKSLASH_EN); +TRANS(UI_TEXT_OPS_MINDIST_EN); +TRANS(UI_TEXT_OPS_MOVE_AFTER_EN); +TRANS(UI_TEXT_ANTI_OOZE_EN); +TRANS(UI_TEXT_PRINT_FILE_EN); +TRANS(UI_TEXT_PAUSE_PRINT_EN); +TRANS(UI_TEXT_CONTINUE_PRINT_EN); +TRANS(UI_TEXT_UNMOUNT_CARD_EN); +TRANS(UI_TEXT_MOUNT_CARD_EN); +TRANS(UI_TEXT_DELETE_FILE_EN); +TRANS(UI_TEXT_FEEDRATE_EN); +TRANS(UI_TEXT_FEED_MAX_X_EN); +TRANS(UI_TEXT_FEED_MAX_Y_EN); +TRANS(UI_TEXT_FEED_MAX_Z_EN); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_EN); +TRANS(UI_TEXT_FEED_HOME_X_EN); +TRANS(UI_TEXT_FEED_HOME_Y_EN); +TRANS(UI_TEXT_FEED_HOME_Z_EN); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_EN); +TRANS(UI_TEXT_ACTION_XPOSITION4A_EN); +TRANS(UI_TEXT_ACTION_XPOSITION4B_EN); +TRANS(UI_TEXT_ACTION_XPOSITION4C_EN); +TRANS(UI_TEXT_ACTION_XPOSITION4D_EN); +TRANS(UI_TEXT_ACTION_YPOSITION4A_EN); +TRANS(UI_TEXT_ACTION_YPOSITION4B_EN); +TRANS(UI_TEXT_ACTION_YPOSITION4C_EN); +TRANS(UI_TEXT_ACTION_YPOSITION4D_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_EN); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_EN); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_EN); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_EN); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_EN); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_EN); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_EN); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_EN); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_EN); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_EN); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_EN); +TRANS(UI_TEXT_ACTION_XPOSITION2A_EN); +TRANS(UI_TEXT_ACTION_XPOSITION2B_EN); +TRANS(UI_TEXT_ACTION_YPOSITION2A_EN); +TRANS(UI_TEXT_ACTION_YPOSITION2B_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_EN); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_EN); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_EN); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_EN); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_EN); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_EN); +TRANS(UI_TEXT_FANSPEED_EN); +TRANS(UI_TEXT_ACTION_FANSPEED_EN); +TRANS(UI_TEXT_FAN_OFF_EN); +TRANS(UI_TEXT_FAN_25_EN); +TRANS(UI_TEXT_FAN_50_EN); +TRANS(UI_TEXT_FAN_75_EN); +TRANS(UI_TEXT_FAN_FULL_EN); +TRANS(UI_TEXT_STEPPER_INACTIVE_EN); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_EN); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_EN); +TRANS(UI_TEXT_POWER_INACTIVE_EN); +TRANS(UI_TEXT_POWER_INACTIVE2A_EN); +TRANS(UI_TEXT_POWER_INACTIVE2B_EN); +TRANS(UI_TEXT_GENERAL_EN); +TRANS(UI_TEXT_BAUDRATE_EN); +TRANS(UI_TEXT_EXTR_STEPS_EN); +TRANS(UI_TEXT_EXTR_START_FEED_EN); +TRANS(UI_TEXT_EXTR_MAX_FEED_EN); +TRANS(UI_TEXT_EXTR_ACCEL_EN); +TRANS(UI_TEXT_EXTR_WATCH_EN); +TRANS(UI_TEXT_EXTR_ADVANCE_L_EN); +TRANS(UI_TEXT_EXTR_ADVANCE_K_EN); +TRANS(UI_TEXT_EXTR_MANAGER_EN); +TRANS(UI_TEXT_EXTR_PGAIN_EN); +TRANS(UI_TEXT_EXTR_DEADTIME_EN); +TRANS(UI_TEXT_EXTR_DMAX_DT_EN); +TRANS(UI_TEXT_EXTR_IGAIN_EN); +TRANS(UI_TEXT_EXTR_DGAIN_EN); +TRANS(UI_TEXT_EXTR_DMIN_EN); +TRANS(UI_TEXT_EXTR_DMAX_EN); +TRANS(UI_TEXT_EXTR_PMAX_EN); +TRANS(UI_TEXT_EXTR_XOFF_EN); +TRANS(UI_TEXT_EXTR_YOFF_EN); +TRANS(UI_TEXT_STRING_HM_BANGBANG_EN); +TRANS(UI_TEXT_STRING_HM_PID_EN); +TRANS(UI_TEXT_STRING_ACTION_EN); +TRANS(UI_TEXT_HEATING_EXTRUDER_EN); +TRANS(UI_TEXT_HEATING_BED_EN); +TRANS(UI_TEXT_KILLED_EN); +TRANS(UI_TEXT_STEPPER_DISABLED_EN); +TRANS(UI_TEXT_EEPROM_STOREDA_EN); +TRANS(UI_TEXT_EEPROM_STOREDB_EN); +TRANS(UI_TEXT_EEPROM_LOADEDA_EN); +TRANS(UI_TEXT_EEPROM_LOADEDB_EN); +TRANS(UI_TEXT_UPLOADING_EN); +TRANS(UI_TEXT_PAGE_BUFFER_EN); +TRANS(UI_TEXT_PAGE_EXTRUDER_EN); +TRANS(UI_TEXT_PAGE_EXTRUDER1_EN); +TRANS(UI_TEXT_PAGE_EXTRUDER2_EN); +TRANS(UI_TEXT_PAGE_EXTRUDER3_EN); +TRANS(UI_TEXT_PAGE_BED_EN); +TRANS(UI_TEXT_SPEED_MULTIPLY_EN); +TRANS(UI_TEXT_FLOW_MULTIPLY_EN); +TRANS(UI_TEXT_SHOW_MEASUREMENT_EN); +TRANS(UI_TEXT_RESET_MEASUREMENT_EN); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_EN); +TRANS(UI_TEXT_ZCALIB_EN); +TRANS(UI_TEXT_SET_P1_EN); +TRANS(UI_TEXT_SET_P2_EN); +TRANS(UI_TEXT_SET_P3_EN); +TRANS(UI_TEXT_CALCULATE_LEVELING_EN); +TRANS(UI_TEXT_LEVEL_EN); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_EN); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_EN); +TRANS(UI_TEXT_SD_REMOVED_EN); +TRANS(UI_TEXT_SD_INSERTED_EN); +TRANS(UI_TEXT_PRINTER_READY_EN); +TRANS(UI_TEXT_PRINTTIME_DAYS_EN); +TRANS(UI_TEXT_PRINTTIME_HOURS_EN); +TRANS(UI_TEXT_PRINTTIME_MINUTES_EN); +TRANS(UI_TEXT_PRINT_TIME_EN); +TRANS(UI_TEXT_PRINT_FILAMENT_EN); +TRANS(UI_TEXT_PRINTED_EN); +TRANS(UI_TEXT_POWER_EN); +TRANS(UI_TEXT_STRING_HM_DEADTIME_EN); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_EN); +TRANS(UI_TEXT_STOP_PRINT_EN); +TRANS(UI_TEXT_Z_BABYSTEPPING_EN); +TRANS(UI_TEXT_CHANGE_FILAMENT_EN); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_EN); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_EN); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_EN); +TRANS(UI_TEXT_CLICK_DONE_EN); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_EN); +TRANS(UI_TEXT_SERVOPOS_EN); +TRANS(UI_TEXT_IGNORE_M106_EN); +TRANS(UI_TEXT_WIZ_REHEAT1_EN); +TRANS(UI_TEXT_WIZ_REHEAT2_EN); +TRANS(UI_TEXT_WIZ_WAITTEMP1_EN); +TRANS(UI_TEXT_WIZ_WAITTEMP2_EN); +TRANS(UI_TEXT_EXTRUDER_JAM_EN); +TRANS(UI_TEXT_STANDBY_EN); +TRANS(UI_TEXT_BED_COATING_EN); +TRANS(UI_TEXT_BED_COATING_SET1_EN); +TRANS(UI_TEXT_BED_COATING_SET2_EN); +TRANS(UI_TEXT_NOCOATING_EN); +TRANS(UI_TEXT_BUILDTAK_EN); +TRANS(UI_TEXT_KAPTON_EN); +TRANS(UI_TEXT_BLUETAPE_EN); +TRANS(UI_TEXT_PETTAPE_EN); +TRANS(UI_TEXT_GLUESTICK_EN); +TRANS(UI_TEXT_CUSTOM_EN); +TRANS(UI_TEXT_COATING_CUSTOM_EN); +TRANS(UI_TEXT_LANGUAGE_EN); +TRANS(UI_TEXT_MAINPAGE6_1_EN); +TRANS(UI_TEXT_MAINPAGE6_2_EN); +TRANS(UI_TEXT_MAINPAGE6_3_EN); +TRANS(UI_TEXT_MAINPAGE6_4_EN); +TRANS(UI_TEXT_MAINPAGE6_5_EN); +TRANS(UI_TEXT_MAINPAGE6_6_EN); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_EN); +TRANS(UI_TEXT_MAINPAGE_BED_EN); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_EN); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_EN); +TRANS(UI_TEXT_MAINPAGE_XY_EN); +TRANS(UI_TEXT_PRINT_TIME_VALUE_EN); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_EN); +TRANS(UI_TEXT_METER_PRINTED_EN); +TRANS(UI_TEXT_STATUS_EN); +TRANS(UI_TEXT_EMPTY_EN); +TRANS(UI_TEXT_TEMP_SET_EN); +TRANS(UI_TEXT_CURRENT_TEMP_EN); +TRANS(UI_TEXT_COATING_THICKNESS_EN); +TRANS(UI_TEXT_EXTR3_TEMP_EN); +TRANS(UI_TEXT_EXTR4_TEMP_EN); +TRANS(UI_TEXT_EXTR5_TEMP_EN); +TRANS(UI_TEXT_EXTR3_OFF_EN); +TRANS(UI_TEXT_EXTR4_OFF_EN); +TRANS(UI_TEXT_EXTR5_OFF_EN); +TRANS(UI_TEXT_EXTR3_SELECT_EN); +TRANS(UI_TEXT_EXTR4_SELECT_EN); +TRANS(UI_TEXT_EXTR5_SELECT_EN); +TRANS(UI_TEXT_DITTO_0_EN); +TRANS(UI_TEXT_DITTO_1_EN); +TRANS(UI_TEXT_DITTO_2_EN); +TRANS(UI_TEXT_DITTO_3_EN); +TRANS(UI_TEXT_ZPROBE_HEIGHT_EN); +TRANS(UI_TEXT_OFFSETS_EN); +TRANS(UI_TEXT_X_OFFSET_EN); +TRANS(UI_TEXT_Y_OFFSET_EN); +TRANS(UI_TEXT_Z_OFFSET_EN); + + +PGM_P const translations_en[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_EN, + FUI_TEXT_OFF_EN, + FUI_TEXT_NA_EN, + FUI_TEXT_YES_EN, + FUI_TEXT_NO_EN, + FUI_TEXT_PRINT_POS_EN, + FUI_TEXT_PRINTING_EN, + FUI_TEXT_IDLE_EN, + FUI_TEXT_NOSDCARD_EN, + FUI_TEXT_ERROR_EN, + FUI_TEXT_BACK_EN, + FUI_TEXT_QUICK_SETTINGS_EN, + FUI_TEXT_ERRORMSG_EN, + FUI_TEXT_CONFIGURATION_EN, + FUI_TEXT_POSITION_EN, + FUI_TEXT_EXTRUDER_EN, + FUI_TEXT_SD_CARD_EN, + FUI_TEXT_DEBUGGING_EN, + FUI_TEXT_HOME_DELTA_EN, + FUI_TEXT_HOME_ALL_EN, + FUI_TEXT_HOME_X_EN, + FUI_TEXT_HOME_Y_EN, + FUI_TEXT_HOME_Z_EN, + FUI_TEXT_PREHEAT_PLA_EN, + FUI_TEXT_PREHEAT_ABS_EN, + FUI_TEXT_LIGHTS_ONOFF_EN, + FUI_TEXT_COOLDOWN_EN, + FUI_TEXT_SET_TO_ORIGIN_EN, + FUI_TEXT_DISABLE_STEPPER_EN, + FUI_TEXT_X_POSITION_EN, + FUI_TEXT_X_POS_FAST_EN, + FUI_TEXT_Y_POSITION_EN, + FUI_TEXT_Y_POS_FAST_EN, + FUI_TEXT_Z_POSITION_EN, + FUI_TEXT_Z_POS_FAST_EN, + FUI_TEXT_E_POSITION_EN, + FUI_TEXT_BED_TEMP_EN, + FUI_TEXT_EXTR0_TEMP_EN, + FUI_TEXT_EXTR1_TEMP_EN, + FUI_TEXT_EXTR2_TEMP_EN, + FUI_TEXT_EXTR0_OFF_EN, + FUI_TEXT_EXTR1_OFF_EN, + FUI_TEXT_EXTR2_OFF_EN, + FUI_TEXT_EXTR0_SELECT_EN, + FUI_TEXT_EXTR1_SELECT_EN, + FUI_TEXT_EXTR2_SELECT_EN, + FUI_TEXT_EXTR_ORIGIN_EN, + FUI_TEXT_PRINT_X_EN, + FUI_TEXT_PRINT_Y_EN, + FUI_TEXT_PRINT_Z_EN, + FUI_TEXT_PRINT_Z_DELTA_EN, + FUI_TEXT_MOVE_X_EN, + FUI_TEXT_MOVE_Y_EN, + FUI_TEXT_MOVE_Z_EN, + FUI_TEXT_MOVE_Z_DELTA_EN, + FUI_TEXT_JERK_EN, + FUI_TEXT_ZJERK_EN, + FUI_TEXT_ACCELERATION_EN, + FUI_TEXT_STORE_TO_EEPROM_EN, + FUI_TEXT_LOAD_EEPROM_EN, + FUI_TEXT_DBG_ECHO_EN, + FUI_TEXT_DBG_INFO_EN, + FUI_TEXT_DBG_ERROR_EN, + FUI_TEXT_DBG_DRYRUN_EN, + FUI_TEXT_OPS_OFF_EN, + FUI_TEXT_OPS_CLASSIC_EN, + FUI_TEXT_OPS_FAST_EN, + FUI_TEXT_OPS_RETRACT_EN, + FUI_TEXT_OPS_BACKSLASH_EN, + FUI_TEXT_OPS_MINDIST_EN, + FUI_TEXT_OPS_MOVE_AFTER_EN, + FUI_TEXT_ANTI_OOZE_EN, + FUI_TEXT_PRINT_FILE_EN, + FUI_TEXT_PAUSE_PRINT_EN, + FUI_TEXT_CONTINUE_PRINT_EN, + FUI_TEXT_UNMOUNT_CARD_EN, + FUI_TEXT_MOUNT_CARD_EN, + FUI_TEXT_DELETE_FILE_EN, + FUI_TEXT_FEEDRATE_EN, + FUI_TEXT_FEED_MAX_X_EN, + FUI_TEXT_FEED_MAX_Y_EN, + FUI_TEXT_FEED_MAX_Z_EN, + FUI_TEXT_FEED_MAX_Z_DELTA_EN, + FUI_TEXT_FEED_HOME_X_EN, + FUI_TEXT_FEED_HOME_Y_EN, + FUI_TEXT_FEED_HOME_Z_EN, + FUI_TEXT_FEED_HOME_Z_DELTA_EN, + FUI_TEXT_ACTION_XPOSITION4A_EN, + FUI_TEXT_ACTION_XPOSITION4B_EN, + FUI_TEXT_ACTION_XPOSITION4C_EN, + FUI_TEXT_ACTION_XPOSITION4D_EN, + FUI_TEXT_ACTION_YPOSITION4A_EN, + FUI_TEXT_ACTION_YPOSITION4B_EN, + FUI_TEXT_ACTION_YPOSITION4C_EN, + FUI_TEXT_ACTION_YPOSITION4D_EN, + FUI_TEXT_ACTION_ZPOSITION4A_EN, + FUI_TEXT_ACTION_ZPOSITION4B_EN, + FUI_TEXT_ACTION_ZPOSITION4C_EN, + FUI_TEXT_ACTION_ZPOSITION4D_EN, + FUI_TEXT_ACTION_XPOSITION_FAST4A_EN, + FUI_TEXT_ACTION_XPOSITION_FAST4B_EN, + FUI_TEXT_ACTION_XPOSITION_FAST4C_EN, + FUI_TEXT_ACTION_XPOSITION_FAST4D_EN, + FUI_TEXT_ACTION_YPOSITION_FAST4A_EN, + FUI_TEXT_ACTION_YPOSITION_FAST4B_EN, + FUI_TEXT_ACTION_YPOSITION_FAST4C_EN, + FUI_TEXT_ACTION_YPOSITION_FAST4D_EN, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_EN, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_EN, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_EN, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_EN, + FUI_TEXT_ACTION_EPOSITION_FAST2A_EN, + FUI_TEXT_ACTION_EPOSITION_FAST2B_EN, + FUI_TEXT_ACTION_XPOSITION2A_EN, + FUI_TEXT_ACTION_XPOSITION2B_EN, + FUI_TEXT_ACTION_YPOSITION2A_EN, + FUI_TEXT_ACTION_YPOSITION2B_EN, + FUI_TEXT_ACTION_ZPOSITION2A_EN, + FUI_TEXT_ACTION_ZPOSITION2B_EN, + FUI_TEXT_ACTION_XPOSITION_FAST2A_EN, + FUI_TEXT_ACTION_XPOSITION_FAST2B_EN, + FUI_TEXT_ACTION_YPOSITION_FAST2A_EN, + FUI_TEXT_ACTION_YPOSITION_FAST2B_EN, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_EN, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_EN, + FUI_TEXT_FANSPEED_EN, + FUI_TEXT_ACTION_FANSPEED_EN, + FUI_TEXT_FAN_OFF_EN, + FUI_TEXT_FAN_25_EN, + FUI_TEXT_FAN_50_EN, + FUI_TEXT_FAN_75_EN, + FUI_TEXT_FAN_FULL_EN, + FUI_TEXT_STEPPER_INACTIVE_EN, + FUI_TEXT_STEPPER_INACTIVE2A_EN, + FUI_TEXT_STEPPER_INACTIVE2B_EN, + FUI_TEXT_POWER_INACTIVE_EN, + FUI_TEXT_POWER_INACTIVE2A_EN, + FUI_TEXT_POWER_INACTIVE2B_EN, + FUI_TEXT_GENERAL_EN, + FUI_TEXT_BAUDRATE_EN, + FUI_TEXT_EXTR_STEPS_EN, + FUI_TEXT_EXTR_START_FEED_EN, + FUI_TEXT_EXTR_MAX_FEED_EN, + FUI_TEXT_EXTR_ACCEL_EN, + FUI_TEXT_EXTR_WATCH_EN, + FUI_TEXT_EXTR_ADVANCE_L_EN, + FUI_TEXT_EXTR_ADVANCE_K_EN, + FUI_TEXT_EXTR_MANAGER_EN, + FUI_TEXT_EXTR_PGAIN_EN, + FUI_TEXT_EXTR_DEADTIME_EN, + FUI_TEXT_EXTR_DMAX_DT_EN, + FUI_TEXT_EXTR_IGAIN_EN, + FUI_TEXT_EXTR_DGAIN_EN, + FUI_TEXT_EXTR_DMIN_EN, + FUI_TEXT_EXTR_DMAX_EN, + FUI_TEXT_EXTR_PMAX_EN, + FUI_TEXT_EXTR_XOFF_EN, + FUI_TEXT_EXTR_YOFF_EN, + FUI_TEXT_STRING_HM_BANGBANG_EN, + FUI_TEXT_STRING_HM_PID_EN, + FUI_TEXT_STRING_ACTION_EN, + FUI_TEXT_HEATING_EXTRUDER_EN, + FUI_TEXT_HEATING_BED_EN, + FUI_TEXT_KILLED_EN, + FUI_TEXT_STEPPER_DISABLED_EN, + FUI_TEXT_EEPROM_STOREDA_EN, + FUI_TEXT_EEPROM_STOREDB_EN, + FUI_TEXT_EEPROM_LOADEDA_EN, + FUI_TEXT_EEPROM_LOADEDB_EN, + FUI_TEXT_UPLOADING_EN, + FUI_TEXT_PAGE_BUFFER_EN, + FUI_TEXT_PAGE_EXTRUDER_EN, + FUI_TEXT_PAGE_EXTRUDER1_EN, + FUI_TEXT_PAGE_EXTRUDER2_EN, + FUI_TEXT_PAGE_EXTRUDER3_EN, + FUI_TEXT_PAGE_BED_EN, + FUI_TEXT_SPEED_MULTIPLY_EN, + FUI_TEXT_FLOW_MULTIPLY_EN, + FUI_TEXT_SHOW_MEASUREMENT_EN, + FUI_TEXT_RESET_MEASUREMENT_EN, + FUI_TEXT_SET_MEASURED_ORIGIN_EN, + FUI_TEXT_ZCALIB_EN, + FUI_TEXT_SET_P1_EN, + FUI_TEXT_SET_P2_EN, + FUI_TEXT_SET_P3_EN, + FUI_TEXT_CALCULATE_LEVELING_EN, + FUI_TEXT_LEVEL_EN, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_EN, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_EN, + FUI_TEXT_SD_REMOVED_EN, + FUI_TEXT_SD_INSERTED_EN, + FUI_TEXT_PRINTER_READY_EN, + FUI_TEXT_PRINTTIME_DAYS_EN, + FUI_TEXT_PRINTTIME_HOURS_EN, + FUI_TEXT_PRINTTIME_MINUTES_EN, + FUI_TEXT_PRINT_TIME_EN, + FUI_TEXT_PRINT_FILAMENT_EN, + FUI_TEXT_PRINTED_EN, + FUI_TEXT_POWER_EN, + FUI_TEXT_STRING_HM_DEADTIME_EN, + FUI_TEXT_STRING_HM_SLOWBANG_EN, + FUI_TEXT_STOP_PRINT_EN, + FUI_TEXT_Z_BABYSTEPPING_EN, + FUI_TEXT_CHANGE_FILAMENT_EN, + FUI_TEXT_WIZ_CH_FILAMENT1_EN, + FUI_TEXT_WIZ_CH_FILAMENT2_EN, + FUI_TEXT_WIZ_CH_FILAMENT3_EN, + FUI_TEXT_CLICK_DONE_EN, + FUI_TEXT_AUTOLEVEL_ONOFF_EN, + FUI_TEXT_SERVOPOS_EN, + FUI_TEXT_IGNORE_M106_EN, + FUI_TEXT_WIZ_REHEAT1_EN, + FUI_TEXT_WIZ_REHEAT2_EN, + FUI_TEXT_WIZ_WAITTEMP1_EN, + FUI_TEXT_WIZ_WAITTEMP2_EN, + FUI_TEXT_EXTRUDER_JAM_EN, + FUI_TEXT_STANDBY_EN, + FUI_TEXT_BED_COATING_EN, + FUI_TEXT_BED_COATING_SET1_EN, + FUI_TEXT_BED_COATING_SET2_EN, + FUI_TEXT_NOCOATING_EN, + FUI_TEXT_BUILDTAK_EN, + FUI_TEXT_KAPTON_EN, + FUI_TEXT_BLUETAPE_EN, + FUI_TEXT_PETTAPE_EN, + FUI_TEXT_GLUESTICK_EN, + FUI_TEXT_CUSTOM_EN, + FUI_TEXT_COATING_CUSTOM_EN, + FUI_TEXT_LANGUAGE_EN, + FUI_TEXT_MAINPAGE6_1_EN, + FUI_TEXT_MAINPAGE6_2_EN, + FUI_TEXT_MAINPAGE6_3_EN, + FUI_TEXT_MAINPAGE6_4_EN, + FUI_TEXT_MAINPAGE6_5_EN, + FUI_TEXT_MAINPAGE6_6_EN, + FUI_TEXT_MAINPAGE_TEMP_BED_EN, + FUI_TEXT_MAINPAGE_BED_EN, + FUI_TEXT_MAINPAGE_Z_BUF_EN, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_EN, + FUI_TEXT_MAINPAGE_XY_EN, + FUI_TEXT_PRINT_TIME_VALUE_EN, + FUI_TEXT_PRINT_FILAMENT_VALUE_EN, + FUI_TEXT_METER_PRINTED_EN, + FUI_TEXT_STATUS_EN, + FUI_TEXT_EMPTY_EN, + FUI_TEXT_TEMP_SET_EN, + FUI_TEXT_CURRENT_TEMP_EN, + FUI_TEXT_COATING_THICKNESS_EN, + FUI_TEXT_EXTR3_TEMP_EN, + FUI_TEXT_EXTR4_TEMP_EN, + FUI_TEXT_EXTR5_TEMP_EN, + FUI_TEXT_EXTR3_OFF_EN, + FUI_TEXT_EXTR4_OFF_EN, + FUI_TEXT_EXTR5_OFF_EN, + FUI_TEXT_EXTR3_SELECT_EN, + FUI_TEXT_EXTR4_SELECT_EN, + FUI_TEXT_EXTR5_SELECT_EN, + FUI_TEXT_DITTO_0_EN, + FUI_TEXT_DITTO_1_EN, + FUI_TEXT_DITTO_2_EN, + FUI_TEXT_DITTO_3_EN, + FUI_TEXT_ZPROBE_HEIGHT_EN, + FUI_TEXT_OFFSETS_EN, + FUI_TEXT_X_OFFSET_EN, + FUI_TEXT_Y_OFFSET_EN, + FUI_TEXT_Z_OFFSET_EN +}; +#define LANG_EN_TABLE translations_en +#else +#define LANG_EN_TABLE NULL +#endif // LANGUAGE_EN_ACTIVE + +#if LANGUAGE_DE_ACTIVE +TRANS(UI_TEXT_ON_DE); +TRANS(UI_TEXT_OFF_DE); +TRANS(UI_TEXT_NA_DE); +TRANS(UI_TEXT_YES_DE); +TRANS(UI_TEXT_NO_DE); +TRANS(UI_TEXT_PRINT_POS_DE); +TRANS(UI_TEXT_PRINTING_DE); +TRANS(UI_TEXT_IDLE_DE); +TRANS(UI_TEXT_NOSDCARD_DE); +TRANS(UI_TEXT_ERROR_DE); +TRANS(UI_TEXT_BACK_DE); +TRANS(UI_TEXT_QUICK_SETTINGS_DE); +TRANS(UI_TEXT_ERRORMSG_DE); +TRANS(UI_TEXT_CONFIGURATION_DE); +TRANS(UI_TEXT_POSITION_DE); +TRANS(UI_TEXT_EXTRUDER_DE); +TRANS(UI_TEXT_SD_CARD_DE); +TRANS(UI_TEXT_DEBUGGING_DE); +TRANS(UI_TEXT_HOME_DELTA_DE); +TRANS(UI_TEXT_HOME_ALL_DE); +TRANS(UI_TEXT_HOME_X_DE); +TRANS(UI_TEXT_HOME_Y_DE); +TRANS(UI_TEXT_HOME_Z_DE); +TRANS(UI_TEXT_PREHEAT_PLA_DE); +TRANS(UI_TEXT_PREHEAT_ABS_DE); +TRANS(UI_TEXT_LIGHTS_ONOFF_DE); +TRANS(UI_TEXT_COOLDOWN_DE); +TRANS(UI_TEXT_SET_TO_ORIGIN_DE); +TRANS(UI_TEXT_DISABLE_STEPPER_DE); +TRANS(UI_TEXT_X_POSITION_DE); +TRANS(UI_TEXT_X_POS_FAST_DE); +TRANS(UI_TEXT_Y_POSITION_DE); +TRANS(UI_TEXT_Y_POS_FAST_DE); +TRANS(UI_TEXT_Z_POSITION_DE); +TRANS(UI_TEXT_Z_POS_FAST_DE); +TRANS(UI_TEXT_E_POSITION_DE); +TRANS(UI_TEXT_BED_TEMP_DE); +TRANS(UI_TEXT_EXTR0_TEMP_DE); +TRANS(UI_TEXT_EXTR1_TEMP_DE); +TRANS(UI_TEXT_EXTR2_TEMP_DE); +TRANS(UI_TEXT_EXTR0_OFF_DE); +TRANS(UI_TEXT_EXTR1_OFF_DE); +TRANS(UI_TEXT_EXTR2_OFF_DE); +TRANS(UI_TEXT_EXTR0_SELECT_DE); +TRANS(UI_TEXT_EXTR1_SELECT_DE); +TRANS(UI_TEXT_EXTR2_SELECT_DE); +TRANS(UI_TEXT_EXTR_ORIGIN_DE); +TRANS(UI_TEXT_PRINT_X_DE); +TRANS(UI_TEXT_PRINT_Y_DE); +TRANS(UI_TEXT_PRINT_Z_DE); +TRANS(UI_TEXT_PRINT_Z_DELTA_DE); +TRANS(UI_TEXT_MOVE_X_DE); +TRANS(UI_TEXT_MOVE_Y_DE); +TRANS(UI_TEXT_MOVE_Z_DE); +TRANS(UI_TEXT_MOVE_Z_DELTA_DE); +TRANS(UI_TEXT_JERK_DE); +TRANS(UI_TEXT_ZJERK_DE); +TRANS(UI_TEXT_ACCELERATION_DE); +TRANS(UI_TEXT_STORE_TO_EEPROM_DE); +TRANS(UI_TEXT_LOAD_EEPROM_DE); +TRANS(UI_TEXT_DBG_ECHO_DE); +TRANS(UI_TEXT_DBG_INFO_DE); +TRANS(UI_TEXT_DBG_ERROR_DE); +TRANS(UI_TEXT_DBG_DRYRUN_DE); +TRANS(UI_TEXT_OPS_OFF_DE); +TRANS(UI_TEXT_OPS_CLASSIC_DE); +TRANS(UI_TEXT_OPS_FAST_DE); +TRANS(UI_TEXT_OPS_RETRACT_DE); +TRANS(UI_TEXT_OPS_BACKSLASH_DE); +TRANS(UI_TEXT_OPS_MINDIST_DE); +TRANS(UI_TEXT_OPS_MOVE_AFTER_DE); +TRANS(UI_TEXT_ANTI_OOZE_DE); +TRANS(UI_TEXT_PRINT_FILE_DE); +TRANS(UI_TEXT_PAUSE_PRINT_DE); +TRANS(UI_TEXT_CONTINUE_PRINT_DE); +TRANS(UI_TEXT_UNMOUNT_CARD_DE); +TRANS(UI_TEXT_MOUNT_CARD_DE); +TRANS(UI_TEXT_DELETE_FILE_DE); +TRANS(UI_TEXT_FEEDRATE_DE); +TRANS(UI_TEXT_FEED_MAX_X_DE); +TRANS(UI_TEXT_FEED_MAX_Y_DE); +TRANS(UI_TEXT_FEED_MAX_Z_DE); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_DE); +TRANS(UI_TEXT_FEED_HOME_X_DE); +TRANS(UI_TEXT_FEED_HOME_Y_DE); +TRANS(UI_TEXT_FEED_HOME_Z_DE); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_DE); +TRANS(UI_TEXT_ACTION_XPOSITION4A_DE); +TRANS(UI_TEXT_ACTION_XPOSITION4B_DE); +TRANS(UI_TEXT_ACTION_XPOSITION4C_DE); +TRANS(UI_TEXT_ACTION_XPOSITION4D_DE); +TRANS(UI_TEXT_ACTION_YPOSITION4A_DE); +TRANS(UI_TEXT_ACTION_YPOSITION4B_DE); +TRANS(UI_TEXT_ACTION_YPOSITION4C_DE); +TRANS(UI_TEXT_ACTION_YPOSITION4D_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_DE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_DE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_DE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_DE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_DE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_DE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_DE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_DE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_DE); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_DE); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_DE); +TRANS(UI_TEXT_ACTION_XPOSITION2A_DE); +TRANS(UI_TEXT_ACTION_XPOSITION2B_DE); +TRANS(UI_TEXT_ACTION_YPOSITION2A_DE); +TRANS(UI_TEXT_ACTION_YPOSITION2B_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_DE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_DE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_DE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_DE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_DE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_DE); +TRANS(UI_TEXT_FANSPEED_DE); +TRANS(UI_TEXT_ACTION_FANSPEED_DE); +TRANS(UI_TEXT_FAN_OFF_DE); +TRANS(UI_TEXT_FAN_25_DE); +TRANS(UI_TEXT_FAN_50_DE); +TRANS(UI_TEXT_FAN_75_DE); +TRANS(UI_TEXT_FAN_FULL_DE); +TRANS(UI_TEXT_STEPPER_INACTIVE_DE); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_DE); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_DE); +TRANS(UI_TEXT_POWER_INACTIVE_DE); +TRANS(UI_TEXT_POWER_INACTIVE2A_DE); +TRANS(UI_TEXT_POWER_INACTIVE2B_DE); +TRANS(UI_TEXT_GENERAL_DE); +TRANS(UI_TEXT_BAUDRATE_DE); +TRANS(UI_TEXT_EXTR_STEPS_DE); +TRANS(UI_TEXT_EXTR_START_FEED_DE); +TRANS(UI_TEXT_EXTR_MAX_FEED_DE); +TRANS(UI_TEXT_EXTR_ACCEL_DE); +TRANS(UI_TEXT_EXTR_WATCH_DE); +TRANS(UI_TEXT_EXTR_ADVANCE_L_DE); +TRANS(UI_TEXT_EXTR_ADVANCE_K_DE); +TRANS(UI_TEXT_EXTR_MANAGER_DE); +TRANS(UI_TEXT_EXTR_PGAIN_DE); +TRANS(UI_TEXT_EXTR_DEADTIME_DE); +TRANS(UI_TEXT_EXTR_DMAX_DT_DE); +TRANS(UI_TEXT_EXTR_IGAIN_DE); +TRANS(UI_TEXT_EXTR_DGAIN_DE); +TRANS(UI_TEXT_EXTR_DMIN_DE); +TRANS(UI_TEXT_EXTR_DMAX_DE); +TRANS(UI_TEXT_EXTR_PMAX_DE); +TRANS(UI_TEXT_EXTR_XOFF_DE); +TRANS(UI_TEXT_EXTR_YOFF_DE); +TRANS(UI_TEXT_STRING_HM_BANGBANG_DE); +TRANS(UI_TEXT_STRING_HM_PID_DE); +TRANS(UI_TEXT_STRING_ACTION_DE); +TRANS(UI_TEXT_HEATING_EXTRUDER_DE); +TRANS(UI_TEXT_HEATING_BED_DE); +TRANS(UI_TEXT_KILLED_DE); +TRANS(UI_TEXT_STEPPER_DISABLED_DE); +TRANS(UI_TEXT_EEPROM_STOREDA_DE); +TRANS(UI_TEXT_EEPROM_STOREDB_DE); +TRANS(UI_TEXT_EEPROM_LOADEDA_DE); +TRANS(UI_TEXT_EEPROM_LOADEDB_DE); +TRANS(UI_TEXT_UPLOADING_DE); +TRANS(UI_TEXT_PAGE_BUFFER_DE); +TRANS(UI_TEXT_PAGE_EXTRUDER_DE); +TRANS(UI_TEXT_PAGE_EXTRUDER1_DE); +TRANS(UI_TEXT_PAGE_EXTRUDER2_DE); +TRANS(UI_TEXT_PAGE_EXTRUDER3_DE); +TRANS(UI_TEXT_PAGE_BED_DE); +TRANS(UI_TEXT_SPEED_MULTIPLY_DE); +TRANS(UI_TEXT_FLOW_MULTIPLY_DE); +TRANS(UI_TEXT_SHOW_MEASUREMENT_DE); +TRANS(UI_TEXT_RESET_MEASUREMENT_DE); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_DE); +TRANS(UI_TEXT_ZCALIB_DE); +TRANS(UI_TEXT_SET_P1_DE); +TRANS(UI_TEXT_SET_P2_DE); +TRANS(UI_TEXT_SET_P3_DE); +TRANS(UI_TEXT_CALCULATE_LEVELING_DE); +TRANS(UI_TEXT_LEVEL_DE); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_DE); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_DE); +TRANS(UI_TEXT_SD_REMOVED_DE); +TRANS(UI_TEXT_SD_INSERTED_DE); +TRANS(UI_TEXT_PRINTER_READY_DE); +TRANS(UI_TEXT_PRINTTIME_DAYS_DE); +TRANS(UI_TEXT_PRINTTIME_HOURS_DE); +TRANS(UI_TEXT_PRINTTIME_MINUTES_DE); +TRANS(UI_TEXT_PRINT_TIME_DE); +TRANS(UI_TEXT_PRINT_FILAMENT_DE); +TRANS(UI_TEXT_PRINTED_DE); +TRANS(UI_TEXT_POWER_DE); +TRANS(UI_TEXT_STRING_HM_DEADTIME_DE); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_DE); +TRANS(UI_TEXT_STOP_PRINT_DE); +TRANS(UI_TEXT_Z_BABYSTEPPING_DE); +TRANS(UI_TEXT_CHANGE_FILAMENT_DE); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_DE); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_DE); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_DE); +TRANS(UI_TEXT_CLICK_DONE_DE); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_DE); +TRANS(UI_TEXT_SERVOPOS_DE); +TRANS(UI_TEXT_IGNORE_M106_DE); +TRANS(UI_TEXT_WIZ_REHEAT1_DE); +TRANS(UI_TEXT_WIZ_REHEAT2_DE); +TRANS(UI_TEXT_WIZ_WAITTEMP1_DE); +TRANS(UI_TEXT_WIZ_WAITTEMP2_DE); +TRANS(UI_TEXT_EXTRUDER_JAM_DE); +TRANS(UI_TEXT_STANDBY_DE); +TRANS(UI_TEXT_BED_COATING_DE); +TRANS(UI_TEXT_BED_COATING_SET1_DE); +TRANS(UI_TEXT_BED_COATING_SET2_DE); +TRANS(UI_TEXT_NOCOATING_DE); +TRANS(UI_TEXT_BUILDTAK_DE); +TRANS(UI_TEXT_KAPTON_DE); +TRANS(UI_TEXT_BLUETAPE_DE); +TRANS(UI_TEXT_PETTAPE_DE); +TRANS(UI_TEXT_GLUESTICK_DE); +TRANS(UI_TEXT_CUSTOM_DE); +TRANS(UI_TEXT_COATING_CUSTOM_DE); +TRANS(UI_TEXT_LANGUAGE_DE); +TRANS(UI_TEXT_MAINPAGE6_1_DE); +TRANS(UI_TEXT_MAINPAGE6_2_DE); +TRANS(UI_TEXT_MAINPAGE6_3_DE); +TRANS(UI_TEXT_MAINPAGE6_4_DE); +TRANS(UI_TEXT_MAINPAGE6_5_DE); +TRANS(UI_TEXT_MAINPAGE6_6_DE); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_DE); +TRANS(UI_TEXT_MAINPAGE_BED_DE); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_DE); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_DE); +TRANS(UI_TEXT_MAINPAGE_XY_DE); +TRANS(UI_TEXT_PRINT_TIME_VALUE_DE); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_DE); +TRANS(UI_TEXT_METER_PRINTED_DE); +TRANS(UI_TEXT_STATUS_DE); +TRANS(UI_TEXT_EMPTY_DE); +TRANS(UI_TEXT_TEMP_SET_DE); +TRANS(UI_TEXT_CURRENT_TEMP_DE); +TRANS(UI_TEXT_COATING_THICKNESS_DE); +TRANS(UI_TEXT_EXTR3_TEMP_DE); +TRANS(UI_TEXT_EXTR4_TEMP_DE); +TRANS(UI_TEXT_EXTR5_TEMP_DE); +TRANS(UI_TEXT_EXTR3_OFF_DE); +TRANS(UI_TEXT_EXTR4_OFF_DE); +TRANS(UI_TEXT_EXTR5_OFF_DE); +TRANS(UI_TEXT_EXTR3_SELECT_DE); +TRANS(UI_TEXT_EXTR4_SELECT_DE); +TRANS(UI_TEXT_EXTR5_SELECT_DE); +TRANS(UI_TEXT_DITTO_0_DE); +TRANS(UI_TEXT_DITTO_1_DE); +TRANS(UI_TEXT_DITTO_2_DE); +TRANS(UI_TEXT_DITTO_3_DE); +TRANS(UI_TEXT_ZPROBE_HEIGHT_DE); +TRANS(UI_TEXT_OFFSETS_DE); +TRANS(UI_TEXT_X_OFFSET_DE); +TRANS(UI_TEXT_Y_OFFSET_DE); +TRANS(UI_TEXT_Z_OFFSET_DE); + +PGM_P const translations_de[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_DE, + FUI_TEXT_OFF_DE, + FUI_TEXT_NA_DE, + FUI_TEXT_YES_DE, + FUI_TEXT_NO_DE, + FUI_TEXT_PRINT_POS_DE, + FUI_TEXT_PRINTING_DE, + FUI_TEXT_IDLE_DE, + FUI_TEXT_NOSDCARD_DE, + FUI_TEXT_ERROR_DE, + FUI_TEXT_BACK_DE, + FUI_TEXT_QUICK_SETTINGS_DE, + FUI_TEXT_ERRORMSG_DE, + FUI_TEXT_CONFIGURATION_DE, + FUI_TEXT_POSITION_DE, + FUI_TEXT_EXTRUDER_DE, + FUI_TEXT_SD_CARD_DE, + FUI_TEXT_DEBUGGING_DE, + FUI_TEXT_HOME_DELTA_DE, + FUI_TEXT_HOME_ALL_DE, + FUI_TEXT_HOME_X_DE, + FUI_TEXT_HOME_Y_DE, + FUI_TEXT_HOME_Z_DE, + FUI_TEXT_PREHEAT_PLA_DE, + FUI_TEXT_PREHEAT_ABS_DE, + FUI_TEXT_LIGHTS_ONOFF_DE, + FUI_TEXT_COOLDOWN_DE, + FUI_TEXT_SET_TO_ORIGIN_DE, + FUI_TEXT_DISABLE_STEPPER_DE, + FUI_TEXT_X_POSITION_DE, + FUI_TEXT_X_POS_FAST_DE, + FUI_TEXT_Y_POSITION_DE, + FUI_TEXT_Y_POS_FAST_DE, + FUI_TEXT_Z_POSITION_DE, + FUI_TEXT_Z_POS_FAST_DE, + FUI_TEXT_E_POSITION_DE, + FUI_TEXT_BED_TEMP_DE, + FUI_TEXT_EXTR0_TEMP_DE, + FUI_TEXT_EXTR1_TEMP_DE, + FUI_TEXT_EXTR2_TEMP_DE, + FUI_TEXT_EXTR0_OFF_DE, + FUI_TEXT_EXTR1_OFF_DE, + FUI_TEXT_EXTR2_OFF_DE, + FUI_TEXT_EXTR0_SELECT_DE, + FUI_TEXT_EXTR1_SELECT_DE, + FUI_TEXT_EXTR2_SELECT_DE, + FUI_TEXT_EXTR_ORIGIN_DE, + FUI_TEXT_PRINT_X_DE, + FUI_TEXT_PRINT_Y_DE, + FUI_TEXT_PRINT_Z_DE, + FUI_TEXT_PRINT_Z_DELTA_DE, + FUI_TEXT_MOVE_X_DE, + FUI_TEXT_MOVE_Y_DE, + FUI_TEXT_MOVE_Z_DE, + FUI_TEXT_MOVE_Z_DELTA_DE, + FUI_TEXT_JERK_DE, + FUI_TEXT_ZJERK_DE, + FUI_TEXT_ACCELERATION_DE, + FUI_TEXT_STORE_TO_EEPROM_DE, + FUI_TEXT_LOAD_EEPROM_DE, + FUI_TEXT_DBG_ECHO_DE, + FUI_TEXT_DBG_INFO_DE, + FUI_TEXT_DBG_ERROR_DE, + FUI_TEXT_DBG_DRYRUN_DE, + FUI_TEXT_OPS_OFF_DE, + FUI_TEXT_OPS_CLASSIC_DE, + FUI_TEXT_OPS_FAST_DE, + FUI_TEXT_OPS_RETRACT_DE, + FUI_TEXT_OPS_BACKSLASH_DE, + FUI_TEXT_OPS_MINDIST_DE, + FUI_TEXT_OPS_MOVE_AFTER_DE, + FUI_TEXT_ANTI_OOZE_DE, + FUI_TEXT_PRINT_FILE_DE, + FUI_TEXT_PAUSE_PRINT_DE, + FUI_TEXT_CONTINUE_PRINT_DE, + FUI_TEXT_UNMOUNT_CARD_DE, + FUI_TEXT_MOUNT_CARD_DE, + FUI_TEXT_DELETE_FILE_DE, + FUI_TEXT_FEEDRATE_DE, + FUI_TEXT_FEED_MAX_X_DE, + FUI_TEXT_FEED_MAX_Y_DE, + FUI_TEXT_FEED_MAX_Z_DE, + FUI_TEXT_FEED_MAX_Z_DELTA_DE, + FUI_TEXT_FEED_HOME_X_DE, + FUI_TEXT_FEED_HOME_Y_DE, + FUI_TEXT_FEED_HOME_Z_DE, + FUI_TEXT_FEED_HOME_Z_DELTA_DE, + FUI_TEXT_ACTION_XPOSITION4A_DE, + FUI_TEXT_ACTION_XPOSITION4B_DE, + FUI_TEXT_ACTION_XPOSITION4C_DE, + FUI_TEXT_ACTION_XPOSITION4D_DE, + FUI_TEXT_ACTION_YPOSITION4A_DE, + FUI_TEXT_ACTION_YPOSITION4B_DE, + FUI_TEXT_ACTION_YPOSITION4C_DE, + FUI_TEXT_ACTION_YPOSITION4D_DE, + FUI_TEXT_ACTION_ZPOSITION4A_DE, + FUI_TEXT_ACTION_ZPOSITION4B_DE, + FUI_TEXT_ACTION_ZPOSITION4C_DE, + FUI_TEXT_ACTION_ZPOSITION4D_DE, + FUI_TEXT_ACTION_XPOSITION_FAST4A_DE, + FUI_TEXT_ACTION_XPOSITION_FAST4B_DE, + FUI_TEXT_ACTION_XPOSITION_FAST4C_DE, + FUI_TEXT_ACTION_XPOSITION_FAST4D_DE, + FUI_TEXT_ACTION_YPOSITION_FAST4A_DE, + FUI_TEXT_ACTION_YPOSITION_FAST4B_DE, + FUI_TEXT_ACTION_YPOSITION_FAST4C_DE, + FUI_TEXT_ACTION_YPOSITION_FAST4D_DE, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_DE, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_DE, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_DE, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_DE, + FUI_TEXT_ACTION_EPOSITION_FAST2A_DE, + FUI_TEXT_ACTION_EPOSITION_FAST2B_DE, + FUI_TEXT_ACTION_XPOSITION2A_DE, + FUI_TEXT_ACTION_XPOSITION2B_DE, + FUI_TEXT_ACTION_YPOSITION2A_DE, + FUI_TEXT_ACTION_YPOSITION2B_DE, + FUI_TEXT_ACTION_ZPOSITION2A_DE, + FUI_TEXT_ACTION_ZPOSITION2B_DE, + FUI_TEXT_ACTION_XPOSITION_FAST2A_DE, + FUI_TEXT_ACTION_XPOSITION_FAST2B_DE, + FUI_TEXT_ACTION_YPOSITION_FAST2A_DE, + FUI_TEXT_ACTION_YPOSITION_FAST2B_DE, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_DE, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_DE, + FUI_TEXT_FANSPEED_DE, + FUI_TEXT_ACTION_FANSPEED_DE, + FUI_TEXT_FAN_OFF_DE, + FUI_TEXT_FAN_25_DE, + FUI_TEXT_FAN_50_DE, + FUI_TEXT_FAN_75_DE, + FUI_TEXT_FAN_FULL_DE, + FUI_TEXT_STEPPER_INACTIVE_DE, + FUI_TEXT_STEPPER_INACTIVE2A_DE, + FUI_TEXT_STEPPER_INACTIVE2B_DE, + FUI_TEXT_POWER_INACTIVE_DE, + FUI_TEXT_POWER_INACTIVE2A_DE, + FUI_TEXT_POWER_INACTIVE2B_DE, + FUI_TEXT_GENERAL_DE, + FUI_TEXT_BAUDRATE_DE, + FUI_TEXT_EXTR_STEPS_DE, + FUI_TEXT_EXTR_START_FEED_DE, + FUI_TEXT_EXTR_MAX_FEED_DE, + FUI_TEXT_EXTR_ACCEL_DE, + FUI_TEXT_EXTR_WATCH_DE, + FUI_TEXT_EXTR_ADVANCE_L_DE, + FUI_TEXT_EXTR_ADVANCE_K_DE, + FUI_TEXT_EXTR_MANAGER_DE, + FUI_TEXT_EXTR_PGAIN_DE, + FUI_TEXT_EXTR_DEADTIME_DE, + FUI_TEXT_EXTR_DMAX_DT_DE, + FUI_TEXT_EXTR_IGAIN_DE, + FUI_TEXT_EXTR_DGAIN_DE, + FUI_TEXT_EXTR_DMIN_DE, + FUI_TEXT_EXTR_DMAX_DE, + FUI_TEXT_EXTR_PMAX_DE, + FUI_TEXT_EXTR_XOFF_DE, + FUI_TEXT_EXTR_YOFF_DE, + FUI_TEXT_STRING_HM_BANGBANG_DE, + FUI_TEXT_STRING_HM_PID_DE, + FUI_TEXT_STRING_ACTION_DE, + FUI_TEXT_HEATING_EXTRUDER_DE, + FUI_TEXT_HEATING_BED_DE, + FUI_TEXT_KILLED_DE, + FUI_TEXT_STEPPER_DISABLED_DE, + FUI_TEXT_EEPROM_STOREDA_DE, + FUI_TEXT_EEPROM_STOREDB_DE, + FUI_TEXT_EEPROM_LOADEDA_DE, + FUI_TEXT_EEPROM_LOADEDB_DE, + FUI_TEXT_UPLOADING_DE, + FUI_TEXT_PAGE_BUFFER_DE, + FUI_TEXT_PAGE_EXTRUDER_DE, + FUI_TEXT_PAGE_EXTRUDER1_DE, + FUI_TEXT_PAGE_EXTRUDER2_DE, + FUI_TEXT_PAGE_EXTRUDER3_DE, + FUI_TEXT_PAGE_BED_DE, + FUI_TEXT_SPEED_MULTIPLY_DE, + FUI_TEXT_FLOW_MULTIPLY_DE, + FUI_TEXT_SHOW_MEASUREMENT_DE, + FUI_TEXT_RESET_MEASUREMENT_DE, + FUI_TEXT_SET_MEASURED_ORIGIN_DE, + FUI_TEXT_ZCALIB_DE, + FUI_TEXT_SET_P1_DE, + FUI_TEXT_SET_P2_DE, + FUI_TEXT_SET_P3_DE, + FUI_TEXT_CALCULATE_LEVELING_DE, + FUI_TEXT_LEVEL_DE, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_DE, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_DE, + FUI_TEXT_SD_REMOVED_DE, + FUI_TEXT_SD_INSERTED_DE, + FUI_TEXT_PRINTER_READY_DE, + FUI_TEXT_PRINTTIME_DAYS_DE, + FUI_TEXT_PRINTTIME_HOURS_DE, + FUI_TEXT_PRINTTIME_MINUTES_DE, + FUI_TEXT_PRINT_TIME_DE, + FUI_TEXT_PRINT_FILAMENT_DE, + FUI_TEXT_PRINTED_DE, + FUI_TEXT_POWER_DE, + FUI_TEXT_STRING_HM_DEADTIME_DE, + FUI_TEXT_STRING_HM_SLOWBANG_DE, + FUI_TEXT_STOP_PRINT_DE, + FUI_TEXT_Z_BABYSTEPPING_DE, + FUI_TEXT_CHANGE_FILAMENT_DE, + FUI_TEXT_WIZ_CH_FILAMENT1_DE, + FUI_TEXT_WIZ_CH_FILAMENT2_DE, + FUI_TEXT_WIZ_CH_FILAMENT3_DE, + FUI_TEXT_CLICK_DONE_DE, + FUI_TEXT_AUTOLEVEL_ONOFF_DE, + FUI_TEXT_SERVOPOS_DE, + FUI_TEXT_IGNORE_M106_DE, + FUI_TEXT_WIZ_REHEAT1_DE, + FUI_TEXT_WIZ_REHEAT2_DE, + FUI_TEXT_WIZ_WAITTEMP1_DE, + FUI_TEXT_WIZ_WAITTEMP2_DE, + FUI_TEXT_EXTRUDER_JAM_DE, + FUI_TEXT_STANDBY_DE, + FUI_TEXT_BED_COATING_DE, + FUI_TEXT_BED_COATING_SET1_DE, + FUI_TEXT_BED_COATING_SET2_DE, + FUI_TEXT_NOCOATING_DE, + FUI_TEXT_BUILDTAK_DE, + FUI_TEXT_KAPTON_DE, + FUI_TEXT_BLUETAPE_DE, + FUI_TEXT_PETTAPE_DE, + FUI_TEXT_GLUESTICK_DE, + FUI_TEXT_CUSTOM_DE, + FUI_TEXT_COATING_CUSTOM_DE, + FUI_TEXT_LANGUAGE_DE, + FUI_TEXT_MAINPAGE6_1_DE, + FUI_TEXT_MAINPAGE6_2_DE, + FUI_TEXT_MAINPAGE6_3_DE, + FUI_TEXT_MAINPAGE6_4_DE, + FUI_TEXT_MAINPAGE6_5_DE, + FUI_TEXT_MAINPAGE6_6_DE, + FUI_TEXT_MAINPAGE_TEMP_BED_DE, + FUI_TEXT_MAINPAGE_BED_DE, + FUI_TEXT_MAINPAGE_Z_BUF_DE, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_DE, + FUI_TEXT_MAINPAGE_XY_DE, + FUI_TEXT_PRINT_TIME_VALUE_DE, + FUI_TEXT_PRINT_FILAMENT_VALUE_DE, + FUI_TEXT_METER_PRINTED_DE, + FUI_TEXT_STATUS_DE, + FUI_TEXT_EMPTY_DE, + FUI_TEXT_TEMP_SET_DE, + FUI_TEXT_CURRENT_TEMP_DE, + FUI_TEXT_COATING_THICKNESS_DE, + FUI_TEXT_EXTR3_TEMP_DE, + FUI_TEXT_EXTR4_TEMP_DE, + FUI_TEXT_EXTR5_TEMP_DE, + FUI_TEXT_EXTR3_OFF_DE, + FUI_TEXT_EXTR4_OFF_DE, + FUI_TEXT_EXTR5_OFF_DE, + FUI_TEXT_EXTR3_SELECT_DE, + FUI_TEXT_EXTR4_SELECT_DE, + FUI_TEXT_EXTR5_SELECT_DE, + FUI_TEXT_DITTO_0_DE, + FUI_TEXT_DITTO_1_DE, + FUI_TEXT_DITTO_2_DE, + FUI_TEXT_DITTO_3_DE, + FUI_TEXT_ZPROBE_HEIGHT_DE, + FUI_TEXT_OFFSETS_DE, + FUI_TEXT_X_OFFSET_DE, + FUI_TEXT_Y_OFFSET_DE, + FUI_TEXT_Z_OFFSET_DE +}; +#define LANG_DE_TABLE translations_de +#else +#define LANG_DE_TABLE NULL +#endif // LANGUAGE_DE_ACTIVE + +#if LANGUAGE_NL_ACTIVE +TRANS(UI_TEXT_ON_NL); +TRANS(UI_TEXT_OFF_NL); +TRANS(UI_TEXT_NA_NL); +TRANS(UI_TEXT_YES_NL); +TRANS(UI_TEXT_NO_NL); +TRANS(UI_TEXT_PRINT_POS_NL); +TRANS(UI_TEXT_PRINTING_NL); +TRANS(UI_TEXT_IDLE_NL); +TRANS(UI_TEXT_NOSDCARD_NL); +TRANS(UI_TEXT_ERROR_NL); +TRANS(UI_TEXT_BACK_NL); +TRANS(UI_TEXT_QUICK_SETTINGS_NL); +TRANS(UI_TEXT_ERRORMSG_NL); +TRANS(UI_TEXT_CONFIGURATION_NL); +TRANS(UI_TEXT_POSITION_NL); +TRANS(UI_TEXT_EXTRUDER_NL); +TRANS(UI_TEXT_SD_CARD_NL); +TRANS(UI_TEXT_DEBUGGING_NL); +TRANS(UI_TEXT_HOME_DELTA_NL); +TRANS(UI_TEXT_HOME_ALL_NL); +TRANS(UI_TEXT_HOME_X_NL); +TRANS(UI_TEXT_HOME_Y_NL); +TRANS(UI_TEXT_HOME_Z_NL); +TRANS(UI_TEXT_PREHEAT_PLA_NL); +TRANS(UI_TEXT_PREHEAT_ABS_NL); +TRANS(UI_TEXT_LIGHTS_ONOFF_NL); +TRANS(UI_TEXT_COOLDOWN_NL); +TRANS(UI_TEXT_SET_TO_ORIGIN_NL); +TRANS(UI_TEXT_DISABLE_STEPPER_NL); +TRANS(UI_TEXT_X_POSITION_NL); +TRANS(UI_TEXT_X_POS_FAST_NL); +TRANS(UI_TEXT_Y_POSITION_NL); +TRANS(UI_TEXT_Y_POS_FAST_NL); +TRANS(UI_TEXT_Z_POSITION_NL); +TRANS(UI_TEXT_Z_POS_FAST_NL); +TRANS(UI_TEXT_E_POSITION_NL); +TRANS(UI_TEXT_BED_TEMP_NL); +TRANS(UI_TEXT_EXTR0_TEMP_NL); +TRANS(UI_TEXT_EXTR1_TEMP_NL); +TRANS(UI_TEXT_EXTR2_TEMP_NL); +TRANS(UI_TEXT_EXTR0_OFF_NL); +TRANS(UI_TEXT_EXTR1_OFF_NL); +TRANS(UI_TEXT_EXTR2_OFF_NL); +TRANS(UI_TEXT_EXTR0_SELECT_NL); +TRANS(UI_TEXT_EXTR1_SELECT_NL); +TRANS(UI_TEXT_EXTR2_SELECT_NL); +TRANS(UI_TEXT_EXTR_ORIGIN_NL); +TRANS(UI_TEXT_PRINT_X_NL); +TRANS(UI_TEXT_PRINT_Y_NL); +TRANS(UI_TEXT_PRINT_Z_NL); +TRANS(UI_TEXT_PRINT_Z_DELTA_NL); +TRANS(UI_TEXT_MOVE_X_NL); +TRANS(UI_TEXT_MOVE_Y_NL); +TRANS(UI_TEXT_MOVE_Z_NL); +TRANS(UI_TEXT_MOVE_Z_DELTA_NL); +TRANS(UI_TEXT_JERK_NL); +TRANS(UI_TEXT_ZJERK_NL); +TRANS(UI_TEXT_ACCELERATION_NL); +TRANS(UI_TEXT_STORE_TO_EEPROM_NL); +TRANS(UI_TEXT_LOAD_EEPROM_NL); +TRANS(UI_TEXT_DBG_ECHO_NL); +TRANS(UI_TEXT_DBG_INFO_NL); +TRANS(UI_TEXT_DBG_ERROR_NL); +TRANS(UI_TEXT_DBG_DRYRUN_NL); +TRANS(UI_TEXT_OPS_OFF_NL); +TRANS(UI_TEXT_OPS_CLASSIC_NL); +TRANS(UI_TEXT_OPS_FAST_NL); +TRANS(UI_TEXT_OPS_RETRACT_NL); +TRANS(UI_TEXT_OPS_BACKSLASH_NL); +TRANS(UI_TEXT_OPS_MINDIST_NL); +TRANS(UI_TEXT_OPS_MOVE_AFTER_NL); +TRANS(UI_TEXT_ANTI_OOZE_NL); +TRANS(UI_TEXT_PRINT_FILE_NL); +TRANS(UI_TEXT_PAUSE_PRINT_NL); +TRANS(UI_TEXT_CONTINUE_PRINT_NL); +TRANS(UI_TEXT_UNMOUNT_CARD_NL); +TRANS(UI_TEXT_MOUNT_CARD_NL); +TRANS(UI_TEXT_DELETE_FILE_NL); +TRANS(UI_TEXT_FEEDRATE_NL); +TRANS(UI_TEXT_FEED_MAX_X_NL); +TRANS(UI_TEXT_FEED_MAX_Y_NL); +TRANS(UI_TEXT_FEED_MAX_Z_NL); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_NL); +TRANS(UI_TEXT_FEED_HOME_X_NL); +TRANS(UI_TEXT_FEED_HOME_Y_NL); +TRANS(UI_TEXT_FEED_HOME_Z_NL); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_NL); +TRANS(UI_TEXT_ACTION_XPOSITION4A_NL); +TRANS(UI_TEXT_ACTION_XPOSITION4B_NL); +TRANS(UI_TEXT_ACTION_XPOSITION4C_NL); +TRANS(UI_TEXT_ACTION_XPOSITION4D_NL); +TRANS(UI_TEXT_ACTION_YPOSITION4A_NL); +TRANS(UI_TEXT_ACTION_YPOSITION4B_NL); +TRANS(UI_TEXT_ACTION_YPOSITION4C_NL); +TRANS(UI_TEXT_ACTION_YPOSITION4D_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_NL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_NL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_NL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_NL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_NL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_NL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_NL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_NL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_NL); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_NL); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_NL); +TRANS(UI_TEXT_ACTION_XPOSITION2A_NL); +TRANS(UI_TEXT_ACTION_XPOSITION2B_NL); +TRANS(UI_TEXT_ACTION_YPOSITION2A_NL); +TRANS(UI_TEXT_ACTION_YPOSITION2B_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_NL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_NL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_NL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_NL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_NL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_NL); +TRANS(UI_TEXT_FANSPEED_NL); +TRANS(UI_TEXT_ACTION_FANSPEED_NL); +TRANS(UI_TEXT_FAN_OFF_NL); +TRANS(UI_TEXT_FAN_25_NL); +TRANS(UI_TEXT_FAN_50_NL); +TRANS(UI_TEXT_FAN_75_NL); +TRANS(UI_TEXT_FAN_FULL_NL); +TRANS(UI_TEXT_STEPPER_INACTIVE_NL); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_NL); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_NL); +TRANS(UI_TEXT_POWER_INACTIVE_NL); +TRANS(UI_TEXT_POWER_INACTIVE2A_NL); +TRANS(UI_TEXT_POWER_INACTIVE2B_NL); +TRANS(UI_TEXT_GENERAL_NL); +TRANS(UI_TEXT_BAUDRATE_NL); +TRANS(UI_TEXT_EXTR_STEPS_NL); +TRANS(UI_TEXT_EXTR_START_FEED_NL); +TRANS(UI_TEXT_EXTR_MAX_FEED_NL); +TRANS(UI_TEXT_EXTR_ACCEL_NL); +TRANS(UI_TEXT_EXTR_WATCH_NL); +TRANS(UI_TEXT_EXTR_ADVANCE_L_NL); +TRANS(UI_TEXT_EXTR_ADVANCE_K_NL); +TRANS(UI_TEXT_EXTR_MANAGER_NL); +TRANS(UI_TEXT_EXTR_PGAIN_NL); +TRANS(UI_TEXT_EXTR_DEADTIME_NL); +TRANS(UI_TEXT_EXTR_DMAX_DT_NL); +TRANS(UI_TEXT_EXTR_IGAIN_NL); +TRANS(UI_TEXT_EXTR_DGAIN_NL); +TRANS(UI_TEXT_EXTR_DMIN_NL); +TRANS(UI_TEXT_EXTR_DMAX_NL); +TRANS(UI_TEXT_EXTR_PMAX_NL); +TRANS(UI_TEXT_EXTR_XOFF_NL); +TRANS(UI_TEXT_EXTR_YOFF_NL); +TRANS(UI_TEXT_STRING_HM_BANGBANG_NL); +TRANS(UI_TEXT_STRING_HM_PID_NL); +TRANS(UI_TEXT_STRING_ACTION_NL); +TRANS(UI_TEXT_HEATING_EXTRUDER_NL); +TRANS(UI_TEXT_HEATING_BED_NL); +TRANS(UI_TEXT_KILLED_NL); +TRANS(UI_TEXT_STEPPER_DISABLED_NL); +TRANS(UI_TEXT_EEPROM_STOREDA_NL); +TRANS(UI_TEXT_EEPROM_STOREDB_NL); +TRANS(UI_TEXT_EEPROM_LOADEDA_NL); +TRANS(UI_TEXT_EEPROM_LOADEDB_NL); +TRANS(UI_TEXT_UPLOADING_NL); +TRANS(UI_TEXT_PAGE_BUFFER_NL); +TRANS(UI_TEXT_PAGE_EXTRUDER_NL); +TRANS(UI_TEXT_PAGE_EXTRUDER1_NL); +TRANS(UI_TEXT_PAGE_EXTRUDER2_NL); +TRANS(UI_TEXT_PAGE_EXTRUDER3_NL); +TRANS(UI_TEXT_PAGE_BED_NL); +TRANS(UI_TEXT_SPEED_MULTIPLY_NL); +TRANS(UI_TEXT_FLOW_MULTIPLY_NL); +TRANS(UI_TEXT_SHOW_MEASUREMENT_NL); +TRANS(UI_TEXT_RESET_MEASUREMENT_NL); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_NL); +TRANS(UI_TEXT_ZCALIB_NL); +TRANS(UI_TEXT_SET_P1_NL); +TRANS(UI_TEXT_SET_P2_NL); +TRANS(UI_TEXT_SET_P3_NL); +TRANS(UI_TEXT_CALCULATE_LEVELING_NL); +TRANS(UI_TEXT_LEVEL_NL); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_NL); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_NL); +TRANS(UI_TEXT_SD_REMOVED_NL); +TRANS(UI_TEXT_SD_INSERTED_NL); +TRANS(UI_TEXT_PRINTER_READY_NL); +TRANS(UI_TEXT_PRINTTIME_DAYS_NL); +TRANS(UI_TEXT_PRINTTIME_HOURS_NL); +TRANS(UI_TEXT_PRINTTIME_MINUTES_NL); +TRANS(UI_TEXT_PRINT_TIME_NL); +TRANS(UI_TEXT_PRINT_FILAMENT_NL); +TRANS(UI_TEXT_PRINTED_NL); +TRANS(UI_TEXT_POWER_NL); +TRANS(UI_TEXT_STRING_HM_DEADTIME_NL); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_NL); +TRANS(UI_TEXT_STOP_PRINT_NL); +TRANS(UI_TEXT_Z_BABYSTEPPING_NL); +TRANS(UI_TEXT_CHANGE_FILAMENT_NL); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_NL); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_NL); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_NL); +TRANS(UI_TEXT_CLICK_DONE_NL); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_NL); +TRANS(UI_TEXT_SERVOPOS_NL); +TRANS(UI_TEXT_IGNORE_M106_NL); +TRANS(UI_TEXT_WIZ_REHEAT1_NL); +TRANS(UI_TEXT_WIZ_REHEAT2_NL); +TRANS(UI_TEXT_WIZ_WAITTEMP1_NL); +TRANS(UI_TEXT_WIZ_WAITTEMP2_NL); +TRANS(UI_TEXT_EXTRUDER_JAM_NL); +TRANS(UI_TEXT_STANDBY_NL); +TRANS(UI_TEXT_BED_COATING_NL); +TRANS(UI_TEXT_BED_COATING_SET1_NL); +TRANS(UI_TEXT_BED_COATING_SET2_NL); +TRANS(UI_TEXT_NOCOATING_NL); +TRANS(UI_TEXT_BUILDTAK_NL); +TRANS(UI_TEXT_KAPTON_NL); +TRANS(UI_TEXT_BLUETAPE_NL); +TRANS(UI_TEXT_PETTAPE_NL); +TRANS(UI_TEXT_GLUESTICK_NL); +TRANS(UI_TEXT_CUSTOM_NL); +TRANS(UI_TEXT_COATING_CUSTOM_NL); +TRANS(UI_TEXT_LANGUAGE_NL); +TRANS(UI_TEXT_MAINPAGE6_1_NL); +TRANS(UI_TEXT_MAINPAGE6_2_NL); +TRANS(UI_TEXT_MAINPAGE6_3_NL); +TRANS(UI_TEXT_MAINPAGE6_4_NL); +TRANS(UI_TEXT_MAINPAGE6_5_NL); +TRANS(UI_TEXT_MAINPAGE6_6_NL); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_NL); +TRANS(UI_TEXT_MAINPAGE_BED_NL); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_NL); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_NL); +TRANS(UI_TEXT_MAINPAGE_XY_NL); +TRANS(UI_TEXT_PRINT_TIME_VALUE_NL); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_NL); +TRANS(UI_TEXT_METER_PRINTED_NL); +TRANS(UI_TEXT_STATUS_NL); +TRANS(UI_TEXT_EMPTY_NL); +TRANS(UI_TEXT_TEMP_SET_NL); +TRANS(UI_TEXT_CURRENT_TEMP_NL); +TRANS(UI_TEXT_COATING_THICKNESS_NL); +TRANS(UI_TEXT_EXTR3_TEMP_NL); +TRANS(UI_TEXT_EXTR4_TEMP_NL); +TRANS(UI_TEXT_EXTR5_TEMP_NL); +TRANS(UI_TEXT_EXTR3_OFF_NL); +TRANS(UI_TEXT_EXTR4_OFF_NL); +TRANS(UI_TEXT_EXTR5_OFF_NL); +TRANS(UI_TEXT_EXTR3_SELECT_NL); +TRANS(UI_TEXT_EXTR4_SELECT_NL); +TRANS(UI_TEXT_EXTR5_SELECT_NL); +TRANS(UI_TEXT_DITTO_0_NL); +TRANS(UI_TEXT_DITTO_1_NL); +TRANS(UI_TEXT_DITTO_2_NL); +TRANS(UI_TEXT_DITTO_3_NL); +TRANS(UI_TEXT_ZPROBE_HEIGHT_NL); +TRANS(UI_TEXT_OFFSETS_NL); +TRANS(UI_TEXT_X_OFFSET_NL); +TRANS(UI_TEXT_Y_OFFSET_NL); +TRANS(UI_TEXT_Z_OFFSET_NL); + +PGM_P const translations_nl[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_NL, + FUI_TEXT_OFF_NL, + FUI_TEXT_NA_NL, + FUI_TEXT_YES_NL, + FUI_TEXT_NO_NL, + FUI_TEXT_PRINT_POS_NL, + FUI_TEXT_PRINTING_NL, + FUI_TEXT_IDLE_NL, + FUI_TEXT_NOSDCARD_NL, + FUI_TEXT_ERROR_NL, + FUI_TEXT_BACK_NL, + FUI_TEXT_QUICK_SETTINGS_NL, + FUI_TEXT_ERRORMSG_NL, + FUI_TEXT_CONFIGURATION_NL, + FUI_TEXT_POSITION_NL, + FUI_TEXT_EXTRUDER_NL, + FUI_TEXT_SD_CARD_NL, + FUI_TEXT_DEBUGGING_NL, + FUI_TEXT_HOME_DELTA_NL, + FUI_TEXT_HOME_ALL_NL, + FUI_TEXT_HOME_X_NL, + FUI_TEXT_HOME_Y_NL, + FUI_TEXT_HOME_Z_NL, + FUI_TEXT_PREHEAT_PLA_NL, + FUI_TEXT_PREHEAT_ABS_NL, + FUI_TEXT_LIGHTS_ONOFF_NL, + FUI_TEXT_COOLDOWN_NL, + FUI_TEXT_SET_TO_ORIGIN_NL, + FUI_TEXT_DISABLE_STEPPER_NL, + FUI_TEXT_X_POSITION_NL, + FUI_TEXT_X_POS_FAST_NL, + FUI_TEXT_Y_POSITION_NL, + FUI_TEXT_Y_POS_FAST_NL, + FUI_TEXT_Z_POSITION_NL, + FUI_TEXT_Z_POS_FAST_NL, + FUI_TEXT_E_POSITION_NL, + FUI_TEXT_BED_TEMP_NL, + FUI_TEXT_EXTR0_TEMP_NL, + FUI_TEXT_EXTR1_TEMP_NL, + FUI_TEXT_EXTR2_TEMP_NL, + FUI_TEXT_EXTR0_OFF_NL, + FUI_TEXT_EXTR1_OFF_NL, + FUI_TEXT_EXTR2_OFF_NL, + FUI_TEXT_EXTR0_SELECT_NL, + FUI_TEXT_EXTR1_SELECT_NL, + FUI_TEXT_EXTR2_SELECT_NL, + FUI_TEXT_EXTR_ORIGIN_NL, + FUI_TEXT_PRINT_X_NL, + FUI_TEXT_PRINT_Y_NL, + FUI_TEXT_PRINT_Z_NL, + FUI_TEXT_PRINT_Z_DELTA_NL, + FUI_TEXT_MOVE_X_NL, + FUI_TEXT_MOVE_Y_NL, + FUI_TEXT_MOVE_Z_NL, + FUI_TEXT_MOVE_Z_DELTA_NL, + FUI_TEXT_JERK_NL, + FUI_TEXT_ZJERK_NL, + FUI_TEXT_ACCELERATION_NL, + FUI_TEXT_STORE_TO_EEPROM_NL, + FUI_TEXT_LOAD_EEPROM_NL, + FUI_TEXT_DBG_ECHO_NL, + FUI_TEXT_DBG_INFO_NL, + FUI_TEXT_DBG_ERROR_NL, + FUI_TEXT_DBG_DRYRUN_NL, + FUI_TEXT_OPS_OFF_NL, + FUI_TEXT_OPS_CLASSIC_NL, + FUI_TEXT_OPS_FAST_NL, + FUI_TEXT_OPS_RETRACT_NL, + FUI_TEXT_OPS_BACKSLASH_NL, + FUI_TEXT_OPS_MINDIST_NL, + FUI_TEXT_OPS_MOVE_AFTER_NL, + FUI_TEXT_ANTI_OOZE_NL, + FUI_TEXT_PRINT_FILE_NL, + FUI_TEXT_PAUSE_PRINT_NL, + FUI_TEXT_CONTINUE_PRINT_NL, + FUI_TEXT_UNMOUNT_CARD_NL, + FUI_TEXT_MOUNT_CARD_NL, + FUI_TEXT_DELETE_FILE_NL, + FUI_TEXT_FEEDRATE_NL, + FUI_TEXT_FEED_MAX_X_NL, + FUI_TEXT_FEED_MAX_Y_NL, + FUI_TEXT_FEED_MAX_Z_NL, + FUI_TEXT_FEED_MAX_Z_DELTA_NL, + FUI_TEXT_FEED_HOME_X_NL, + FUI_TEXT_FEED_HOME_Y_NL, + FUI_TEXT_FEED_HOME_Z_NL, + FUI_TEXT_FEED_HOME_Z_DELTA_NL, + FUI_TEXT_ACTION_XPOSITION4A_NL, + FUI_TEXT_ACTION_XPOSITION4B_NL, + FUI_TEXT_ACTION_XPOSITION4C_NL, + FUI_TEXT_ACTION_XPOSITION4D_NL, + FUI_TEXT_ACTION_YPOSITION4A_NL, + FUI_TEXT_ACTION_YPOSITION4B_NL, + FUI_TEXT_ACTION_YPOSITION4C_NL, + FUI_TEXT_ACTION_YPOSITION4D_NL, + FUI_TEXT_ACTION_ZPOSITION4A_NL, + FUI_TEXT_ACTION_ZPOSITION4B_NL, + FUI_TEXT_ACTION_ZPOSITION4C_NL, + FUI_TEXT_ACTION_ZPOSITION4D_NL, + FUI_TEXT_ACTION_XPOSITION_FAST4A_NL, + FUI_TEXT_ACTION_XPOSITION_FAST4B_NL, + FUI_TEXT_ACTION_XPOSITION_FAST4C_NL, + FUI_TEXT_ACTION_XPOSITION_FAST4D_NL, + FUI_TEXT_ACTION_YPOSITION_FAST4A_NL, + FUI_TEXT_ACTION_YPOSITION_FAST4B_NL, + FUI_TEXT_ACTION_YPOSITION_FAST4C_NL, + FUI_TEXT_ACTION_YPOSITION_FAST4D_NL, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_NL, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_NL, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_NL, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_NL, + FUI_TEXT_ACTION_EPOSITION_FAST2A_NL, + FUI_TEXT_ACTION_EPOSITION_FAST2B_NL, + FUI_TEXT_ACTION_XPOSITION2A_NL, + FUI_TEXT_ACTION_XPOSITION2B_NL, + FUI_TEXT_ACTION_YPOSITION2A_NL, + FUI_TEXT_ACTION_YPOSITION2B_NL, + FUI_TEXT_ACTION_ZPOSITION2A_NL, + FUI_TEXT_ACTION_ZPOSITION2B_NL, + FUI_TEXT_ACTION_XPOSITION_FAST2A_NL, + FUI_TEXT_ACTION_XPOSITION_FAST2B_NL, + FUI_TEXT_ACTION_YPOSITION_FAST2A_NL, + FUI_TEXT_ACTION_YPOSITION_FAST2B_NL, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_NL, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_NL, + FUI_TEXT_FANSPEED_NL, + FUI_TEXT_ACTION_FANSPEED_NL, + FUI_TEXT_FAN_OFF_NL, + FUI_TEXT_FAN_25_NL, + FUI_TEXT_FAN_50_NL, + FUI_TEXT_FAN_75_NL, + FUI_TEXT_FAN_FULL_NL, + FUI_TEXT_STEPPER_INACTIVE_NL, + FUI_TEXT_STEPPER_INACTIVE2A_NL, + FUI_TEXT_STEPPER_INACTIVE2B_NL, + FUI_TEXT_POWER_INACTIVE_NL, + FUI_TEXT_POWER_INACTIVE2A_NL, + FUI_TEXT_POWER_INACTIVE2B_NL, + FUI_TEXT_GENERAL_NL, + FUI_TEXT_BAUDRATE_NL, + FUI_TEXT_EXTR_STEPS_NL, + FUI_TEXT_EXTR_START_FEED_NL, + FUI_TEXT_EXTR_MAX_FEED_NL, + FUI_TEXT_EXTR_ACCEL_NL, + FUI_TEXT_EXTR_WATCH_NL, + FUI_TEXT_EXTR_ADVANCE_L_NL, + FUI_TEXT_EXTR_ADVANCE_K_NL, + FUI_TEXT_EXTR_MANAGER_NL, + FUI_TEXT_EXTR_PGAIN_NL, + FUI_TEXT_EXTR_DEADTIME_NL, + FUI_TEXT_EXTR_DMAX_DT_NL, + FUI_TEXT_EXTR_IGAIN_NL, + FUI_TEXT_EXTR_DGAIN_NL, + FUI_TEXT_EXTR_DMIN_NL, + FUI_TEXT_EXTR_DMAX_NL, + FUI_TEXT_EXTR_PMAX_NL, + FUI_TEXT_EXTR_XOFF_NL, + FUI_TEXT_EXTR_YOFF_NL, + FUI_TEXT_STRING_HM_BANGBANG_NL, + FUI_TEXT_STRING_HM_PID_NL, + FUI_TEXT_STRING_ACTION_NL, + FUI_TEXT_HEATING_EXTRUDER_NL, + FUI_TEXT_HEATING_BED_NL, + FUI_TEXT_KILLED_NL, + FUI_TEXT_STEPPER_DISABLED_NL, + FUI_TEXT_EEPROM_STOREDA_NL, + FUI_TEXT_EEPROM_STOREDB_NL, + FUI_TEXT_EEPROM_LOADEDA_NL, + FUI_TEXT_EEPROM_LOADEDB_NL, + FUI_TEXT_UPLOADING_NL, + FUI_TEXT_PAGE_BUFFER_NL, + FUI_TEXT_PAGE_EXTRUDER_NL, + FUI_TEXT_PAGE_EXTRUDER1_NL, + FUI_TEXT_PAGE_EXTRUDER2_NL, + FUI_TEXT_PAGE_EXTRUDER3_NL, + FUI_TEXT_PAGE_BED_NL, + FUI_TEXT_SPEED_MULTIPLY_NL, + FUI_TEXT_FLOW_MULTIPLY_NL, + FUI_TEXT_SHOW_MEASUREMENT_NL, + FUI_TEXT_RESET_MEASUREMENT_NL, + FUI_TEXT_SET_MEASURED_ORIGIN_NL, + FUI_TEXT_ZCALIB_NL, + FUI_TEXT_SET_P1_NL, + FUI_TEXT_SET_P2_NL, + FUI_TEXT_SET_P3_NL, + FUI_TEXT_CALCULATE_LEVELING_NL, + FUI_TEXT_LEVEL_NL, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_NL, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_NL, + FUI_TEXT_SD_REMOVED_NL, + FUI_TEXT_SD_INSERTED_NL, + FUI_TEXT_PRINTER_READY_NL, + FUI_TEXT_PRINTTIME_DAYS_NL, + FUI_TEXT_PRINTTIME_HOURS_NL, + FUI_TEXT_PRINTTIME_MINUTES_NL, + FUI_TEXT_PRINT_TIME_NL, + FUI_TEXT_PRINT_FILAMENT_NL, + FUI_TEXT_PRINTED_NL, + FUI_TEXT_POWER_NL, + FUI_TEXT_STRING_HM_DEADTIME_NL, + FUI_TEXT_STRING_HM_SLOWBANG_NL, + FUI_TEXT_STOP_PRINT_NL, + FUI_TEXT_Z_BABYSTEPPING_NL, + FUI_TEXT_CHANGE_FILAMENT_NL, + FUI_TEXT_WIZ_CH_FILAMENT1_NL, + FUI_TEXT_WIZ_CH_FILAMENT2_NL, + FUI_TEXT_WIZ_CH_FILAMENT3_NL, + FUI_TEXT_CLICK_DONE_NL, + FUI_TEXT_AUTOLEVEL_ONOFF_NL, + FUI_TEXT_SERVOPOS_NL, + FUI_TEXT_IGNORE_M106_NL, + FUI_TEXT_WIZ_REHEAT1_NL, + FUI_TEXT_WIZ_REHEAT2_NL, + FUI_TEXT_WIZ_WAITTEMP1_NL, + FUI_TEXT_WIZ_WAITTEMP2_NL, + FUI_TEXT_EXTRUDER_JAM_NL, + FUI_TEXT_STANDBY_NL, + FUI_TEXT_BED_COATING_NL, + FUI_TEXT_BED_COATING_SET1_NL, + FUI_TEXT_BED_COATING_SET2_NL, + FUI_TEXT_NOCOATING_NL, + FUI_TEXT_BUILDTAK_NL, + FUI_TEXT_KAPTON_NL, + FUI_TEXT_BLUETAPE_NL, + FUI_TEXT_PETTAPE_NL, + FUI_TEXT_GLUESTICK_NL, + FUI_TEXT_CUSTOM_NL, + FUI_TEXT_COATING_CUSTOM_NL, + FUI_TEXT_LANGUAGE_NL, + FUI_TEXT_MAINPAGE6_1_NL, + FUI_TEXT_MAINPAGE6_2_NL, + FUI_TEXT_MAINPAGE6_3_NL, + FUI_TEXT_MAINPAGE6_4_NL, + FUI_TEXT_MAINPAGE6_5_NL, + FUI_TEXT_MAINPAGE6_6_NL, + FUI_TEXT_MAINPAGE_TEMP_BED_NL, + FUI_TEXT_MAINPAGE_BED_NL, + FUI_TEXT_MAINPAGE_Z_BUF_NL, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_NL, + FUI_TEXT_MAINPAGE_XY_NL, + FUI_TEXT_PRINT_TIME_VALUE_NL, + FUI_TEXT_PRINT_FILAMENT_VALUE_NL, + FUI_TEXT_METER_PRINTED_NL, + FUI_TEXT_STATUS_NL, + FUI_TEXT_EMPTY_NL, + FUI_TEXT_TEMP_SET_NL, + FUI_TEXT_CURRENT_TEMP_NL, + FUI_TEXT_COATING_THICKNESS_NL, + FUI_TEXT_EXTR3_TEMP_NL, + FUI_TEXT_EXTR4_TEMP_NL, + FUI_TEXT_EXTR5_TEMP_NL, + FUI_TEXT_EXTR3_OFF_NL, + FUI_TEXT_EXTR4_OFF_NL, + FUI_TEXT_EXTR5_OFF_NL, + FUI_TEXT_EXTR3_SELECT_NL, + FUI_TEXT_EXTR4_SELECT_NL, + FUI_TEXT_EXTR5_SELECT_NL, + FUI_TEXT_DITTO_0_NL, + FUI_TEXT_DITTO_1_NL, + FUI_TEXT_DITTO_2_NL, + FUI_TEXT_DITTO_3_NL, + FUI_TEXT_ZPROBE_HEIGHT_NL, + FUI_TEXT_OFFSETS_NL, + FUI_TEXT_X_OFFSET_NL, + FUI_TEXT_Y_OFFSET_NL, + FUI_TEXT_Z_OFFSET_NL +}; +#define LANG_NL_TABLE translations_nl +#else +#define LANG_NL_TABLE NULL +#endif // LANGUAGE_NL_ACTIVE + + +#if LANGUAGE_PT_ACTIVE +TRANS(UI_TEXT_ON_PT); +TRANS(UI_TEXT_OFF_PT); +TRANS(UI_TEXT_NA_PT); +TRANS(UI_TEXT_YES_PT); +TRANS(UI_TEXT_NO_PT); +TRANS(UI_TEXT_PRINT_POS_PT); +TRANS(UI_TEXT_PRINTING_PT); +TRANS(UI_TEXT_IDLE_PT); +TRANS(UI_TEXT_NOSDCARD_PT); +TRANS(UI_TEXT_ERROR_PT); +TRANS(UI_TEXT_BACK_PT); +TRANS(UI_TEXT_QUICK_SETTINGS_PT); +TRANS(UI_TEXT_ERRORMSG_PT); +TRANS(UI_TEXT_CONFIGURATION_PT); +TRANS(UI_TEXT_POSITION_PT); +TRANS(UI_TEXT_EXTRUDER_PT); +TRANS(UI_TEXT_SD_CARD_PT); +TRANS(UI_TEXT_DEBUGGING_PT); +TRANS(UI_TEXT_HOME_DELTA_PT); +TRANS(UI_TEXT_HOME_ALL_PT); +TRANS(UI_TEXT_HOME_X_PT); +TRANS(UI_TEXT_HOME_Y_PT); +TRANS(UI_TEXT_HOME_Z_PT); +TRANS(UI_TEXT_PREHEAT_PLA_PT); +TRANS(UI_TEXT_PREHEAT_ABS_PT); +TRANS(UI_TEXT_LIGHTS_ONOFF_PT); +TRANS(UI_TEXT_COOLDOWN_PT); +TRANS(UI_TEXT_SET_TO_ORIGIN_PT); +TRANS(UI_TEXT_DISABLE_STEPPER_PT); +TRANS(UI_TEXT_X_POSITION_PT); +TRANS(UI_TEXT_X_POS_FAST_PT); +TRANS(UI_TEXT_Y_POSITION_PT); +TRANS(UI_TEXT_Y_POS_FAST_PT); +TRANS(UI_TEXT_Z_POSITION_PT); +TRANS(UI_TEXT_Z_POS_FAST_PT); +TRANS(UI_TEXT_E_POSITION_PT); +TRANS(UI_TEXT_BED_TEMP_PT); +TRANS(UI_TEXT_EXTR0_TEMP_PT); +TRANS(UI_TEXT_EXTR1_TEMP_PT); +TRANS(UI_TEXT_EXTR2_TEMP_PT); +TRANS(UI_TEXT_EXTR0_OFF_PT); +TRANS(UI_TEXT_EXTR1_OFF_PT); +TRANS(UI_TEXT_EXTR2_OFF_PT); +TRANS(UI_TEXT_EXTR0_SELECT_PT); +TRANS(UI_TEXT_EXTR1_SELECT_PT); +TRANS(UI_TEXT_EXTR2_SELECT_PT); +TRANS(UI_TEXT_EXTR_ORIGIN_PT); +TRANS(UI_TEXT_PRINT_X_PT); +TRANS(UI_TEXT_PRINT_Y_PT); +TRANS(UI_TEXT_PRINT_Z_PT); +TRANS(UI_TEXT_PRINT_Z_DELTA_PT); +TRANS(UI_TEXT_MOVE_X_PT); +TRANS(UI_TEXT_MOVE_Y_PT); +TRANS(UI_TEXT_MOVE_Z_PT); +TRANS(UI_TEXT_MOVE_Z_DELTA_PT); +TRANS(UI_TEXT_JERK_PT); +TRANS(UI_TEXT_ZJERK_PT); +TRANS(UI_TEXT_ACCELERATION_PT); +TRANS(UI_TEXT_STORE_TO_EEPROM_PT); +TRANS(UI_TEXT_LOAD_EEPROM_PT); +TRANS(UI_TEXT_DBG_ECHO_PT); +TRANS(UI_TEXT_DBG_INFO_PT); +TRANS(UI_TEXT_DBG_ERROR_PT); +TRANS(UI_TEXT_DBG_DRYRUN_PT); +TRANS(UI_TEXT_OPS_OFF_PT); +TRANS(UI_TEXT_OPS_CLASSIC_PT); +TRANS(UI_TEXT_OPS_FAST_PT); +TRANS(UI_TEXT_OPS_RETRACT_PT); +TRANS(UI_TEXT_OPS_BACKSLASH_PT); +TRANS(UI_TEXT_OPS_MINDIST_PT); +TRANS(UI_TEXT_OPS_MOVE_AFTER_PT); +TRANS(UI_TEXT_ANTI_OOZE_PT); +TRANS(UI_TEXT_PRINT_FILE_PT); +TRANS(UI_TEXT_PAUSE_PRINT_PT); +TRANS(UI_TEXT_CONTINUE_PRINT_PT); +TRANS(UI_TEXT_UNMOUNT_CARD_PT); +TRANS(UI_TEXT_MOUNT_CARD_PT); +TRANS(UI_TEXT_DELETE_FILE_PT); +TRANS(UI_TEXT_FEEDRATE_PT); +TRANS(UI_TEXT_FEED_MAX_X_PT); +TRANS(UI_TEXT_FEED_MAX_Y_PT); +TRANS(UI_TEXT_FEED_MAX_Z_PT); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_PT); +TRANS(UI_TEXT_FEED_HOME_X_PT); +TRANS(UI_TEXT_FEED_HOME_Y_PT); +TRANS(UI_TEXT_FEED_HOME_Z_PT); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_PT); +TRANS(UI_TEXT_ACTION_XPOSITION4A_PT); +TRANS(UI_TEXT_ACTION_XPOSITION4B_PT); +TRANS(UI_TEXT_ACTION_XPOSITION4C_PT); +TRANS(UI_TEXT_ACTION_XPOSITION4D_PT); +TRANS(UI_TEXT_ACTION_YPOSITION4A_PT); +TRANS(UI_TEXT_ACTION_YPOSITION4B_PT); +TRANS(UI_TEXT_ACTION_YPOSITION4C_PT); +TRANS(UI_TEXT_ACTION_YPOSITION4D_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_PT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_PT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_PT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_PT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_PT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_PT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_PT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_PT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_PT); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_PT); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_PT); +TRANS(UI_TEXT_ACTION_XPOSITION2A_PT); +TRANS(UI_TEXT_ACTION_XPOSITION2B_PT); +TRANS(UI_TEXT_ACTION_YPOSITION2A_PT); +TRANS(UI_TEXT_ACTION_YPOSITION2B_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_PT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_PT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_PT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_PT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_PT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_PT); +TRANS(UI_TEXT_FANSPEED_PT); +TRANS(UI_TEXT_ACTION_FANSPEED_PT); +TRANS(UI_TEXT_FAN_OFF_PT); +TRANS(UI_TEXT_FAN_25_PT); +TRANS(UI_TEXT_FAN_50_PT); +TRANS(UI_TEXT_FAN_75_PT); +TRANS(UI_TEXT_FAN_FULL_PT); +TRANS(UI_TEXT_STEPPER_INACTIVE_PT); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_PT); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_PT); +TRANS(UI_TEXT_POWER_INACTIVE_PT); +TRANS(UI_TEXT_POWER_INACTIVE2A_PT); +TRANS(UI_TEXT_POWER_INACTIVE2B_PT); +TRANS(UI_TEXT_GENERAL_PT); +TRANS(UI_TEXT_BAUDRATE_PT); +TRANS(UI_TEXT_EXTR_STEPS_PT); +TRANS(UI_TEXT_EXTR_START_FEED_PT); +TRANS(UI_TEXT_EXTR_MAX_FEED_PT); +TRANS(UI_TEXT_EXTR_ACCEL_PT); +TRANS(UI_TEXT_EXTR_WATCH_PT); +TRANS(UI_TEXT_EXTR_ADVANCE_L_PT); +TRANS(UI_TEXT_EXTR_ADVANCE_K_PT); +TRANS(UI_TEXT_EXTR_MANAGER_PT); +TRANS(UI_TEXT_EXTR_PGAIN_PT); +TRANS(UI_TEXT_EXTR_DEADTIME_PT); +TRANS(UI_TEXT_EXTR_DMAX_DT_PT); +TRANS(UI_TEXT_EXTR_IGAIN_PT); +TRANS(UI_TEXT_EXTR_DGAIN_PT); +TRANS(UI_TEXT_EXTR_DMIN_PT); +TRANS(UI_TEXT_EXTR_DMAX_PT); +TRANS(UI_TEXT_EXTR_PMAX_PT); +TRANS(UI_TEXT_EXTR_XOFF_PT); +TRANS(UI_TEXT_EXTR_YOFF_PT); +TRANS(UI_TEXT_STRING_HM_BANGBANG_PT); +TRANS(UI_TEXT_STRING_HM_PID_PT); +TRANS(UI_TEXT_STRING_ACTION_PT); +TRANS(UI_TEXT_HEATING_EXTRUDER_PT); +TRANS(UI_TEXT_HEATING_BED_PT); +TRANS(UI_TEXT_KILLED_PT); +TRANS(UI_TEXT_STEPPER_DISABLED_PT); +TRANS(UI_TEXT_EEPROM_STOREDA_PT); +TRANS(UI_TEXT_EEPROM_STOREDB_PT); +TRANS(UI_TEXT_EEPROM_LOADEDA_PT); +TRANS(UI_TEXT_EEPROM_LOADEDB_PT); +TRANS(UI_TEXT_UPLOADING_PT); +TRANS(UI_TEXT_PAGE_BUFFER_PT); +TRANS(UI_TEXT_PAGE_EXTRUDER_PT); +TRANS(UI_TEXT_PAGE_EXTRUDER1_PT); +TRANS(UI_TEXT_PAGE_EXTRUDER2_PT); +TRANS(UI_TEXT_PAGE_EXTRUDER3_PT); +TRANS(UI_TEXT_PAGE_BED_PT); +TRANS(UI_TEXT_SPEED_MULTIPLY_PT); +TRANS(UI_TEXT_FLOW_MULTIPLY_PT); +TRANS(UI_TEXT_SHOW_MEASUREMENT_PT); +TRANS(UI_TEXT_RESET_MEASUREMENT_PT); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_PT); +TRANS(UI_TEXT_ZCALIB_PT); +TRANS(UI_TEXT_SET_P1_PT); +TRANS(UI_TEXT_SET_P2_PT); +TRANS(UI_TEXT_SET_P3_PT); +TRANS(UI_TEXT_CALCULATE_LEVELING_PT); +TRANS(UI_TEXT_LEVEL_PT); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_PT); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_PT); +TRANS(UI_TEXT_SD_REMOVED_PT); +TRANS(UI_TEXT_SD_INSERTED_PT); +TRANS(UI_TEXT_PRINTER_READY_PT); +TRANS(UI_TEXT_PRINTTIME_DAYS_PT); +TRANS(UI_TEXT_PRINTTIME_HOURS_PT); +TRANS(UI_TEXT_PRINTTIME_MINUTES_PT); +TRANS(UI_TEXT_PRINT_TIME_PT); +TRANS(UI_TEXT_PRINT_FILAMENT_PT); +TRANS(UI_TEXT_PRINTED_PT); +TRANS(UI_TEXT_POWER_PT); +TRANS(UI_TEXT_STRING_HM_DEADTIME_PT); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_PT); +TRANS(UI_TEXT_STOP_PRINT_PT); +TRANS(UI_TEXT_Z_BABYSTEPPING_PT); +TRANS(UI_TEXT_CHANGE_FILAMENT_PT); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_PT); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_PT); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_PT); +TRANS(UI_TEXT_CLICK_DONE_PT); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_PT); +TRANS(UI_TEXT_SERVOPOS_PT); +TRANS(UI_TEXT_IGNORE_M106_PT); +TRANS(UI_TEXT_WIZ_REHEAT1_PT); +TRANS(UI_TEXT_WIZ_REHEAT2_PT); +TRANS(UI_TEXT_WIZ_WAITTEMP1_PT); +TRANS(UI_TEXT_WIZ_WAITTEMP2_PT); +TRANS(UI_TEXT_EXTRUDER_JAM_PT); +TRANS(UI_TEXT_STANDBY_PT); +TRANS(UI_TEXT_BED_COATING_PT); +TRANS(UI_TEXT_BED_COATING_SET1_PT); +TRANS(UI_TEXT_BED_COATING_SET2_PT); +TRANS(UI_TEXT_NOCOATING_PT); +TRANS(UI_TEXT_BUILDTAK_PT); +TRANS(UI_TEXT_KAPTON_PT); +TRANS(UI_TEXT_BLUETAPE_PT); +TRANS(UI_TEXT_PETTAPE_PT); +TRANS(UI_TEXT_GLUESTICK_PT); +TRANS(UI_TEXT_CUSTOM_PT); +TRANS(UI_TEXT_COATING_CUSTOM_PT); +TRANS(UI_TEXT_LANGUAGE_PT); +TRANS(UI_TEXT_MAINPAGE6_1_PT); +TRANS(UI_TEXT_MAINPAGE6_2_PT); +TRANS(UI_TEXT_MAINPAGE6_3_PT); +TRANS(UI_TEXT_MAINPAGE6_4_PT); +TRANS(UI_TEXT_MAINPAGE6_5_PT); +TRANS(UI_TEXT_MAINPAGE6_6_PT); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_PT); +TRANS(UI_TEXT_MAINPAGE_BED_PT); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_PT); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_PT); +TRANS(UI_TEXT_MAINPAGE_XY_PT); +TRANS(UI_TEXT_PRINT_TIME_VALUE_PT); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_PT); +TRANS(UI_TEXT_METER_PRINTED_PT); +TRANS(UI_TEXT_STATUS_PT); +TRANS(UI_TEXT_EMPTY_PT); +TRANS(UI_TEXT_TEMP_SET_PT); +TRANS(UI_TEXT_CURRENT_TEMP_PT); +TRANS(UI_TEXT_COATING_THICKNESS_PT); +TRANS(UI_TEXT_EXTR3_TEMP_PT); +TRANS(UI_TEXT_EXTR4_TEMP_PT); +TRANS(UI_TEXT_EXTR5_TEMP_PT); +TRANS(UI_TEXT_EXTR3_OFF_PT); +TRANS(UI_TEXT_EXTR4_OFF_PT); +TRANS(UI_TEXT_EXTR5_OFF_PT); +TRANS(UI_TEXT_EXTR3_SELECT_PT); +TRANS(UI_TEXT_EXTR4_SELECT_PT); +TRANS(UI_TEXT_EXTR5_SELECT_PT); +TRANS(UI_TEXT_DITTO_0_PT); +TRANS(UI_TEXT_DITTO_1_PT); +TRANS(UI_TEXT_DITTO_2_PT); +TRANS(UI_TEXT_DITTO_3_PT); +TRANS(UI_TEXT_ZPROBE_HEIGHT_PT); +TRANS(UI_TEXT_OFFSETS_PT); +TRANS(UI_TEXT_X_OFFSET_PT); +TRANS(UI_TEXT_Y_OFFSET_PT); +TRANS(UI_TEXT_Z_OFFSET_PT); + +PGM_P const translations_pt[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_PT, + FUI_TEXT_OFF_PT, + FUI_TEXT_NA_PT, + FUI_TEXT_YES_PT, + FUI_TEXT_NO_PT, + FUI_TEXT_PRINT_POS_PT, + FUI_TEXT_PRINTING_PT, + FUI_TEXT_IDLE_PT, + FUI_TEXT_NOSDCARD_PT, + FUI_TEXT_ERROR_PT, + FUI_TEXT_BACK_PT, + FUI_TEXT_QUICK_SETTINGS_PT, + FUI_TEXT_ERRORMSG_PT, + FUI_TEXT_CONFIGURATION_PT, + FUI_TEXT_POSITION_PT, + FUI_TEXT_EXTRUDER_PT, + FUI_TEXT_SD_CARD_PT, + FUI_TEXT_DEBUGGING_PT, + FUI_TEXT_HOME_DELTA_PT, + FUI_TEXT_HOME_ALL_PT, + FUI_TEXT_HOME_X_PT, + FUI_TEXT_HOME_Y_PT, + FUI_TEXT_HOME_Z_PT, + FUI_TEXT_PREHEAT_PLA_PT, + FUI_TEXT_PREHEAT_ABS_PT, + FUI_TEXT_LIGHTS_ONOFF_PT, + FUI_TEXT_COOLDOWN_PT, + FUI_TEXT_SET_TO_ORIGIN_PT, + FUI_TEXT_DISABLE_STEPPER_PT, + FUI_TEXT_X_POSITION_PT, + FUI_TEXT_X_POS_FAST_PT, + FUI_TEXT_Y_POSITION_PT, + FUI_TEXT_Y_POS_FAST_PT, + FUI_TEXT_Z_POSITION_PT, + FUI_TEXT_Z_POS_FAST_PT, + FUI_TEXT_E_POSITION_PT, + FUI_TEXT_BED_TEMP_PT, + FUI_TEXT_EXTR0_TEMP_PT, + FUI_TEXT_EXTR1_TEMP_PT, + FUI_TEXT_EXTR2_TEMP_PT, + FUI_TEXT_EXTR0_OFF_PT, + FUI_TEXT_EXTR1_OFF_PT, + FUI_TEXT_EXTR2_OFF_PT, + FUI_TEXT_EXTR0_SELECT_PT, + FUI_TEXT_EXTR1_SELECT_PT, + FUI_TEXT_EXTR2_SELECT_PT, + FUI_TEXT_EXTR_ORIGIN_PT, + FUI_TEXT_PRINT_X_PT, + FUI_TEXT_PRINT_Y_PT, + FUI_TEXT_PRINT_Z_PT, + FUI_TEXT_PRINT_Z_DELTA_PT, + FUI_TEXT_MOVE_X_PT, + FUI_TEXT_MOVE_Y_PT, + FUI_TEXT_MOVE_Z_PT, + FUI_TEXT_MOVE_Z_DELTA_PT, + FUI_TEXT_JERK_PT, + FUI_TEXT_ZJERK_PT, + FUI_TEXT_ACCELERATION_PT, + FUI_TEXT_STORE_TO_EEPROM_PT, + FUI_TEXT_LOAD_EEPROM_PT, + FUI_TEXT_DBG_ECHO_PT, + FUI_TEXT_DBG_INFO_PT, + FUI_TEXT_DBG_ERROR_PT, + FUI_TEXT_DBG_DRYRUN_PT, + FUI_TEXT_OPS_OFF_PT, + FUI_TEXT_OPS_CLASSIC_PT, + FUI_TEXT_OPS_FAST_PT, + FUI_TEXT_OPS_RETRACT_PT, + FUI_TEXT_OPS_BACKSLASH_PT, + FUI_TEXT_OPS_MINDIST_PT, + FUI_TEXT_OPS_MOVE_AFTER_PT, + FUI_TEXT_ANTI_OOZE_PT, + FUI_TEXT_PRINT_FILE_PT, + FUI_TEXT_PAUSE_PRINT_PT, + FUI_TEXT_CONTINUE_PRINT_PT, + FUI_TEXT_UNMOUNT_CARD_PT, + FUI_TEXT_MOUNT_CARD_PT, + FUI_TEXT_DELETE_FILE_PT, + FUI_TEXT_FEEDRATE_PT, + FUI_TEXT_FEED_MAX_X_PT, + FUI_TEXT_FEED_MAX_Y_PT, + FUI_TEXT_FEED_MAX_Z_PT, + FUI_TEXT_FEED_MAX_Z_DELTA_PT, + FUI_TEXT_FEED_HOME_X_PT, + FUI_TEXT_FEED_HOME_Y_PT, + FUI_TEXT_FEED_HOME_Z_PT, + FUI_TEXT_FEED_HOME_Z_DELTA_PT, + FUI_TEXT_ACTION_XPOSITION4A_PT, + FUI_TEXT_ACTION_XPOSITION4B_PT, + FUI_TEXT_ACTION_XPOSITION4C_PT, + FUI_TEXT_ACTION_XPOSITION4D_PT, + FUI_TEXT_ACTION_YPOSITION4A_PT, + FUI_TEXT_ACTION_YPOSITION4B_PT, + FUI_TEXT_ACTION_YPOSITION4C_PT, + FUI_TEXT_ACTION_YPOSITION4D_PT, + FUI_TEXT_ACTION_ZPOSITION4A_PT, + FUI_TEXT_ACTION_ZPOSITION4B_PT, + FUI_TEXT_ACTION_ZPOSITION4C_PT, + FUI_TEXT_ACTION_ZPOSITION4D_PT, + FUI_TEXT_ACTION_XPOSITION_FAST4A_PT, + FUI_TEXT_ACTION_XPOSITION_FAST4B_PT, + FUI_TEXT_ACTION_XPOSITION_FAST4C_PT, + FUI_TEXT_ACTION_XPOSITION_FAST4D_PT, + FUI_TEXT_ACTION_YPOSITION_FAST4A_PT, + FUI_TEXT_ACTION_YPOSITION_FAST4B_PT, + FUI_TEXT_ACTION_YPOSITION_FAST4C_PT, + FUI_TEXT_ACTION_YPOSITION_FAST4D_PT, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_PT, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_PT, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_PT, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_PT, + FUI_TEXT_ACTION_EPOSITION_FAST2A_PT, + FUI_TEXT_ACTION_EPOSITION_FAST2B_PT, + FUI_TEXT_ACTION_XPOSITION2A_PT, + FUI_TEXT_ACTION_XPOSITION2B_PT, + FUI_TEXT_ACTION_YPOSITION2A_PT, + FUI_TEXT_ACTION_YPOSITION2B_PT, + FUI_TEXT_ACTION_ZPOSITION2A_PT, + FUI_TEXT_ACTION_ZPOSITION2B_PT, + FUI_TEXT_ACTION_XPOSITION_FAST2A_PT, + FUI_TEXT_ACTION_XPOSITION_FAST2B_PT, + FUI_TEXT_ACTION_YPOSITION_FAST2A_PT, + FUI_TEXT_ACTION_YPOSITION_FAST2B_PT, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_PT, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_PT, + FUI_TEXT_FANSPEED_PT, + FUI_TEXT_ACTION_FANSPEED_PT, + FUI_TEXT_FAN_OFF_PT, + FUI_TEXT_FAN_25_PT, + FUI_TEXT_FAN_50_PT, + FUI_TEXT_FAN_75_PT, + FUI_TEXT_FAN_FULL_PT, + FUI_TEXT_STEPPER_INACTIVE_PT, + FUI_TEXT_STEPPER_INACTIVE2A_PT, + FUI_TEXT_STEPPER_INACTIVE2B_PT, + FUI_TEXT_POWER_INACTIVE_PT, + FUI_TEXT_POWER_INACTIVE2A_PT, + FUI_TEXT_POWER_INACTIVE2B_PT, + FUI_TEXT_GENERAL_PT, + FUI_TEXT_BAUDRATE_PT, + FUI_TEXT_EXTR_STEPS_PT, + FUI_TEXT_EXTR_START_FEED_PT, + FUI_TEXT_EXTR_MAX_FEED_PT, + FUI_TEXT_EXTR_ACCEL_PT, + FUI_TEXT_EXTR_WATCH_PT, + FUI_TEXT_EXTR_ADVANCE_L_PT, + FUI_TEXT_EXTR_ADVANCE_K_PT, + FUI_TEXT_EXTR_MANAGER_PT, + FUI_TEXT_EXTR_PGAIN_PT, + FUI_TEXT_EXTR_DEADTIME_PT, + FUI_TEXT_EXTR_DMAX_DT_PT, + FUI_TEXT_EXTR_IGAIN_PT, + FUI_TEXT_EXTR_DGAIN_PT, + FUI_TEXT_EXTR_DMIN_PT, + FUI_TEXT_EXTR_DMAX_PT, + FUI_TEXT_EXTR_PMAX_PT, + FUI_TEXT_EXTR_XOFF_PT, + FUI_TEXT_EXTR_YOFF_PT, + FUI_TEXT_STRING_HM_BANGBANG_PT, + FUI_TEXT_STRING_HM_PID_PT, + FUI_TEXT_STRING_ACTION_PT, + FUI_TEXT_HEATING_EXTRUDER_PT, + FUI_TEXT_HEATING_BED_PT, + FUI_TEXT_KILLED_PT, + FUI_TEXT_STEPPER_DISABLED_PT, + FUI_TEXT_EEPROM_STOREDA_PT, + FUI_TEXT_EEPROM_STOREDB_PT, + FUI_TEXT_EEPROM_LOADEDA_PT, + FUI_TEXT_EEPROM_LOADEDB_PT, + FUI_TEXT_UPLOADING_PT, + FUI_TEXT_PAGE_BUFFER_PT, + FUI_TEXT_PAGE_EXTRUDER_PT, + FUI_TEXT_PAGE_EXTRUDER1_PT, + FUI_TEXT_PAGE_EXTRUDER2_PT, + FUI_TEXT_PAGE_EXTRUDER3_PT, + FUI_TEXT_PAGE_BED_PT, + FUI_TEXT_SPEED_MULTIPLY_PT, + FUI_TEXT_FLOW_MULTIPLY_PT, + FUI_TEXT_SHOW_MEASUREMENT_PT, + FUI_TEXT_RESET_MEASUREMENT_PT, + FUI_TEXT_SET_MEASURED_ORIGIN_PT, + FUI_TEXT_ZCALIB_PT, + FUI_TEXT_SET_P1_PT, + FUI_TEXT_SET_P2_PT, + FUI_TEXT_SET_P3_PT, + FUI_TEXT_CALCULATE_LEVELING_PT, + FUI_TEXT_LEVEL_PT, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_PT, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_PT, + FUI_TEXT_SD_REMOVED_PT, + FUI_TEXT_SD_INSERTED_PT, + FUI_TEXT_PRINTER_READY_PT, + FUI_TEXT_PRINTTIME_DAYS_PT, + FUI_TEXT_PRINTTIME_HOURS_PT, + FUI_TEXT_PRINTTIME_MINUTES_PT, + FUI_TEXT_PRINT_TIME_PT, + FUI_TEXT_PRINT_FILAMENT_PT, + FUI_TEXT_PRINTED_PT, + FUI_TEXT_POWER_PT, + FUI_TEXT_STRING_HM_DEADTIME_PT, + FUI_TEXT_STRING_HM_SLOWBANG_PT, + FUI_TEXT_STOP_PRINT_PT, + FUI_TEXT_Z_BABYSTEPPING_PT, + FUI_TEXT_CHANGE_FILAMENT_PT, + FUI_TEXT_WIZ_CH_FILAMENT1_PT, + FUI_TEXT_WIZ_CH_FILAMENT2_PT, + FUI_TEXT_WIZ_CH_FILAMENT3_PT, + FUI_TEXT_CLICK_DONE_PT, + FUI_TEXT_AUTOLEVEL_ONOFF_PT, + FUI_TEXT_SERVOPOS_PT, + FUI_TEXT_IGNORE_M106_PT, + FUI_TEXT_WIZ_REHEAT1_PT, + FUI_TEXT_WIZ_REHEAT2_PT, + FUI_TEXT_WIZ_WAITTEMP1_PT, + FUI_TEXT_WIZ_WAITTEMP2_PT, + FUI_TEXT_EXTRUDER_JAM_PT, + FUI_TEXT_STANDBY_PT, + FUI_TEXT_BED_COATING_PT, + FUI_TEXT_BED_COATING_SET1_PT, + FUI_TEXT_BED_COATING_SET2_PT, + FUI_TEXT_NOCOATING_PT, + FUI_TEXT_BUILDTAK_PT, + FUI_TEXT_KAPTON_PT, + FUI_TEXT_BLUETAPE_PT, + FUI_TEXT_PETTAPE_PT, + FUI_TEXT_GLUESTICK_PT, + FUI_TEXT_CUSTOM_PT, + FUI_TEXT_COATING_CUSTOM_PT, + FUI_TEXT_LANGUAGE_PT, + FUI_TEXT_MAINPAGE6_1_PT, + FUI_TEXT_MAINPAGE6_2_PT, + FUI_TEXT_MAINPAGE6_3_PT, + FUI_TEXT_MAINPAGE6_4_PT, + FUI_TEXT_MAINPAGE6_5_PT, + FUI_TEXT_MAINPAGE6_6_PT, + FUI_TEXT_MAINPAGE_TEMP_BED_PT, + FUI_TEXT_MAINPAGE_BED_PT, + FUI_TEXT_MAINPAGE_Z_BUF_PT, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_PT, + FUI_TEXT_MAINPAGE_XY_PT, + FUI_TEXT_PRINT_TIME_VALUE_PT, + FUI_TEXT_PRINT_FILAMENT_VALUE_PT, + FUI_TEXT_METER_PRINTED_PT, + FUI_TEXT_STATUS_PT, + FUI_TEXT_EMPTY_PT, + FUI_TEXT_TEMP_SET_PT, + FUI_TEXT_CURRENT_TEMP_PT, + FUI_TEXT_COATING_THICKNESS_PT, + FUI_TEXT_EXTR3_TEMP_PT, + FUI_TEXT_EXTR4_TEMP_PT, + FUI_TEXT_EXTR5_TEMP_PT, + FUI_TEXT_EXTR3_OFF_PT, + FUI_TEXT_EXTR4_OFF_PT, + FUI_TEXT_EXTR5_OFF_PT, + FUI_TEXT_EXTR3_SELECT_PT, + FUI_TEXT_EXTR4_SELECT_PT, + FUI_TEXT_EXTR5_SELECT_PT, + FUI_TEXT_DITTO_0_PT, + FUI_TEXT_DITTO_1_PT, + FUI_TEXT_DITTO_2_PT, + FUI_TEXT_DITTO_3_PT, + FUI_TEXT_ZPROBE_HEIGHT_PT, + FUI_TEXT_OFFSETS_PT, + FUI_TEXT_X_OFFSET_PT, + FUI_TEXT_Y_OFFSET_PT, + FUI_TEXT_Z_OFFSET_PT +}; +#define LANG_PT_TABLE translations_pt +#else +#define LANG_PT_TABLE NULL +#endif // LANGUAGE_PT_ACTIVE + + +#if LANGUAGE_IT_ACTIVE +TRANS(UI_TEXT_ON_IT); +TRANS(UI_TEXT_OFF_IT); +TRANS(UI_TEXT_NA_IT); +TRANS(UI_TEXT_YES_IT); +TRANS(UI_TEXT_NO_IT); +TRANS(UI_TEXT_PRINT_POS_IT); +TRANS(UI_TEXT_PRINTING_IT); +TRANS(UI_TEXT_IDLE_IT); +TRANS(UI_TEXT_NOSDCARD_IT); +TRANS(UI_TEXT_ERROR_IT); +TRANS(UI_TEXT_BACK_IT); +TRANS(UI_TEXT_QUICK_SETTINGS_IT); +TRANS(UI_TEXT_ERRORMSG_IT); +TRANS(UI_TEXT_CONFIGURATION_IT); +TRANS(UI_TEXT_POSITION_IT); +TRANS(UI_TEXT_EXTRUDER_IT); +TRANS(UI_TEXT_SD_CARD_IT); +TRANS(UI_TEXT_DEBUGGING_IT); +TRANS(UI_TEXT_HOME_DELTA_IT); +TRANS(UI_TEXT_HOME_ALL_IT); +TRANS(UI_TEXT_HOME_X_IT); +TRANS(UI_TEXT_HOME_Y_IT); +TRANS(UI_TEXT_HOME_Z_IT); +TRANS(UI_TEXT_PREHEAT_PLA_IT); +TRANS(UI_TEXT_PREHEAT_ABS_IT); +TRANS(UI_TEXT_LIGHTS_ONOFF_IT); +TRANS(UI_TEXT_COOLDOWN_IT); +TRANS(UI_TEXT_SET_TO_ORIGIN_IT); +TRANS(UI_TEXT_DISABLE_STEPPER_IT); +TRANS(UI_TEXT_X_POSITION_IT); +TRANS(UI_TEXT_X_POS_FAST_IT); +TRANS(UI_TEXT_Y_POSITION_IT); +TRANS(UI_TEXT_Y_POS_FAST_IT); +TRANS(UI_TEXT_Z_POSITION_IT); +TRANS(UI_TEXT_Z_POS_FAST_IT); +TRANS(UI_TEXT_E_POSITION_IT); +TRANS(UI_TEXT_BED_TEMP_IT); +TRANS(UI_TEXT_EXTR0_TEMP_IT); +TRANS(UI_TEXT_EXTR1_TEMP_IT); +TRANS(UI_TEXT_EXTR2_TEMP_IT); +TRANS(UI_TEXT_EXTR0_OFF_IT); +TRANS(UI_TEXT_EXTR1_OFF_IT); +TRANS(UI_TEXT_EXTR2_OFF_IT); +TRANS(UI_TEXT_EXTR0_SELECT_IT); +TRANS(UI_TEXT_EXTR1_SELECT_IT); +TRANS(UI_TEXT_EXTR2_SELECT_IT); +TRANS(UI_TEXT_EXTR_ORIGIN_IT); +TRANS(UI_TEXT_PRINT_X_IT); +TRANS(UI_TEXT_PRINT_Y_IT); +TRANS(UI_TEXT_PRINT_Z_IT); +TRANS(UI_TEXT_PRINT_Z_DELTA_IT); +TRANS(UI_TEXT_MOVE_X_IT); +TRANS(UI_TEXT_MOVE_Y_IT); +TRANS(UI_TEXT_MOVE_Z_IT); +TRANS(UI_TEXT_MOVE_Z_DELTA_IT); +TRANS(UI_TEXT_JERK_IT); +TRANS(UI_TEXT_ZJERK_IT); +TRANS(UI_TEXT_ACCELERATION_IT); +TRANS(UI_TEXT_STORE_TO_EEPROM_IT); +TRANS(UI_TEXT_LOAD_EEPROM_IT); +TRANS(UI_TEXT_DBG_ECHO_IT); +TRANS(UI_TEXT_DBG_INFO_IT); +TRANS(UI_TEXT_DBG_ERROR_IT); +TRANS(UI_TEXT_DBG_DRYRUN_IT); +TRANS(UI_TEXT_OPS_OFF_IT); +TRANS(UI_TEXT_OPS_CLASSIC_IT); +TRANS(UI_TEXT_OPS_FAST_IT); +TRANS(UI_TEXT_OPS_RETRACT_IT); +TRANS(UI_TEXT_OPS_BACKSLASH_IT); +TRANS(UI_TEXT_OPS_MINDIST_IT); +TRANS(UI_TEXT_OPS_MOVE_AFTER_IT); +TRANS(UI_TEXT_ANTI_OOZE_IT); +TRANS(UI_TEXT_PRINT_FILE_IT); +TRANS(UI_TEXT_PAUSE_PRINT_IT); +TRANS(UI_TEXT_CONTINUE_PRINT_IT); +TRANS(UI_TEXT_UNMOUNT_CARD_IT); +TRANS(UI_TEXT_MOUNT_CARD_IT); +TRANS(UI_TEXT_DELETE_FILE_IT); +TRANS(UI_TEXT_FEEDRATE_IT); +TRANS(UI_TEXT_FEED_MAX_X_IT); +TRANS(UI_TEXT_FEED_MAX_Y_IT); +TRANS(UI_TEXT_FEED_MAX_Z_IT); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_IT); +TRANS(UI_TEXT_FEED_HOME_X_IT); +TRANS(UI_TEXT_FEED_HOME_Y_IT); +TRANS(UI_TEXT_FEED_HOME_Z_IT); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_IT); +TRANS(UI_TEXT_ACTION_XPOSITION4A_IT); +TRANS(UI_TEXT_ACTION_XPOSITION4B_IT); +TRANS(UI_TEXT_ACTION_XPOSITION4C_IT); +TRANS(UI_TEXT_ACTION_XPOSITION4D_IT); +TRANS(UI_TEXT_ACTION_YPOSITION4A_IT); +TRANS(UI_TEXT_ACTION_YPOSITION4B_IT); +TRANS(UI_TEXT_ACTION_YPOSITION4C_IT); +TRANS(UI_TEXT_ACTION_YPOSITION4D_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_IT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_IT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_IT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_IT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_IT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_IT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_IT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_IT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_IT); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_IT); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_IT); +TRANS(UI_TEXT_ACTION_XPOSITION2A_IT); +TRANS(UI_TEXT_ACTION_XPOSITION2B_IT); +TRANS(UI_TEXT_ACTION_YPOSITION2A_IT); +TRANS(UI_TEXT_ACTION_YPOSITION2B_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_IT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_IT); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_IT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_IT); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_IT); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_IT); +TRANS(UI_TEXT_FANSPEED_IT); +TRANS(UI_TEXT_ACTION_FANSPEED_IT); +TRANS(UI_TEXT_FAN_OFF_IT); +TRANS(UI_TEXT_FAN_25_IT); +TRANS(UI_TEXT_FAN_50_IT); +TRANS(UI_TEXT_FAN_75_IT); +TRANS(UI_TEXT_FAN_FULL_IT); +TRANS(UI_TEXT_STEPPER_INACTIVE_IT); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_IT); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_IT); +TRANS(UI_TEXT_POWER_INACTIVE_IT); +TRANS(UI_TEXT_POWER_INACTIVE2A_IT); +TRANS(UI_TEXT_POWER_INACTIVE2B_IT); +TRANS(UI_TEXT_GENERAL_IT); +TRANS(UI_TEXT_BAUDRATE_IT); +TRANS(UI_TEXT_EXTR_STEPS_IT); +TRANS(UI_TEXT_EXTR_START_FEED_IT); +TRANS(UI_TEXT_EXTR_MAX_FEED_IT); +TRANS(UI_TEXT_EXTR_ACCEL_IT); +TRANS(UI_TEXT_EXTR_WATCH_IT); +TRANS(UI_TEXT_EXTR_ADVANCE_L_IT); +TRANS(UI_TEXT_EXTR_ADVANCE_K_IT); +TRANS(UI_TEXT_EXTR_MANAGER_IT); +TRANS(UI_TEXT_EXTR_PGAIN_IT); +TRANS(UI_TEXT_EXTR_DEADTIME_IT); +TRANS(UI_TEXT_EXTR_DMAX_DT_IT); +TRANS(UI_TEXT_EXTR_IGAIN_IT); +TRANS(UI_TEXT_EXTR_DGAIN_IT); +TRANS(UI_TEXT_EXTR_DMIN_IT); +TRANS(UI_TEXT_EXTR_DMAX_IT); +TRANS(UI_TEXT_EXTR_PMAX_IT); +TRANS(UI_TEXT_EXTR_XOFF_IT); +TRANS(UI_TEXT_EXTR_YOFF_IT); +TRANS(UI_TEXT_STRING_HM_BANGBANG_IT); +TRANS(UI_TEXT_STRING_HM_PID_IT); +TRANS(UI_TEXT_STRING_ACTION_IT); +TRANS(UI_TEXT_HEATING_EXTRUDER_IT); +TRANS(UI_TEXT_HEATING_BED_IT); +TRANS(UI_TEXT_KILLED_IT); +TRANS(UI_TEXT_STEPPER_DISABLED_IT); +TRANS(UI_TEXT_EEPROM_STOREDA_IT); +TRANS(UI_TEXT_EEPROM_STOREDB_IT); +TRANS(UI_TEXT_EEPROM_LOADEDA_IT); +TRANS(UI_TEXT_EEPROM_LOADEDB_IT); +TRANS(UI_TEXT_UPLOADING_IT); +TRANS(UI_TEXT_PAGE_BUFFER_IT); +TRANS(UI_TEXT_PAGE_EXTRUDER_IT); +TRANS(UI_TEXT_PAGE_EXTRUDER1_IT); +TRANS(UI_TEXT_PAGE_EXTRUDER2_IT); +TRANS(UI_TEXT_PAGE_EXTRUDER3_IT); +TRANS(UI_TEXT_PAGE_BED_IT); +TRANS(UI_TEXT_SPEED_MULTIPLY_IT); +TRANS(UI_TEXT_FLOW_MULTIPLY_IT); +TRANS(UI_TEXT_SHOW_MEASUREMENT_IT); +TRANS(UI_TEXT_RESET_MEASUREMENT_IT); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_IT); +TRANS(UI_TEXT_ZCALIB_IT); +TRANS(UI_TEXT_SET_P1_IT); +TRANS(UI_TEXT_SET_P2_IT); +TRANS(UI_TEXT_SET_P3_IT); +TRANS(UI_TEXT_CALCULATE_LEVELING_IT); +TRANS(UI_TEXT_LEVEL_IT); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_IT); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_IT); +TRANS(UI_TEXT_SD_REMOVED_IT); +TRANS(UI_TEXT_SD_INSERTED_IT); +TRANS(UI_TEXT_PRINTER_READY_IT); +TRANS(UI_TEXT_PRINTTIME_DAYS_IT); +TRANS(UI_TEXT_PRINTTIME_HOURS_IT); +TRANS(UI_TEXT_PRINTTIME_MINUTES_IT); +TRANS(UI_TEXT_PRINT_TIME_IT); +TRANS(UI_TEXT_PRINT_FILAMENT_IT); +TRANS(UI_TEXT_PRINTED_IT); +TRANS(UI_TEXT_POWER_IT); +TRANS(UI_TEXT_STRING_HM_DEADTIME_IT); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_IT); +TRANS(UI_TEXT_STOP_PRINT_IT); +TRANS(UI_TEXT_Z_BABYSTEPPING_IT); +TRANS(UI_TEXT_CHANGE_FILAMENT_IT); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_IT); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_IT); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_IT); +TRANS(UI_TEXT_CLICK_DONE_IT); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_IT); +TRANS(UI_TEXT_SERVOPOS_IT); +TRANS(UI_TEXT_IGNORE_M106_IT); +TRANS(UI_TEXT_WIZ_REHEAT1_IT); +TRANS(UI_TEXT_WIZ_REHEAT2_IT); +TRANS(UI_TEXT_WIZ_WAITTEMP1_IT); +TRANS(UI_TEXT_WIZ_WAITTEMP2_IT); +TRANS(UI_TEXT_EXTRUDER_JAM_IT); +TRANS(UI_TEXT_STANDBY_IT); +TRANS(UI_TEXT_BED_COATING_IT); +TRANS(UI_TEXT_BED_COATING_SET1_IT); +TRANS(UI_TEXT_BED_COATING_SET2_IT); +TRANS(UI_TEXT_NOCOATING_IT); +TRANS(UI_TEXT_BUILDTAK_IT); +TRANS(UI_TEXT_KAPTON_IT); +TRANS(UI_TEXT_BLUETAPE_IT); +TRANS(UI_TEXT_PETTAPE_IT); +TRANS(UI_TEXT_GLUESTICK_IT); +TRANS(UI_TEXT_CUSTOM_IT); +TRANS(UI_TEXT_COATING_CUSTOM_IT); +TRANS(UI_TEXT_LANGUAGE_IT); +TRANS(UI_TEXT_MAINPAGE6_1_IT); +TRANS(UI_TEXT_MAINPAGE6_2_IT); +TRANS(UI_TEXT_MAINPAGE6_3_IT); +TRANS(UI_TEXT_MAINPAGE6_4_IT); +TRANS(UI_TEXT_MAINPAGE6_5_IT); +TRANS(UI_TEXT_MAINPAGE6_6_IT); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_IT); +TRANS(UI_TEXT_MAINPAGE_BED_IT); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_IT); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_IT); +TRANS(UI_TEXT_MAINPAGE_XY_IT); +TRANS(UI_TEXT_PRINT_TIME_VALUE_IT); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_IT); +TRANS(UI_TEXT_METER_PRINTED_IT); +TRANS(UI_TEXT_STATUS_IT); +TRANS(UI_TEXT_EMPTY_IT); +TRANS(UI_TEXT_TEMP_SET_IT); +TRANS(UI_TEXT_CURRENT_TEMP_IT); +TRANS(UI_TEXT_COATING_THICKNESS_IT); +TRANS(UI_TEXT_EXTR3_TEMP_IT); +TRANS(UI_TEXT_EXTR4_TEMP_IT); +TRANS(UI_TEXT_EXTR5_TEMP_IT); +TRANS(UI_TEXT_EXTR3_OFF_IT); +TRANS(UI_TEXT_EXTR4_OFF_IT); +TRANS(UI_TEXT_EXTR5_OFF_IT); +TRANS(UI_TEXT_EXTR3_SELECT_IT); +TRANS(UI_TEXT_EXTR4_SELECT_IT); +TRANS(UI_TEXT_EXTR5_SELECT_IT); +TRANS(UI_TEXT_DITTO_0_IT); +TRANS(UI_TEXT_DITTO_1_IT); +TRANS(UI_TEXT_DITTO_2_IT); +TRANS(UI_TEXT_DITTO_3_IT); +TRANS(UI_TEXT_ZPROBE_HEIGHT_IT); +TRANS(UI_TEXT_OFFSETS_IT); +TRANS(UI_TEXT_X_OFFSET_IT); +TRANS(UI_TEXT_Y_OFFSET_IT); +TRANS(UI_TEXT_Z_OFFSET_IT); + +PGM_P const translations_it[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_IT, + FUI_TEXT_OFF_IT, + FUI_TEXT_NA_IT, + FUI_TEXT_YES_IT, + FUI_TEXT_NO_IT, + FUI_TEXT_PRINT_POS_IT, + FUI_TEXT_PRINTING_IT, + FUI_TEXT_IDLE_IT, + FUI_TEXT_NOSDCARD_IT, + FUI_TEXT_ERROR_IT, + FUI_TEXT_BACK_IT, + FUI_TEXT_QUICK_SETTINGS_IT, + FUI_TEXT_ERRORMSG_IT, + FUI_TEXT_CONFIGURATION_IT, + FUI_TEXT_POSITION_IT, + FUI_TEXT_EXTRUDER_IT, + FUI_TEXT_SD_CARD_IT, + FUI_TEXT_DEBUGGING_IT, + FUI_TEXT_HOME_DELTA_IT, + FUI_TEXT_HOME_ALL_IT, + FUI_TEXT_HOME_X_IT, + FUI_TEXT_HOME_Y_IT, + FUI_TEXT_HOME_Z_IT, + FUI_TEXT_PREHEAT_PLA_IT, + FUI_TEXT_PREHEAT_ABS_IT, + FUI_TEXT_LIGHTS_ONOFF_IT, + FUI_TEXT_COOLDOWN_IT, + FUI_TEXT_SET_TO_ORIGIN_IT, + FUI_TEXT_DISABLE_STEPPER_IT, + FUI_TEXT_X_POSITION_IT, + FUI_TEXT_X_POS_FAST_IT, + FUI_TEXT_Y_POSITION_IT, + FUI_TEXT_Y_POS_FAST_IT, + FUI_TEXT_Z_POSITION_IT, + FUI_TEXT_Z_POS_FAST_IT, + FUI_TEXT_E_POSITION_IT, + FUI_TEXT_BED_TEMP_IT, + FUI_TEXT_EXTR0_TEMP_IT, + FUI_TEXT_EXTR1_TEMP_IT, + FUI_TEXT_EXTR2_TEMP_IT, + FUI_TEXT_EXTR0_OFF_IT, + FUI_TEXT_EXTR1_OFF_IT, + FUI_TEXT_EXTR2_OFF_IT, + FUI_TEXT_EXTR0_SELECT_IT, + FUI_TEXT_EXTR1_SELECT_IT, + FUI_TEXT_EXTR2_SELECT_IT, + FUI_TEXT_EXTR_ORIGIN_IT, + FUI_TEXT_PRINT_X_IT, + FUI_TEXT_PRINT_Y_IT, + FUI_TEXT_PRINT_Z_IT, + FUI_TEXT_PRINT_Z_DELTA_IT, + FUI_TEXT_MOVE_X_IT, + FUI_TEXT_MOVE_Y_IT, + FUI_TEXT_MOVE_Z_IT, + FUI_TEXT_MOVE_Z_DELTA_IT, + FUI_TEXT_JERK_IT, + FUI_TEXT_ZJERK_IT, + FUI_TEXT_ACCELERATION_IT, + FUI_TEXT_STORE_TO_EEPROM_IT, + FUI_TEXT_LOAD_EEPROM_IT, + FUI_TEXT_DBG_ECHO_IT, + FUI_TEXT_DBG_INFO_IT, + FUI_TEXT_DBG_ERROR_IT, + FUI_TEXT_DBG_DRYRUN_IT, + FUI_TEXT_OPS_OFF_IT, + FUI_TEXT_OPS_CLASSIC_IT, + FUI_TEXT_OPS_FAST_IT, + FUI_TEXT_OPS_RETRACT_IT, + FUI_TEXT_OPS_BACKSLASH_IT, + FUI_TEXT_OPS_MINDIST_IT, + FUI_TEXT_OPS_MOVE_AFTER_IT, + FUI_TEXT_ANTI_OOZE_IT, + FUI_TEXT_PRINT_FILE_IT, + FUI_TEXT_PAUSE_PRINT_IT, + FUI_TEXT_CONTINUE_PRINT_IT, + FUI_TEXT_UNMOUNT_CARD_IT, + FUI_TEXT_MOUNT_CARD_IT, + FUI_TEXT_DELETE_FILE_IT, + FUI_TEXT_FEEDRATE_IT, + FUI_TEXT_FEED_MAX_X_IT, + FUI_TEXT_FEED_MAX_Y_IT, + FUI_TEXT_FEED_MAX_Z_IT, + FUI_TEXT_FEED_MAX_Z_DELTA_IT, + FUI_TEXT_FEED_HOME_X_IT, + FUI_TEXT_FEED_HOME_Y_IT, + FUI_TEXT_FEED_HOME_Z_IT, + FUI_TEXT_FEED_HOME_Z_DELTA_IT, + FUI_TEXT_ACTION_XPOSITION4A_IT, + FUI_TEXT_ACTION_XPOSITION4B_IT, + FUI_TEXT_ACTION_XPOSITION4C_IT, + FUI_TEXT_ACTION_XPOSITION4D_IT, + FUI_TEXT_ACTION_YPOSITION4A_IT, + FUI_TEXT_ACTION_YPOSITION4B_IT, + FUI_TEXT_ACTION_YPOSITION4C_IT, + FUI_TEXT_ACTION_YPOSITION4D_IT, + FUI_TEXT_ACTION_ZPOSITION4A_IT, + FUI_TEXT_ACTION_ZPOSITION4B_IT, + FUI_TEXT_ACTION_ZPOSITION4C_IT, + FUI_TEXT_ACTION_ZPOSITION4D_IT, + FUI_TEXT_ACTION_XPOSITION_FAST4A_IT, + FUI_TEXT_ACTION_XPOSITION_FAST4B_IT, + FUI_TEXT_ACTION_XPOSITION_FAST4C_IT, + FUI_TEXT_ACTION_XPOSITION_FAST4D_IT, + FUI_TEXT_ACTION_YPOSITION_FAST4A_IT, + FUI_TEXT_ACTION_YPOSITION_FAST4B_IT, + FUI_TEXT_ACTION_YPOSITION_FAST4C_IT, + FUI_TEXT_ACTION_YPOSITION_FAST4D_IT, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_IT, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_IT, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_IT, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_IT, + FUI_TEXT_ACTION_EPOSITION_FAST2A_IT, + FUI_TEXT_ACTION_EPOSITION_FAST2B_IT, + FUI_TEXT_ACTION_XPOSITION2A_IT, + FUI_TEXT_ACTION_XPOSITION2B_IT, + FUI_TEXT_ACTION_YPOSITION2A_IT, + FUI_TEXT_ACTION_YPOSITION2B_IT, + FUI_TEXT_ACTION_ZPOSITION2A_IT, + FUI_TEXT_ACTION_ZPOSITION2B_IT, + FUI_TEXT_ACTION_XPOSITION_FAST2A_IT, + FUI_TEXT_ACTION_XPOSITION_FAST2B_IT, + FUI_TEXT_ACTION_YPOSITION_FAST2A_IT, + FUI_TEXT_ACTION_YPOSITION_FAST2B_IT, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_IT, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_IT, + FUI_TEXT_FANSPEED_IT, + FUI_TEXT_ACTION_FANSPEED_IT, + FUI_TEXT_FAN_OFF_IT, + FUI_TEXT_FAN_25_IT, + FUI_TEXT_FAN_50_IT, + FUI_TEXT_FAN_75_IT, + FUI_TEXT_FAN_FULL_IT, + FUI_TEXT_STEPPER_INACTIVE_IT, + FUI_TEXT_STEPPER_INACTIVE2A_IT, + FUI_TEXT_STEPPER_INACTIVE2B_IT, + FUI_TEXT_POWER_INACTIVE_IT, + FUI_TEXT_POWER_INACTIVE2A_IT, + FUI_TEXT_POWER_INACTIVE2B_IT, + FUI_TEXT_GENERAL_IT, + FUI_TEXT_BAUDRATE_IT, + FUI_TEXT_EXTR_STEPS_IT, + FUI_TEXT_EXTR_START_FEED_IT, + FUI_TEXT_EXTR_MAX_FEED_IT, + FUI_TEXT_EXTR_ACCEL_IT, + FUI_TEXT_EXTR_WATCH_IT, + FUI_TEXT_EXTR_ADVANCE_L_IT, + FUI_TEXT_EXTR_ADVANCE_K_IT, + FUI_TEXT_EXTR_MANAGER_IT, + FUI_TEXT_EXTR_PGAIN_IT, + FUI_TEXT_EXTR_DEADTIME_IT, + FUI_TEXT_EXTR_DMAX_DT_IT, + FUI_TEXT_EXTR_IGAIN_IT, + FUI_TEXT_EXTR_DGAIN_IT, + FUI_TEXT_EXTR_DMIN_IT, + FUI_TEXT_EXTR_DMAX_IT, + FUI_TEXT_EXTR_PMAX_IT, + FUI_TEXT_EXTR_XOFF_IT, + FUI_TEXT_EXTR_YOFF_IT, + FUI_TEXT_STRING_HM_BANGBANG_IT, + FUI_TEXT_STRING_HM_PID_IT, + FUI_TEXT_STRING_ACTION_IT, + FUI_TEXT_HEATING_EXTRUDER_IT, + FUI_TEXT_HEATING_BED_IT, + FUI_TEXT_KILLED_IT, + FUI_TEXT_STEPPER_DISABLED_IT, + FUI_TEXT_EEPROM_STOREDA_IT, + FUI_TEXT_EEPROM_STOREDB_IT, + FUI_TEXT_EEPROM_LOADEDA_IT, + FUI_TEXT_EEPROM_LOADEDB_IT, + FUI_TEXT_UPLOADING_IT, + FUI_TEXT_PAGE_BUFFER_IT, + FUI_TEXT_PAGE_EXTRUDER_IT, + FUI_TEXT_PAGE_EXTRUDER1_IT, + FUI_TEXT_PAGE_EXTRUDER2_IT, + FUI_TEXT_PAGE_EXTRUDER3_IT, + FUI_TEXT_PAGE_BED_IT, + FUI_TEXT_SPEED_MULTIPLY_IT, + FUI_TEXT_FLOW_MULTIPLY_IT, + FUI_TEXT_SHOW_MEASUREMENT_IT, + FUI_TEXT_RESET_MEASUREMENT_IT, + FUI_TEXT_SET_MEASURED_ORIGIN_IT, + FUI_TEXT_ZCALIB_IT, + FUI_TEXT_SET_P1_IT, + FUI_TEXT_SET_P2_IT, + FUI_TEXT_SET_P3_IT, + FUI_TEXT_CALCULATE_LEVELING_IT, + FUI_TEXT_LEVEL_IT, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_IT, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_IT, + FUI_TEXT_SD_REMOVED_IT, + FUI_TEXT_SD_INSERTED_IT, + FUI_TEXT_PRINTER_READY_IT, + FUI_TEXT_PRINTTIME_DAYS_IT, + FUI_TEXT_PRINTTIME_HOURS_IT, + FUI_TEXT_PRINTTIME_MINUTES_IT, + FUI_TEXT_PRINT_TIME_IT, + FUI_TEXT_PRINT_FILAMENT_IT, + FUI_TEXT_PRINTED_IT, + FUI_TEXT_POWER_IT, + FUI_TEXT_STRING_HM_DEADTIME_IT, + FUI_TEXT_STRING_HM_SLOWBANG_IT, + FUI_TEXT_STOP_PRINT_IT, + FUI_TEXT_Z_BABYSTEPPING_IT, + FUI_TEXT_CHANGE_FILAMENT_IT, + FUI_TEXT_WIZ_CH_FILAMENT1_IT, + FUI_TEXT_WIZ_CH_FILAMENT2_IT, + FUI_TEXT_WIZ_CH_FILAMENT3_IT, + FUI_TEXT_CLICK_DONE_IT, + FUI_TEXT_AUTOLEVEL_ONOFF_IT, + FUI_TEXT_SERVOPOS_IT, + FUI_TEXT_IGNORE_M106_IT, + FUI_TEXT_WIZ_REHEAT1_IT, + FUI_TEXT_WIZ_REHEAT2_IT, + FUI_TEXT_WIZ_WAITTEMP1_IT, + FUI_TEXT_WIZ_WAITTEMP2_IT, + FUI_TEXT_EXTRUDER_JAM_IT, + FUI_TEXT_STANDBY_IT, + FUI_TEXT_BED_COATING_IT, + FUI_TEXT_BED_COATING_SET1_IT, + FUI_TEXT_BED_COATING_SET2_IT, + FUI_TEXT_NOCOATING_IT, + FUI_TEXT_BUILDTAK_IT, + FUI_TEXT_KAPTON_IT, + FUI_TEXT_BLUETAPE_IT, + FUI_TEXT_PETTAPE_IT, + FUI_TEXT_GLUESTICK_IT, + FUI_TEXT_CUSTOM_IT, + FUI_TEXT_COATING_CUSTOM_IT, + FUI_TEXT_LANGUAGE_IT, + FUI_TEXT_MAINPAGE6_1_IT, + FUI_TEXT_MAINPAGE6_2_IT, + FUI_TEXT_MAINPAGE6_3_IT, + FUI_TEXT_MAINPAGE6_4_IT, + FUI_TEXT_MAINPAGE6_5_IT, + FUI_TEXT_MAINPAGE6_6_IT, + FUI_TEXT_MAINPAGE_TEMP_BED_IT, + FUI_TEXT_MAINPAGE_BED_IT, + FUI_TEXT_MAINPAGE_Z_BUF_IT, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_IT, + FUI_TEXT_MAINPAGE_XY_IT, + FUI_TEXT_PRINT_TIME_VALUE_IT, + FUI_TEXT_PRINT_FILAMENT_VALUE_IT, + FUI_TEXT_METER_PRINTED_IT, + FUI_TEXT_STATUS_IT, + FUI_TEXT_EMPTY_IT, + FUI_TEXT_TEMP_SET_IT, + FUI_TEXT_CURRENT_TEMP_IT, + FUI_TEXT_COATING_THICKNESS_IT, + FUI_TEXT_EXTR3_TEMP_IT, + FUI_TEXT_EXTR4_TEMP_IT, + FUI_TEXT_EXTR5_TEMP_IT, + FUI_TEXT_EXTR3_OFF_IT, + FUI_TEXT_EXTR4_OFF_IT, + FUI_TEXT_EXTR5_OFF_IT, + FUI_TEXT_EXTR3_SELECT_IT, + FUI_TEXT_EXTR4_SELECT_IT, + FUI_TEXT_EXTR5_SELECT_IT, + FUI_TEXT_DITTO_0_IT, + FUI_TEXT_DITTO_1_IT, + FUI_TEXT_DITTO_2_IT, + FUI_TEXT_DITTO_3_IT, + FUI_TEXT_ZPROBE_HEIGHT_IT, + FUI_TEXT_OFFSETS_IT, + FUI_TEXT_X_OFFSET_IT, + FUI_TEXT_Y_OFFSET_IT, + FUI_TEXT_Z_OFFSET_IT +}; +#define LANG_IT_TABLE translations_it +#else +#define LANG_IT_TABLE NULL +#endif // LANGUAGE_IT_ACTIVE + + +#if LANGUAGE_ES_ACTIVE +TRANS(UI_TEXT_ON_ES); +TRANS(UI_TEXT_OFF_ES); +TRANS(UI_TEXT_NA_ES); +TRANS(UI_TEXT_YES_ES); +TRANS(UI_TEXT_NO_ES); +TRANS(UI_TEXT_PRINT_POS_ES); +TRANS(UI_TEXT_PRINTING_ES); +TRANS(UI_TEXT_IDLE_ES); +TRANS(UI_TEXT_NOSDCARD_ES); +TRANS(UI_TEXT_ERROR_ES); +TRANS(UI_TEXT_BACK_ES); +TRANS(UI_TEXT_QUICK_SETTINGS_ES); +TRANS(UI_TEXT_ERRORMSG_ES); +TRANS(UI_TEXT_CONFIGURATION_ES); +TRANS(UI_TEXT_POSITION_ES); +TRANS(UI_TEXT_EXTRUDER_ES); +TRANS(UI_TEXT_SD_CARD_ES); +TRANS(UI_TEXT_DEBUGGING_ES); +TRANS(UI_TEXT_HOME_DELTA_ES); +TRANS(UI_TEXT_HOME_ALL_ES); +TRANS(UI_TEXT_HOME_X_ES); +TRANS(UI_TEXT_HOME_Y_ES); +TRANS(UI_TEXT_HOME_Z_ES); +TRANS(UI_TEXT_PREHEAT_PLA_ES); +TRANS(UI_TEXT_PREHEAT_ABS_ES); +TRANS(UI_TEXT_LIGHTS_ONOFF_ES); +TRANS(UI_TEXT_COOLDOWN_ES); +TRANS(UI_TEXT_SET_TO_ORIGIN_ES); +TRANS(UI_TEXT_DISABLE_STEPPER_ES); +TRANS(UI_TEXT_X_POSITION_ES); +TRANS(UI_TEXT_X_POS_FAST_ES); +TRANS(UI_TEXT_Y_POSITION_ES); +TRANS(UI_TEXT_Y_POS_FAST_ES); +TRANS(UI_TEXT_Z_POSITION_ES); +TRANS(UI_TEXT_Z_POS_FAST_ES); +TRANS(UI_TEXT_E_POSITION_ES); +TRANS(UI_TEXT_BED_TEMP_ES); +TRANS(UI_TEXT_EXTR0_TEMP_ES); +TRANS(UI_TEXT_EXTR1_TEMP_ES); +TRANS(UI_TEXT_EXTR2_TEMP_ES); +TRANS(UI_TEXT_EXTR0_OFF_ES); +TRANS(UI_TEXT_EXTR1_OFF_ES); +TRANS(UI_TEXT_EXTR2_OFF_ES); +TRANS(UI_TEXT_EXTR0_SELECT_ES); +TRANS(UI_TEXT_EXTR1_SELECT_ES); +TRANS(UI_TEXT_EXTR2_SELECT_ES); +TRANS(UI_TEXT_EXTR_ORIGIN_ES); +TRANS(UI_TEXT_PRINT_X_ES); +TRANS(UI_TEXT_PRINT_Y_ES); +TRANS(UI_TEXT_PRINT_Z_ES); +TRANS(UI_TEXT_PRINT_Z_DELTA_ES); +TRANS(UI_TEXT_MOVE_X_ES); +TRANS(UI_TEXT_MOVE_Y_ES); +TRANS(UI_TEXT_MOVE_Z_ES); +TRANS(UI_TEXT_MOVE_Z_DELTA_ES); +TRANS(UI_TEXT_JERK_ES); +TRANS(UI_TEXT_ZJERK_ES); +TRANS(UI_TEXT_ACCELERATION_ES); +TRANS(UI_TEXT_STORE_TO_EEPROM_ES); +TRANS(UI_TEXT_LOAD_EEPROM_ES); +TRANS(UI_TEXT_DBG_ECHO_ES); +TRANS(UI_TEXT_DBG_INFO_ES); +TRANS(UI_TEXT_DBG_ERROR_ES); +TRANS(UI_TEXT_DBG_DRYRUN_ES); +TRANS(UI_TEXT_OPS_OFF_ES); +TRANS(UI_TEXT_OPS_CLASSIC_ES); +TRANS(UI_TEXT_OPS_FAST_ES); +TRANS(UI_TEXT_OPS_RETRACT_ES); +TRANS(UI_TEXT_OPS_BACKSLASH_ES); +TRANS(UI_TEXT_OPS_MINDIST_ES); +TRANS(UI_TEXT_OPS_MOVE_AFTER_ES); +TRANS(UI_TEXT_ANTI_OOZE_ES); +TRANS(UI_TEXT_PRINT_FILE_ES); +TRANS(UI_TEXT_PAUSE_PRINT_ES); +TRANS(UI_TEXT_CONTINUE_PRINT_ES); +TRANS(UI_TEXT_UNMOUNT_CARD_ES); +TRANS(UI_TEXT_MOUNT_CARD_ES); +TRANS(UI_TEXT_DELETE_FILE_ES); +TRANS(UI_TEXT_FEEDRATE_ES); +TRANS(UI_TEXT_FEED_MAX_X_ES); +TRANS(UI_TEXT_FEED_MAX_Y_ES); +TRANS(UI_TEXT_FEED_MAX_Z_ES); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_ES); +TRANS(UI_TEXT_FEED_HOME_X_ES); +TRANS(UI_TEXT_FEED_HOME_Y_ES); +TRANS(UI_TEXT_FEED_HOME_Z_ES); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_ES); +TRANS(UI_TEXT_ACTION_XPOSITION4A_ES); +TRANS(UI_TEXT_ACTION_XPOSITION4B_ES); +TRANS(UI_TEXT_ACTION_XPOSITION4C_ES); +TRANS(UI_TEXT_ACTION_XPOSITION4D_ES); +TRANS(UI_TEXT_ACTION_YPOSITION4A_ES); +TRANS(UI_TEXT_ACTION_YPOSITION4B_ES); +TRANS(UI_TEXT_ACTION_YPOSITION4C_ES); +TRANS(UI_TEXT_ACTION_YPOSITION4D_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_ES); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_ES); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_ES); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_ES); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_ES); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_ES); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_ES); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_ES); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_ES); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_ES); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_ES); +TRANS(UI_TEXT_ACTION_XPOSITION2A_ES); +TRANS(UI_TEXT_ACTION_XPOSITION2B_ES); +TRANS(UI_TEXT_ACTION_YPOSITION2A_ES); +TRANS(UI_TEXT_ACTION_YPOSITION2B_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_ES); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_ES); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_ES); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_ES); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_ES); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_ES); +TRANS(UI_TEXT_FANSPEED_ES); +TRANS(UI_TEXT_ACTION_FANSPEED_ES); +TRANS(UI_TEXT_FAN_OFF_ES); +TRANS(UI_TEXT_FAN_25_ES); +TRANS(UI_TEXT_FAN_50_ES); +TRANS(UI_TEXT_FAN_75_ES); +TRANS(UI_TEXT_FAN_FULL_ES); +TRANS(UI_TEXT_STEPPER_INACTIVE_ES); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_ES); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_ES); +TRANS(UI_TEXT_POWER_INACTIVE_ES); +TRANS(UI_TEXT_POWER_INACTIVE2A_ES); +TRANS(UI_TEXT_POWER_INACTIVE2B_ES); +TRANS(UI_TEXT_GENERAL_ES); +TRANS(UI_TEXT_BAUDRATE_ES); +TRANS(UI_TEXT_EXTR_STEPS_ES); +TRANS(UI_TEXT_EXTR_START_FEED_ES); +TRANS(UI_TEXT_EXTR_MAX_FEED_ES); +TRANS(UI_TEXT_EXTR_ACCEL_ES); +TRANS(UI_TEXT_EXTR_WATCH_ES); +TRANS(UI_TEXT_EXTR_ADVANCE_L_ES); +TRANS(UI_TEXT_EXTR_ADVANCE_K_ES); +TRANS(UI_TEXT_EXTR_MANAGER_ES); +TRANS(UI_TEXT_EXTR_PGAIN_ES); +TRANS(UI_TEXT_EXTR_DEADTIME_ES); +TRANS(UI_TEXT_EXTR_DMAX_DT_ES); +TRANS(UI_TEXT_EXTR_IGAIN_ES); +TRANS(UI_TEXT_EXTR_DGAIN_ES); +TRANS(UI_TEXT_EXTR_DMIN_ES); +TRANS(UI_TEXT_EXTR_DMAX_ES); +TRANS(UI_TEXT_EXTR_PMAX_ES); +TRANS(UI_TEXT_EXTR_XOFF_ES); +TRANS(UI_TEXT_EXTR_YOFF_ES); +TRANS(UI_TEXT_STRING_HM_BANGBANG_ES); +TRANS(UI_TEXT_STRING_HM_PID_ES); +TRANS(UI_TEXT_STRING_ACTION_ES); +TRANS(UI_TEXT_HEATING_EXTRUDER_ES); +TRANS(UI_TEXT_HEATING_BED_ES); +TRANS(UI_TEXT_KILLED_ES); +TRANS(UI_TEXT_STEPPER_DISABLED_ES); +TRANS(UI_TEXT_EEPROM_STOREDA_ES); +TRANS(UI_TEXT_EEPROM_STOREDB_ES); +TRANS(UI_TEXT_EEPROM_LOADEDA_ES); +TRANS(UI_TEXT_EEPROM_LOADEDB_ES); +TRANS(UI_TEXT_UPLOADING_ES); +TRANS(UI_TEXT_PAGE_BUFFER_ES); +TRANS(UI_TEXT_PAGE_EXTRUDER_ES); +TRANS(UI_TEXT_PAGE_EXTRUDER1_ES); +TRANS(UI_TEXT_PAGE_EXTRUDER2_ES); +TRANS(UI_TEXT_PAGE_EXTRUDER3_ES); +TRANS(UI_TEXT_PAGE_BED_ES); +TRANS(UI_TEXT_SPEED_MULTIPLY_ES); +TRANS(UI_TEXT_FLOW_MULTIPLY_ES); +TRANS(UI_TEXT_SHOW_MEASUREMENT_ES); +TRANS(UI_TEXT_RESET_MEASUREMENT_ES); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_ES); +TRANS(UI_TEXT_ZCALIB_ES); +TRANS(UI_TEXT_SET_P1_ES); +TRANS(UI_TEXT_SET_P2_ES); +TRANS(UI_TEXT_SET_P3_ES); +TRANS(UI_TEXT_CALCULATE_LEVELING_ES); +TRANS(UI_TEXT_LEVEL_ES); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_ES); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_ES); +TRANS(UI_TEXT_SD_REMOVED_ES); +TRANS(UI_TEXT_SD_INSERTED_ES); +TRANS(UI_TEXT_PRINTER_READY_ES); +TRANS(UI_TEXT_PRINTTIME_DAYS_ES); +TRANS(UI_TEXT_PRINTTIME_HOURS_ES); +TRANS(UI_TEXT_PRINTTIME_MINUTES_ES); +TRANS(UI_TEXT_PRINT_TIME_ES); +TRANS(UI_TEXT_PRINT_FILAMENT_ES); +TRANS(UI_TEXT_PRINTED_ES); +TRANS(UI_TEXT_POWER_ES); +TRANS(UI_TEXT_STRING_HM_DEADTIME_ES); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_ES); +TRANS(UI_TEXT_STOP_PRINT_ES); +TRANS(UI_TEXT_Z_BABYSTEPPING_ES); +TRANS(UI_TEXT_CHANGE_FILAMENT_ES); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_ES); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_ES); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_ES); +TRANS(UI_TEXT_CLICK_DONE_ES); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_ES); +TRANS(UI_TEXT_SERVOPOS_ES); +TRANS(UI_TEXT_IGNORE_M106_ES); +TRANS(UI_TEXT_WIZ_REHEAT1_ES); +TRANS(UI_TEXT_WIZ_REHEAT2_ES); +TRANS(UI_TEXT_WIZ_WAITTEMP1_ES); +TRANS(UI_TEXT_WIZ_WAITTEMP2_ES); +TRANS(UI_TEXT_EXTRUDER_JAM_ES); +TRANS(UI_TEXT_STANDBY_ES); +TRANS(UI_TEXT_BED_COATING_ES); +TRANS(UI_TEXT_BED_COATING_SET1_ES); +TRANS(UI_TEXT_BED_COATING_SET2_ES); +TRANS(UI_TEXT_NOCOATING_ES); +TRANS(UI_TEXT_BUILDTAK_ES); +TRANS(UI_TEXT_KAPTON_ES); +TRANS(UI_TEXT_BLUETAPE_ES); +TRANS(UI_TEXT_PETTAPE_ES); +TRANS(UI_TEXT_GLUESTICK_ES); +TRANS(UI_TEXT_CUSTOM_ES); +TRANS(UI_TEXT_COATING_CUSTOM_ES); +TRANS(UI_TEXT_LANGUAGE_ES); +TRANS(UI_TEXT_MAINPAGE6_1_ES); +TRANS(UI_TEXT_MAINPAGE6_2_ES); +TRANS(UI_TEXT_MAINPAGE6_3_ES); +TRANS(UI_TEXT_MAINPAGE6_4_ES); +TRANS(UI_TEXT_MAINPAGE6_5_ES); +TRANS(UI_TEXT_MAINPAGE6_6_ES); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_ES); +TRANS(UI_TEXT_MAINPAGE_BED_ES); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_ES); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_ES); +TRANS(UI_TEXT_MAINPAGE_XY_ES); +TRANS(UI_TEXT_PRINT_TIME_VALUE_ES); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_ES); +TRANS(UI_TEXT_METER_PRINTED_ES); +TRANS(UI_TEXT_STATUS_ES); +TRANS(UI_TEXT_EMPTY_ES); +TRANS(UI_TEXT_TEMP_SET_ES); +TRANS(UI_TEXT_CURRENT_TEMP_ES); +TRANS(UI_TEXT_COATING_THICKNESS_ES); +TRANS(UI_TEXT_EXTR3_TEMP_ES); +TRANS(UI_TEXT_EXTR4_TEMP_ES); +TRANS(UI_TEXT_EXTR5_TEMP_ES); +TRANS(UI_TEXT_EXTR3_OFF_ES); +TRANS(UI_TEXT_EXTR4_OFF_ES); +TRANS(UI_TEXT_EXTR5_OFF_ES); +TRANS(UI_TEXT_EXTR3_SELECT_ES); +TRANS(UI_TEXT_EXTR4_SELECT_ES); +TRANS(UI_TEXT_EXTR5_SELECT_ES); +TRANS(UI_TEXT_DITTO_0_ES); +TRANS(UI_TEXT_DITTO_1_ES); +TRANS(UI_TEXT_DITTO_2_ES); +TRANS(UI_TEXT_DITTO_3_ES); +TRANS(UI_TEXT_ZPROBE_HEIGHT_ES); +TRANS(UI_TEXT_OFFSETS_ES); +TRANS(UI_TEXT_X_OFFSET_ES); +TRANS(UI_TEXT_Y_OFFSET_ES); +TRANS(UI_TEXT_Z_OFFSET_ES); + +PGM_P const translations_es[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_ES, + FUI_TEXT_OFF_ES, + FUI_TEXT_NA_ES, + FUI_TEXT_YES_ES, + FUI_TEXT_NO_ES, + FUI_TEXT_PRINT_POS_ES, + FUI_TEXT_PRINTING_ES, + FUI_TEXT_IDLE_ES, + FUI_TEXT_NOSDCARD_ES, + FUI_TEXT_ERROR_ES, + FUI_TEXT_BACK_ES, + FUI_TEXT_QUICK_SETTINGS_ES, + FUI_TEXT_ERRORMSG_ES, + FUI_TEXT_CONFIGURATION_ES, + FUI_TEXT_POSITION_ES, + FUI_TEXT_EXTRUDER_ES, + FUI_TEXT_SD_CARD_ES, + FUI_TEXT_DEBUGGING_ES, + FUI_TEXT_HOME_DELTA_ES, + FUI_TEXT_HOME_ALL_ES, + FUI_TEXT_HOME_X_ES, + FUI_TEXT_HOME_Y_ES, + FUI_TEXT_HOME_Z_ES, + FUI_TEXT_PREHEAT_PLA_ES, + FUI_TEXT_PREHEAT_ABS_ES, + FUI_TEXT_LIGHTS_ONOFF_ES, + FUI_TEXT_COOLDOWN_ES, + FUI_TEXT_SET_TO_ORIGIN_ES, + FUI_TEXT_DISABLE_STEPPER_ES, + FUI_TEXT_X_POSITION_ES, + FUI_TEXT_X_POS_FAST_ES, + FUI_TEXT_Y_POSITION_ES, + FUI_TEXT_Y_POS_FAST_ES, + FUI_TEXT_Z_POSITION_ES, + FUI_TEXT_Z_POS_FAST_ES, + FUI_TEXT_E_POSITION_ES, + FUI_TEXT_BED_TEMP_ES, + FUI_TEXT_EXTR0_TEMP_ES, + FUI_TEXT_EXTR1_TEMP_ES, + FUI_TEXT_EXTR2_TEMP_ES, + FUI_TEXT_EXTR0_OFF_ES, + FUI_TEXT_EXTR1_OFF_ES, + FUI_TEXT_EXTR2_OFF_ES, + FUI_TEXT_EXTR0_SELECT_ES, + FUI_TEXT_EXTR1_SELECT_ES, + FUI_TEXT_EXTR2_SELECT_ES, + FUI_TEXT_EXTR_ORIGIN_ES, + FUI_TEXT_PRINT_X_ES, + FUI_TEXT_PRINT_Y_ES, + FUI_TEXT_PRINT_Z_ES, + FUI_TEXT_PRINT_Z_DELTA_ES, + FUI_TEXT_MOVE_X_ES, + FUI_TEXT_MOVE_Y_ES, + FUI_TEXT_MOVE_Z_ES, + FUI_TEXT_MOVE_Z_DELTA_ES, + FUI_TEXT_JERK_ES, + FUI_TEXT_ZJERK_ES, + FUI_TEXT_ACCELERATION_ES, + FUI_TEXT_STORE_TO_EEPROM_ES, + FUI_TEXT_LOAD_EEPROM_ES, + FUI_TEXT_DBG_ECHO_ES, + FUI_TEXT_DBG_INFO_ES, + FUI_TEXT_DBG_ERROR_ES, + FUI_TEXT_DBG_DRYRUN_ES, + FUI_TEXT_OPS_OFF_ES, + FUI_TEXT_OPS_CLASSIC_ES, + FUI_TEXT_OPS_FAST_ES, + FUI_TEXT_OPS_RETRACT_ES, + FUI_TEXT_OPS_BACKSLASH_ES, + FUI_TEXT_OPS_MINDIST_ES, + FUI_TEXT_OPS_MOVE_AFTER_ES, + FUI_TEXT_ANTI_OOZE_ES, + FUI_TEXT_PRINT_FILE_ES, + FUI_TEXT_PAUSE_PRINT_ES, + FUI_TEXT_CONTINUE_PRINT_ES, + FUI_TEXT_UNMOUNT_CARD_ES, + FUI_TEXT_MOUNT_CARD_ES, + FUI_TEXT_DELETE_FILE_ES, + FUI_TEXT_FEEDRATE_ES, + FUI_TEXT_FEED_MAX_X_ES, + FUI_TEXT_FEED_MAX_Y_ES, + FUI_TEXT_FEED_MAX_Z_ES, + FUI_TEXT_FEED_MAX_Z_DELTA_ES, + FUI_TEXT_FEED_HOME_X_ES, + FUI_TEXT_FEED_HOME_Y_ES, + FUI_TEXT_FEED_HOME_Z_ES, + FUI_TEXT_FEED_HOME_Z_DELTA_ES, + FUI_TEXT_ACTION_XPOSITION4A_ES, + FUI_TEXT_ACTION_XPOSITION4B_ES, + FUI_TEXT_ACTION_XPOSITION4C_ES, + FUI_TEXT_ACTION_XPOSITION4D_ES, + FUI_TEXT_ACTION_YPOSITION4A_ES, + FUI_TEXT_ACTION_YPOSITION4B_ES, + FUI_TEXT_ACTION_YPOSITION4C_ES, + FUI_TEXT_ACTION_YPOSITION4D_ES, + FUI_TEXT_ACTION_ZPOSITION4A_ES, + FUI_TEXT_ACTION_ZPOSITION4B_ES, + FUI_TEXT_ACTION_ZPOSITION4C_ES, + FUI_TEXT_ACTION_ZPOSITION4D_ES, + FUI_TEXT_ACTION_XPOSITION_FAST4A_ES, + FUI_TEXT_ACTION_XPOSITION_FAST4B_ES, + FUI_TEXT_ACTION_XPOSITION_FAST4C_ES, + FUI_TEXT_ACTION_XPOSITION_FAST4D_ES, + FUI_TEXT_ACTION_YPOSITION_FAST4A_ES, + FUI_TEXT_ACTION_YPOSITION_FAST4B_ES, + FUI_TEXT_ACTION_YPOSITION_FAST4C_ES, + FUI_TEXT_ACTION_YPOSITION_FAST4D_ES, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_ES, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_ES, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_ES, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_ES, + FUI_TEXT_ACTION_EPOSITION_FAST2A_ES, + FUI_TEXT_ACTION_EPOSITION_FAST2B_ES, + FUI_TEXT_ACTION_XPOSITION2A_ES, + FUI_TEXT_ACTION_XPOSITION2B_ES, + FUI_TEXT_ACTION_YPOSITION2A_ES, + FUI_TEXT_ACTION_YPOSITION2B_ES, + FUI_TEXT_ACTION_ZPOSITION2A_ES, + FUI_TEXT_ACTION_ZPOSITION2B_ES, + FUI_TEXT_ACTION_XPOSITION_FAST2A_ES, + FUI_TEXT_ACTION_XPOSITION_FAST2B_ES, + FUI_TEXT_ACTION_YPOSITION_FAST2A_ES, + FUI_TEXT_ACTION_YPOSITION_FAST2B_ES, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_ES, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_ES, + FUI_TEXT_FANSPEED_ES, + FUI_TEXT_ACTION_FANSPEED_ES, + FUI_TEXT_FAN_OFF_ES, + FUI_TEXT_FAN_25_ES, + FUI_TEXT_FAN_50_ES, + FUI_TEXT_FAN_75_ES, + FUI_TEXT_FAN_FULL_ES, + FUI_TEXT_STEPPER_INACTIVE_ES, + FUI_TEXT_STEPPER_INACTIVE2A_ES, + FUI_TEXT_STEPPER_INACTIVE2B_ES, + FUI_TEXT_POWER_INACTIVE_ES, + FUI_TEXT_POWER_INACTIVE2A_ES, + FUI_TEXT_POWER_INACTIVE2B_ES, + FUI_TEXT_GENERAL_ES, + FUI_TEXT_BAUDRATE_ES, + FUI_TEXT_EXTR_STEPS_ES, + FUI_TEXT_EXTR_START_FEED_ES, + FUI_TEXT_EXTR_MAX_FEED_ES, + FUI_TEXT_EXTR_ACCEL_ES, + FUI_TEXT_EXTR_WATCH_ES, + FUI_TEXT_EXTR_ADVANCE_L_ES, + FUI_TEXT_EXTR_ADVANCE_K_ES, + FUI_TEXT_EXTR_MANAGER_ES, + FUI_TEXT_EXTR_PGAIN_ES, + FUI_TEXT_EXTR_DEADTIME_ES, + FUI_TEXT_EXTR_DMAX_DT_ES, + FUI_TEXT_EXTR_IGAIN_ES, + FUI_TEXT_EXTR_DGAIN_ES, + FUI_TEXT_EXTR_DMIN_ES, + FUI_TEXT_EXTR_DMAX_ES, + FUI_TEXT_EXTR_PMAX_ES, + FUI_TEXT_EXTR_XOFF_ES, + FUI_TEXT_EXTR_YOFF_ES, + FUI_TEXT_STRING_HM_BANGBANG_ES, + FUI_TEXT_STRING_HM_PID_ES, + FUI_TEXT_STRING_ACTION_ES, + FUI_TEXT_HEATING_EXTRUDER_ES, + FUI_TEXT_HEATING_BED_ES, + FUI_TEXT_KILLED_ES, + FUI_TEXT_STEPPER_DISABLED_ES, + FUI_TEXT_EEPROM_STOREDA_ES, + FUI_TEXT_EEPROM_STOREDB_ES, + FUI_TEXT_EEPROM_LOADEDA_ES, + FUI_TEXT_EEPROM_LOADEDB_ES, + FUI_TEXT_UPLOADING_ES, + FUI_TEXT_PAGE_BUFFER_ES, + FUI_TEXT_PAGE_EXTRUDER_ES, + FUI_TEXT_PAGE_EXTRUDER1_ES, + FUI_TEXT_PAGE_EXTRUDER2_ES, + FUI_TEXT_PAGE_EXTRUDER3_ES, + FUI_TEXT_PAGE_BED_ES, + FUI_TEXT_SPEED_MULTIPLY_ES, + FUI_TEXT_FLOW_MULTIPLY_ES, + FUI_TEXT_SHOW_MEASUREMENT_ES, + FUI_TEXT_RESET_MEASUREMENT_ES, + FUI_TEXT_SET_MEASURED_ORIGIN_ES, + FUI_TEXT_ZCALIB_ES, + FUI_TEXT_SET_P1_ES, + FUI_TEXT_SET_P2_ES, + FUI_TEXT_SET_P3_ES, + FUI_TEXT_CALCULATE_LEVELING_ES, + FUI_TEXT_LEVEL_ES, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_ES, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_ES, + FUI_TEXT_SD_REMOVED_ES, + FUI_TEXT_SD_INSERTED_ES, + FUI_TEXT_PRINTER_READY_ES, + FUI_TEXT_PRINTTIME_DAYS_ES, + FUI_TEXT_PRINTTIME_HOURS_ES, + FUI_TEXT_PRINTTIME_MINUTES_ES, + FUI_TEXT_PRINT_TIME_ES, + FUI_TEXT_PRINT_FILAMENT_ES, + FUI_TEXT_PRINTED_ES, + FUI_TEXT_POWER_ES, + FUI_TEXT_STRING_HM_DEADTIME_ES, + FUI_TEXT_STRING_HM_SLOWBANG_ES, + FUI_TEXT_STOP_PRINT_ES, + FUI_TEXT_Z_BABYSTEPPING_ES, + FUI_TEXT_CHANGE_FILAMENT_ES, + FUI_TEXT_WIZ_CH_FILAMENT1_ES, + FUI_TEXT_WIZ_CH_FILAMENT2_ES, + FUI_TEXT_WIZ_CH_FILAMENT3_ES, + FUI_TEXT_CLICK_DONE_ES, + FUI_TEXT_AUTOLEVEL_ONOFF_ES, + FUI_TEXT_SERVOPOS_ES, + FUI_TEXT_IGNORE_M106_ES, + FUI_TEXT_WIZ_REHEAT1_ES, + FUI_TEXT_WIZ_REHEAT2_ES, + FUI_TEXT_WIZ_WAITTEMP1_ES, + FUI_TEXT_WIZ_WAITTEMP2_ES, + FUI_TEXT_EXTRUDER_JAM_ES, + FUI_TEXT_STANDBY_ES, + FUI_TEXT_BED_COATING_ES, + FUI_TEXT_BED_COATING_SET1_ES, + FUI_TEXT_BED_COATING_SET2_ES, + FUI_TEXT_NOCOATING_ES, + FUI_TEXT_BUILDTAK_ES, + FUI_TEXT_KAPTON_ES, + FUI_TEXT_BLUETAPE_ES, + FUI_TEXT_PETTAPE_ES, + FUI_TEXT_GLUESTICK_ES, + FUI_TEXT_CUSTOM_ES, + FUI_TEXT_COATING_CUSTOM_ES, + FUI_TEXT_LANGUAGE_ES, + FUI_TEXT_MAINPAGE6_1_ES, + FUI_TEXT_MAINPAGE6_2_ES, + FUI_TEXT_MAINPAGE6_3_ES, + FUI_TEXT_MAINPAGE6_4_ES, + FUI_TEXT_MAINPAGE6_5_ES, + FUI_TEXT_MAINPAGE6_6_ES, + FUI_TEXT_MAINPAGE_TEMP_BED_ES, + FUI_TEXT_MAINPAGE_BED_ES, + FUI_TEXT_MAINPAGE_Z_BUF_ES, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_ES, + FUI_TEXT_MAINPAGE_XY_ES, + FUI_TEXT_PRINT_TIME_VALUE_ES, + FUI_TEXT_PRINT_FILAMENT_VALUE_ES, + FUI_TEXT_METER_PRINTED_ES, + FUI_TEXT_STATUS_ES, + FUI_TEXT_EMPTY_ES, + FUI_TEXT_TEMP_SET_ES, + FUI_TEXT_CURRENT_TEMP_ES, + FUI_TEXT_COATING_THICKNESS_ES, + FUI_TEXT_EXTR3_TEMP_ES, + FUI_TEXT_EXTR4_TEMP_ES, + FUI_TEXT_EXTR5_TEMP_ES, + FUI_TEXT_EXTR3_OFF_ES, + FUI_TEXT_EXTR4_OFF_ES, + FUI_TEXT_EXTR5_OFF_ES, + FUI_TEXT_EXTR3_SELECT_ES, + FUI_TEXT_EXTR4_SELECT_ES, + FUI_TEXT_EXTR5_SELECT_ES, + FUI_TEXT_DITTO_0_ES, + FUI_TEXT_DITTO_1_ES, + FUI_TEXT_DITTO_2_ES, + FUI_TEXT_DITTO_3_ES, + FUI_TEXT_ZPROBE_HEIGHT_ES, + FUI_TEXT_OFFSETS_ES, + FUI_TEXT_X_OFFSET_ES, + FUI_TEXT_Y_OFFSET_ES, + FUI_TEXT_Z_OFFSET_ES +}; +#define LANG_ES_TABLE translations_es +#else +#define LANG_ES_TABLE NULL +#endif // LANGUAGE_ES_ACTIVE + + +#if LANGUAGE_SE_ACTIVE +TRANS(UI_TEXT_ON_SE); +TRANS(UI_TEXT_OFF_SE); +TRANS(UI_TEXT_NA_SE); +TRANS(UI_TEXT_YES_SE); +TRANS(UI_TEXT_NO_SE); +TRANS(UI_TEXT_PRINT_POS_SE); +TRANS(UI_TEXT_PRINTING_SE); +TRANS(UI_TEXT_IDLE_SE); +TRANS(UI_TEXT_NOSDCARD_SE); +TRANS(UI_TEXT_ERROR_SE); +TRANS(UI_TEXT_BACK_SE); +TRANS(UI_TEXT_QUICK_SETTINGS_SE); +TRANS(UI_TEXT_ERRORMSG_SE); +TRANS(UI_TEXT_CONFIGURATION_SE); +TRANS(UI_TEXT_POSITION_SE); +TRANS(UI_TEXT_EXTRUDER_SE); +TRANS(UI_TEXT_SD_CARD_SE); +TRANS(UI_TEXT_DEBUGGING_SE); +TRANS(UI_TEXT_HOME_DELTA_SE); +TRANS(UI_TEXT_HOME_ALL_SE); +TRANS(UI_TEXT_HOME_X_SE); +TRANS(UI_TEXT_HOME_Y_SE); +TRANS(UI_TEXT_HOME_Z_SE); +TRANS(UI_TEXT_PREHEAT_PLA_SE); +TRANS(UI_TEXT_PREHEAT_ABS_SE); +TRANS(UI_TEXT_LIGHTS_ONOFF_SE); +TRANS(UI_TEXT_COOLDOWN_SE); +TRANS(UI_TEXT_SET_TO_ORIGIN_SE); +TRANS(UI_TEXT_DISABLE_STEPPER_SE); +TRANS(UI_TEXT_X_POSITION_SE); +TRANS(UI_TEXT_X_POS_FAST_SE); +TRANS(UI_TEXT_Y_POSITION_SE); +TRANS(UI_TEXT_Y_POS_FAST_SE); +TRANS(UI_TEXT_Z_POSITION_SE); +TRANS(UI_TEXT_Z_POS_FAST_SE); +TRANS(UI_TEXT_E_POSITION_SE); +TRANS(UI_TEXT_BED_TEMP_SE); +TRANS(UI_TEXT_EXTR0_TEMP_SE); +TRANS(UI_TEXT_EXTR1_TEMP_SE); +TRANS(UI_TEXT_EXTR2_TEMP_SE); +TRANS(UI_TEXT_EXTR0_OFF_SE); +TRANS(UI_TEXT_EXTR1_OFF_SE); +TRANS(UI_TEXT_EXTR2_OFF_SE); +TRANS(UI_TEXT_EXTR0_SELECT_SE); +TRANS(UI_TEXT_EXTR1_SELECT_SE); +TRANS(UI_TEXT_EXTR2_SELECT_SE); +TRANS(UI_TEXT_EXTR_ORIGIN_SE); +TRANS(UI_TEXT_PRINT_X_SE); +TRANS(UI_TEXT_PRINT_Y_SE); +TRANS(UI_TEXT_PRINT_Z_SE); +TRANS(UI_TEXT_PRINT_Z_DELTA_SE); +TRANS(UI_TEXT_MOVE_X_SE); +TRANS(UI_TEXT_MOVE_Y_SE); +TRANS(UI_TEXT_MOVE_Z_SE); +TRANS(UI_TEXT_MOVE_Z_DELTA_SE); +TRANS(UI_TEXT_JERK_SE); +TRANS(UI_TEXT_ZJERK_SE); +TRANS(UI_TEXT_ACCELERATION_SE); +TRANS(UI_TEXT_STORE_TO_EEPROM_SE); +TRANS(UI_TEXT_LOAD_EEPROM_SE); +TRANS(UI_TEXT_DBG_ECHO_SE); +TRANS(UI_TEXT_DBG_INFO_SE); +TRANS(UI_TEXT_DBG_ERROR_SE); +TRANS(UI_TEXT_DBG_DRYRUN_SE); +TRANS(UI_TEXT_OPS_OFF_SE); +TRANS(UI_TEXT_OPS_CLASSIC_SE); +TRANS(UI_TEXT_OPS_FAST_SE); +TRANS(UI_TEXT_OPS_RETRACT_SE); +TRANS(UI_TEXT_OPS_BACKSLASH_SE); +TRANS(UI_TEXT_OPS_MINDIST_SE); +TRANS(UI_TEXT_OPS_MOVE_AFTER_SE); +TRANS(UI_TEXT_ANTI_OOZE_SE); +TRANS(UI_TEXT_PRINT_FILE_SE); +TRANS(UI_TEXT_PAUSE_PRINT_SE); +TRANS(UI_TEXT_CONTINUE_PRINT_SE); +TRANS(UI_TEXT_UNMOUNT_CARD_SE); +TRANS(UI_TEXT_MOUNT_CARD_SE); +TRANS(UI_TEXT_DELETE_FILE_SE); +TRANS(UI_TEXT_FEEDRATE_SE); +TRANS(UI_TEXT_FEED_MAX_X_SE); +TRANS(UI_TEXT_FEED_MAX_Y_SE); +TRANS(UI_TEXT_FEED_MAX_Z_SE); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_SE); +TRANS(UI_TEXT_FEED_HOME_X_SE); +TRANS(UI_TEXT_FEED_HOME_Y_SE); +TRANS(UI_TEXT_FEED_HOME_Z_SE); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_SE); +TRANS(UI_TEXT_ACTION_XPOSITION4A_SE); +TRANS(UI_TEXT_ACTION_XPOSITION4B_SE); +TRANS(UI_TEXT_ACTION_XPOSITION4C_SE); +TRANS(UI_TEXT_ACTION_XPOSITION4D_SE); +TRANS(UI_TEXT_ACTION_YPOSITION4A_SE); +TRANS(UI_TEXT_ACTION_YPOSITION4B_SE); +TRANS(UI_TEXT_ACTION_YPOSITION4C_SE); +TRANS(UI_TEXT_ACTION_YPOSITION4D_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_SE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_SE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_SE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_SE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_SE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_SE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_SE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_SE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_SE); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_SE); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_SE); +TRANS(UI_TEXT_ACTION_XPOSITION2A_SE); +TRANS(UI_TEXT_ACTION_XPOSITION2B_SE); +TRANS(UI_TEXT_ACTION_YPOSITION2A_SE); +TRANS(UI_TEXT_ACTION_YPOSITION2B_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_SE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_SE); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_SE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_SE); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_SE); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_SE); +TRANS(UI_TEXT_FANSPEED_SE); +TRANS(UI_TEXT_ACTION_FANSPEED_SE); +TRANS(UI_TEXT_FAN_OFF_SE); +TRANS(UI_TEXT_FAN_25_SE); +TRANS(UI_TEXT_FAN_50_SE); +TRANS(UI_TEXT_FAN_75_SE); +TRANS(UI_TEXT_FAN_FULL_SE); +TRANS(UI_TEXT_STEPPER_INACTIVE_SE); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_SE); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_SE); +TRANS(UI_TEXT_POWER_INACTIVE_SE); +TRANS(UI_TEXT_POWER_INACTIVE2A_SE); +TRANS(UI_TEXT_POWER_INACTIVE2B_SE); +TRANS(UI_TEXT_GENERAL_SE); +TRANS(UI_TEXT_BAUDRATE_SE); +TRANS(UI_TEXT_EXTR_STEPS_SE); +TRANS(UI_TEXT_EXTR_START_FEED_SE); +TRANS(UI_TEXT_EXTR_MAX_FEED_SE); +TRANS(UI_TEXT_EXTR_ACCEL_SE); +TRANS(UI_TEXT_EXTR_WATCH_SE); +TRANS(UI_TEXT_EXTR_ADVANCE_L_SE); +TRANS(UI_TEXT_EXTR_ADVANCE_K_SE); +TRANS(UI_TEXT_EXTR_MANAGER_SE); +TRANS(UI_TEXT_EXTR_PGAIN_SE); +TRANS(UI_TEXT_EXTR_DEADTIME_SE); +TRANS(UI_TEXT_EXTR_DMAX_DT_SE); +TRANS(UI_TEXT_EXTR_IGAIN_SE); +TRANS(UI_TEXT_EXTR_DGAIN_SE); +TRANS(UI_TEXT_EXTR_DMIN_SE); +TRANS(UI_TEXT_EXTR_DMAX_SE); +TRANS(UI_TEXT_EXTR_PMAX_SE); +TRANS(UI_TEXT_EXTR_XOFF_SE); +TRANS(UI_TEXT_EXTR_YOFF_SE); +TRANS(UI_TEXT_STRING_HM_BANGBANG_SE); +TRANS(UI_TEXT_STRING_HM_PID_SE); +TRANS(UI_TEXT_STRING_ACTION_SE); +TRANS(UI_TEXT_HEATING_EXTRUDER_SE); +TRANS(UI_TEXT_HEATING_BED_SE); +TRANS(UI_TEXT_KILLED_SE); +TRANS(UI_TEXT_STEPPER_DISABLED_SE); +TRANS(UI_TEXT_EEPROM_STOREDA_SE); +TRANS(UI_TEXT_EEPROM_STOREDB_SE); +TRANS(UI_TEXT_EEPROM_LOADEDA_SE); +TRANS(UI_TEXT_EEPROM_LOADEDB_SE); +TRANS(UI_TEXT_UPLOADING_SE); +TRANS(UI_TEXT_PAGE_BUFFER_SE); +TRANS(UI_TEXT_PAGE_EXTRUDER_SE); +TRANS(UI_TEXT_PAGE_EXTRUDER1_SE); +TRANS(UI_TEXT_PAGE_EXTRUDER2_SE); +TRANS(UI_TEXT_PAGE_EXTRUDER3_SE); +TRANS(UI_TEXT_PAGE_BED_SE); +TRANS(UI_TEXT_SPEED_MULTIPLY_SE); +TRANS(UI_TEXT_FLOW_MULTIPLY_SE); +TRANS(UI_TEXT_SHOW_MEASUREMENT_SE); +TRANS(UI_TEXT_RESET_MEASUREMENT_SE); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_SE); +TRANS(UI_TEXT_ZCALIB_SE); +TRANS(UI_TEXT_SET_P1_SE); +TRANS(UI_TEXT_SET_P2_SE); +TRANS(UI_TEXT_SET_P3_SE); +TRANS(UI_TEXT_CALCULATE_LEVELING_SE); +TRANS(UI_TEXT_LEVEL_SE); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_SE); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_SE); +TRANS(UI_TEXT_SD_REMOVED_SE); +TRANS(UI_TEXT_SD_INSERTED_SE); +TRANS(UI_TEXT_PRINTER_READY_SE); +TRANS(UI_TEXT_PRINTTIME_DAYS_SE); +TRANS(UI_TEXT_PRINTTIME_HOURS_SE); +TRANS(UI_TEXT_PRINTTIME_MINUTES_SE); +TRANS(UI_TEXT_PRINT_TIME_SE); +TRANS(UI_TEXT_PRINT_FILAMENT_SE); +TRANS(UI_TEXT_PRINTED_SE); +TRANS(UI_TEXT_POWER_SE); +TRANS(UI_TEXT_STRING_HM_DEADTIME_SE); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_SE); +TRANS(UI_TEXT_STOP_PRINT_SE); +TRANS(UI_TEXT_Z_BABYSTEPPING_SE); +TRANS(UI_TEXT_CHANGE_FILAMENT_SE); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_SE); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_SE); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_SE); +TRANS(UI_TEXT_CLICK_DONE_SE); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_SE); +TRANS(UI_TEXT_SERVOPOS_SE); +TRANS(UI_TEXT_IGNORE_M106_SE); +TRANS(UI_TEXT_WIZ_REHEAT1_SE); +TRANS(UI_TEXT_WIZ_REHEAT2_SE); +TRANS(UI_TEXT_WIZ_WAITTEMP1_SE); +TRANS(UI_TEXT_WIZ_WAITTEMP2_SE); +TRANS(UI_TEXT_EXTRUDER_JAM_SE); +TRANS(UI_TEXT_STANDBY_SE); +TRANS(UI_TEXT_BED_COATING_SE); +TRANS(UI_TEXT_BED_COATING_SET1_SE); +TRANS(UI_TEXT_BED_COATING_SET2_SE); +TRANS(UI_TEXT_NOCOATING_SE); +TRANS(UI_TEXT_BUILDTAK_SE); +TRANS(UI_TEXT_KAPTON_SE); +TRANS(UI_TEXT_BLUETAPE_SE); +TRANS(UI_TEXT_PETTAPE_SE); +TRANS(UI_TEXT_GLUESTICK_SE); +TRANS(UI_TEXT_CUSTOM_SE); +TRANS(UI_TEXT_COATING_CUSTOM_SE); +TRANS(UI_TEXT_LANGUAGE_SE); +TRANS(UI_TEXT_MAINPAGE6_1_SE); +TRANS(UI_TEXT_MAINPAGE6_2_SE); +TRANS(UI_TEXT_MAINPAGE6_3_SE); +TRANS(UI_TEXT_MAINPAGE6_4_SE); +TRANS(UI_TEXT_MAINPAGE6_5_SE); +TRANS(UI_TEXT_MAINPAGE6_6_SE); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_SE); +TRANS(UI_TEXT_MAINPAGE_BED_SE); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_SE); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_SE); +TRANS(UI_TEXT_MAINPAGE_XY_SE); +TRANS(UI_TEXT_PRINT_TIME_VALUE_SE); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_SE); +TRANS(UI_TEXT_METER_PRINTED_SE); +TRANS(UI_TEXT_STATUS_SE); +TRANS(UI_TEXT_EMPTY_SE); +TRANS(UI_TEXT_TEMP_SET_SE); +TRANS(UI_TEXT_CURRENT_TEMP_SE); +TRANS(UI_TEXT_COATING_THICKNESS_SE); +TRANS(UI_TEXT_EXTR3_TEMP_SE); +TRANS(UI_TEXT_EXTR4_TEMP_SE); +TRANS(UI_TEXT_EXTR5_TEMP_SE); +TRANS(UI_TEXT_EXTR3_OFF_SE); +TRANS(UI_TEXT_EXTR4_OFF_SE); +TRANS(UI_TEXT_EXTR5_OFF_SE); +TRANS(UI_TEXT_EXTR3_SELECT_SE); +TRANS(UI_TEXT_EXTR4_SELECT_SE); +TRANS(UI_TEXT_EXTR5_SELECT_SE); +TRANS(UI_TEXT_DITTO_0_SE); +TRANS(UI_TEXT_DITTO_1_SE); +TRANS(UI_TEXT_DITTO_2_SE); +TRANS(UI_TEXT_DITTO_3_SE); +TRANS(UI_TEXT_ZPROBE_HEIGHT_SE); +TRANS(UI_TEXT_OFFSETS_SE); +TRANS(UI_TEXT_X_OFFSET_SE); +TRANS(UI_TEXT_Y_OFFSET_SE); +TRANS(UI_TEXT_Z_OFFSET_SE); + +PGM_P const translations_se[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_SE, + FUI_TEXT_OFF_SE, + FUI_TEXT_NA_SE, + FUI_TEXT_YES_SE, + FUI_TEXT_NO_SE, + FUI_TEXT_PRINT_POS_SE, + FUI_TEXT_PRINTING_SE, + FUI_TEXT_IDLE_SE, + FUI_TEXT_NOSDCARD_SE, + FUI_TEXT_ERROR_SE, + FUI_TEXT_BACK_SE, + FUI_TEXT_QUICK_SETTINGS_SE, + FUI_TEXT_ERRORMSG_SE, + FUI_TEXT_CONFIGURATION_SE, + FUI_TEXT_POSITION_SE, + FUI_TEXT_EXTRUDER_SE, + FUI_TEXT_SD_CARD_SE, + FUI_TEXT_DEBUGGING_SE, + FUI_TEXT_HOME_DELTA_SE, + FUI_TEXT_HOME_ALL_SE, + FUI_TEXT_HOME_X_SE, + FUI_TEXT_HOME_Y_SE, + FUI_TEXT_HOME_Z_SE, + FUI_TEXT_PREHEAT_PLA_SE, + FUI_TEXT_PREHEAT_ABS_SE, + FUI_TEXT_LIGHTS_ONOFF_SE, + FUI_TEXT_COOLDOWN_SE, + FUI_TEXT_SET_TO_ORIGIN_SE, + FUI_TEXT_DISABLE_STEPPER_SE, + FUI_TEXT_X_POSITION_SE, + FUI_TEXT_X_POS_FAST_SE, + FUI_TEXT_Y_POSITION_SE, + FUI_TEXT_Y_POS_FAST_SE, + FUI_TEXT_Z_POSITION_SE, + FUI_TEXT_Z_POS_FAST_SE, + FUI_TEXT_E_POSITION_SE, + FUI_TEXT_BED_TEMP_SE, + FUI_TEXT_EXTR0_TEMP_SE, + FUI_TEXT_EXTR1_TEMP_SE, + FUI_TEXT_EXTR2_TEMP_SE, + FUI_TEXT_EXTR0_OFF_SE, + FUI_TEXT_EXTR1_OFF_SE, + FUI_TEXT_EXTR2_OFF_SE, + FUI_TEXT_EXTR0_SELECT_SE, + FUI_TEXT_EXTR1_SELECT_SE, + FUI_TEXT_EXTR2_SELECT_SE, + FUI_TEXT_EXTR_ORIGIN_SE, + FUI_TEXT_PRINT_X_SE, + FUI_TEXT_PRINT_Y_SE, + FUI_TEXT_PRINT_Z_SE, + FUI_TEXT_PRINT_Z_DELTA_SE, + FUI_TEXT_MOVE_X_SE, + FUI_TEXT_MOVE_Y_SE, + FUI_TEXT_MOVE_Z_SE, + FUI_TEXT_MOVE_Z_DELTA_SE, + FUI_TEXT_JERK_SE, + FUI_TEXT_ZJERK_SE, + FUI_TEXT_ACCELERATION_SE, + FUI_TEXT_STORE_TO_EEPROM_SE, + FUI_TEXT_LOAD_EEPROM_SE, + FUI_TEXT_DBG_ECHO_SE, + FUI_TEXT_DBG_INFO_SE, + FUI_TEXT_DBG_ERROR_SE, + FUI_TEXT_DBG_DRYRUN_SE, + FUI_TEXT_OPS_OFF_SE, + FUI_TEXT_OPS_CLASSIC_SE, + FUI_TEXT_OPS_FAST_SE, + FUI_TEXT_OPS_RETRACT_SE, + FUI_TEXT_OPS_BACKSLASH_SE, + FUI_TEXT_OPS_MINDIST_SE, + FUI_TEXT_OPS_MOVE_AFTER_SE, + FUI_TEXT_ANTI_OOZE_SE, + FUI_TEXT_PRINT_FILE_SE, + FUI_TEXT_PAUSE_PRINT_SE, + FUI_TEXT_CONTINUE_PRINT_SE, + FUI_TEXT_UNMOUNT_CARD_SE, + FUI_TEXT_MOUNT_CARD_SE, + FUI_TEXT_DELETE_FILE_SE, + FUI_TEXT_FEEDRATE_SE, + FUI_TEXT_FEED_MAX_X_SE, + FUI_TEXT_FEED_MAX_Y_SE, + FUI_TEXT_FEED_MAX_Z_SE, + FUI_TEXT_FEED_MAX_Z_DELTA_SE, + FUI_TEXT_FEED_HOME_X_SE, + FUI_TEXT_FEED_HOME_Y_SE, + FUI_TEXT_FEED_HOME_Z_SE, + FUI_TEXT_FEED_HOME_Z_DELTA_SE, + FUI_TEXT_ACTION_XPOSITION4A_SE, + FUI_TEXT_ACTION_XPOSITION4B_SE, + FUI_TEXT_ACTION_XPOSITION4C_SE, + FUI_TEXT_ACTION_XPOSITION4D_SE, + FUI_TEXT_ACTION_YPOSITION4A_SE, + FUI_TEXT_ACTION_YPOSITION4B_SE, + FUI_TEXT_ACTION_YPOSITION4C_SE, + FUI_TEXT_ACTION_YPOSITION4D_SE, + FUI_TEXT_ACTION_ZPOSITION4A_SE, + FUI_TEXT_ACTION_ZPOSITION4B_SE, + FUI_TEXT_ACTION_ZPOSITION4C_SE, + FUI_TEXT_ACTION_ZPOSITION4D_SE, + FUI_TEXT_ACTION_XPOSITION_FAST4A_SE, + FUI_TEXT_ACTION_XPOSITION_FAST4B_SE, + FUI_TEXT_ACTION_XPOSITION_FAST4C_SE, + FUI_TEXT_ACTION_XPOSITION_FAST4D_SE, + FUI_TEXT_ACTION_YPOSITION_FAST4A_SE, + FUI_TEXT_ACTION_YPOSITION_FAST4B_SE, + FUI_TEXT_ACTION_YPOSITION_FAST4C_SE, + FUI_TEXT_ACTION_YPOSITION_FAST4D_SE, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_SE, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_SE, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_SE, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_SE, + FUI_TEXT_ACTION_EPOSITION_FAST2A_SE, + FUI_TEXT_ACTION_EPOSITION_FAST2B_SE, + FUI_TEXT_ACTION_XPOSITION2A_SE, + FUI_TEXT_ACTION_XPOSITION2B_SE, + FUI_TEXT_ACTION_YPOSITION2A_SE, + FUI_TEXT_ACTION_YPOSITION2B_SE, + FUI_TEXT_ACTION_ZPOSITION2A_SE, + FUI_TEXT_ACTION_ZPOSITION2B_SE, + FUI_TEXT_ACTION_XPOSITION_FAST2A_SE, + FUI_TEXT_ACTION_XPOSITION_FAST2B_SE, + FUI_TEXT_ACTION_YPOSITION_FAST2A_SE, + FUI_TEXT_ACTION_YPOSITION_FAST2B_SE, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_SE, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_SE, + FUI_TEXT_FANSPEED_SE, + FUI_TEXT_ACTION_FANSPEED_SE, + FUI_TEXT_FAN_OFF_SE, + FUI_TEXT_FAN_25_SE, + FUI_TEXT_FAN_50_SE, + FUI_TEXT_FAN_75_SE, + FUI_TEXT_FAN_FULL_SE, + FUI_TEXT_STEPPER_INACTIVE_SE, + FUI_TEXT_STEPPER_INACTIVE2A_SE, + FUI_TEXT_STEPPER_INACTIVE2B_SE, + FUI_TEXT_POWER_INACTIVE_SE, + FUI_TEXT_POWER_INACTIVE2A_SE, + FUI_TEXT_POWER_INACTIVE2B_SE, + FUI_TEXT_GENERAL_SE, + FUI_TEXT_BAUDRATE_SE, + FUI_TEXT_EXTR_STEPS_SE, + FUI_TEXT_EXTR_START_FEED_SE, + FUI_TEXT_EXTR_MAX_FEED_SE, + FUI_TEXT_EXTR_ACCEL_SE, + FUI_TEXT_EXTR_WATCH_SE, + FUI_TEXT_EXTR_ADVANCE_L_SE, + FUI_TEXT_EXTR_ADVANCE_K_SE, + FUI_TEXT_EXTR_MANAGER_SE, + FUI_TEXT_EXTR_PGAIN_SE, + FUI_TEXT_EXTR_DEADTIME_SE, + FUI_TEXT_EXTR_DMAX_DT_SE, + FUI_TEXT_EXTR_IGAIN_SE, + FUI_TEXT_EXTR_DGAIN_SE, + FUI_TEXT_EXTR_DMIN_SE, + FUI_TEXT_EXTR_DMAX_SE, + FUI_TEXT_EXTR_PMAX_SE, + FUI_TEXT_EXTR_XOFF_SE, + FUI_TEXT_EXTR_YOFF_SE, + FUI_TEXT_STRING_HM_BANGBANG_SE, + FUI_TEXT_STRING_HM_PID_SE, + FUI_TEXT_STRING_ACTION_SE, + FUI_TEXT_HEATING_EXTRUDER_SE, + FUI_TEXT_HEATING_BED_SE, + FUI_TEXT_KILLED_SE, + FUI_TEXT_STEPPER_DISABLED_SE, + FUI_TEXT_EEPROM_STOREDA_SE, + FUI_TEXT_EEPROM_STOREDB_SE, + FUI_TEXT_EEPROM_LOADEDA_SE, + FUI_TEXT_EEPROM_LOADEDB_SE, + FUI_TEXT_UPLOADING_SE, + FUI_TEXT_PAGE_BUFFER_SE, + FUI_TEXT_PAGE_EXTRUDER_SE, + FUI_TEXT_PAGE_EXTRUDER1_SE, + FUI_TEXT_PAGE_EXTRUDER2_SE, + FUI_TEXT_PAGE_EXTRUDER3_SE, + FUI_TEXT_PAGE_BED_SE, + FUI_TEXT_SPEED_MULTIPLY_SE, + FUI_TEXT_FLOW_MULTIPLY_SE, + FUI_TEXT_SHOW_MEASUREMENT_SE, + FUI_TEXT_RESET_MEASUREMENT_SE, + FUI_TEXT_SET_MEASURED_ORIGIN_SE, + FUI_TEXT_ZCALIB_SE, + FUI_TEXT_SET_P1_SE, + FUI_TEXT_SET_P2_SE, + FUI_TEXT_SET_P3_SE, + FUI_TEXT_CALCULATE_LEVELING_SE, + FUI_TEXT_LEVEL_SE, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_SE, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_SE, + FUI_TEXT_SD_REMOVED_SE, + FUI_TEXT_SD_INSERTED_SE, + FUI_TEXT_PRINTER_READY_SE, + FUI_TEXT_PRINTTIME_DAYS_SE, + FUI_TEXT_PRINTTIME_HOURS_SE, + FUI_TEXT_PRINTTIME_MINUTES_SE, + FUI_TEXT_PRINT_TIME_SE, + FUI_TEXT_PRINT_FILAMENT_SE, + FUI_TEXT_PRINTED_SE, + FUI_TEXT_POWER_SE, + FUI_TEXT_STRING_HM_DEADTIME_SE, + FUI_TEXT_STRING_HM_SLOWBANG_SE, + FUI_TEXT_STOP_PRINT_SE, + FUI_TEXT_Z_BABYSTEPPING_SE, + FUI_TEXT_CHANGE_FILAMENT_SE, + FUI_TEXT_WIZ_CH_FILAMENT1_SE, + FUI_TEXT_WIZ_CH_FILAMENT2_SE, + FUI_TEXT_WIZ_CH_FILAMENT3_SE, + FUI_TEXT_CLICK_DONE_SE, + FUI_TEXT_AUTOLEVEL_ONOFF_SE, + FUI_TEXT_SERVOPOS_SE, + FUI_TEXT_IGNORE_M106_SE, + FUI_TEXT_WIZ_REHEAT1_SE, + FUI_TEXT_WIZ_REHEAT2_SE, + FUI_TEXT_WIZ_WAITTEMP1_SE, + FUI_TEXT_WIZ_WAITTEMP2_SE, + FUI_TEXT_EXTRUDER_JAM_SE, + FUI_TEXT_STANDBY_SE, + FUI_TEXT_BED_COATING_SE, + FUI_TEXT_BED_COATING_SET1_SE, + FUI_TEXT_BED_COATING_SET2_SE, + FUI_TEXT_NOCOATING_SE, + FUI_TEXT_BUILDTAK_SE, + FUI_TEXT_KAPTON_SE, + FUI_TEXT_BLUETAPE_SE, + FUI_TEXT_PETTAPE_SE, + FUI_TEXT_GLUESTICK_SE, + FUI_TEXT_CUSTOM_SE, + FUI_TEXT_COATING_CUSTOM_SE, + FUI_TEXT_LANGUAGE_SE, + FUI_TEXT_MAINPAGE6_1_SE, + FUI_TEXT_MAINPAGE6_2_SE, + FUI_TEXT_MAINPAGE6_3_SE, + FUI_TEXT_MAINPAGE6_4_SE, + FUI_TEXT_MAINPAGE6_5_SE, + FUI_TEXT_MAINPAGE6_6_SE, + FUI_TEXT_MAINPAGE_TEMP_BED_SE, + FUI_TEXT_MAINPAGE_BED_SE, + FUI_TEXT_MAINPAGE_Z_BUF_SE, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_SE, + FUI_TEXT_MAINPAGE_XY_SE, + FUI_TEXT_PRINT_TIME_VALUE_SE, + FUI_TEXT_PRINT_FILAMENT_VALUE_SE, + FUI_TEXT_METER_PRINTED_SE, + FUI_TEXT_STATUS_SE, + FUI_TEXT_EMPTY_SE, + FUI_TEXT_TEMP_SET_SE, + FUI_TEXT_CURRENT_TEMP_SE, + FUI_TEXT_COATING_THICKNESS_SE, + FUI_TEXT_EXTR3_TEMP_SE, + FUI_TEXT_EXTR4_TEMP_SE, + FUI_TEXT_EXTR5_TEMP_SE, + FUI_TEXT_EXTR3_OFF_SE, + FUI_TEXT_EXTR4_OFF_SE, + FUI_TEXT_EXTR5_OFF_SE, + FUI_TEXT_EXTR3_SELECT_SE, + FUI_TEXT_EXTR4_SELECT_SE, + FUI_TEXT_EXTR5_SELECT_SE, + FUI_TEXT_DITTO_0_SE, + FUI_TEXT_DITTO_1_SE, + FUI_TEXT_DITTO_2_SE, + FUI_TEXT_DITTO_3_SE, + FUI_TEXT_ZPROBE_HEIGHT_SE, + FUI_TEXT_OFFSETS_SE, + FUI_TEXT_X_OFFSET_SE, + FUI_TEXT_Y_OFFSET_SE, + FUI_TEXT_Z_OFFSET_SE +}; +#define LANG_SE_TABLE translations_se +#else +#define LANG_SE_TABLE NULL +#endif // LANGUAGE_SE_ACTIVE + + +#if LANGUAGE_FR_ACTIVE +TRANS(UI_TEXT_ON_FR); +TRANS(UI_TEXT_OFF_FR); +TRANS(UI_TEXT_NA_FR); +TRANS(UI_TEXT_YES_FR); +TRANS(UI_TEXT_NO_FR); +TRANS(UI_TEXT_PRINT_POS_FR); +TRANS(UI_TEXT_PRINTING_FR); +TRANS(UI_TEXT_IDLE_FR); +TRANS(UI_TEXT_NOSDCARD_FR); +TRANS(UI_TEXT_ERROR_FR); +TRANS(UI_TEXT_BACK_FR); +TRANS(UI_TEXT_QUICK_SETTINGS_FR); +TRANS(UI_TEXT_ERRORMSG_FR); +TRANS(UI_TEXT_CONFIGURATION_FR); +TRANS(UI_TEXT_POSITION_FR); +TRANS(UI_TEXT_EXTRUDER_FR); +TRANS(UI_TEXT_SD_CARD_FR); +TRANS(UI_TEXT_DEBUGGING_FR); +TRANS(UI_TEXT_HOME_DELTA_FR); +TRANS(UI_TEXT_HOME_ALL_FR); +TRANS(UI_TEXT_HOME_X_FR); +TRANS(UI_TEXT_HOME_Y_FR); +TRANS(UI_TEXT_HOME_Z_FR); +TRANS(UI_TEXT_PREHEAT_PLA_FR); +TRANS(UI_TEXT_PREHEAT_ABS_FR); +TRANS(UI_TEXT_LIGHTS_ONOFF_FR); +TRANS(UI_TEXT_COOLDOWN_FR); +TRANS(UI_TEXT_SET_TO_ORIGIN_FR); +TRANS(UI_TEXT_DISABLE_STEPPER_FR); +TRANS(UI_TEXT_X_POSITION_FR); +TRANS(UI_TEXT_X_POS_FAST_FR); +TRANS(UI_TEXT_Y_POSITION_FR); +TRANS(UI_TEXT_Y_POS_FAST_FR); +TRANS(UI_TEXT_Z_POSITION_FR); +TRANS(UI_TEXT_Z_POS_FAST_FR); +TRANS(UI_TEXT_E_POSITION_FR); +TRANS(UI_TEXT_BED_TEMP_FR); +TRANS(UI_TEXT_EXTR0_TEMP_FR); +TRANS(UI_TEXT_EXTR1_TEMP_FR); +TRANS(UI_TEXT_EXTR2_TEMP_FR); +TRANS(UI_TEXT_EXTR0_OFF_FR); +TRANS(UI_TEXT_EXTR1_OFF_FR); +TRANS(UI_TEXT_EXTR2_OFF_FR); +TRANS(UI_TEXT_EXTR0_SELECT_FR); +TRANS(UI_TEXT_EXTR1_SELECT_FR); +TRANS(UI_TEXT_EXTR2_SELECT_FR); +TRANS(UI_TEXT_EXTR_ORIGIN_FR); +TRANS(UI_TEXT_PRINT_X_FR); +TRANS(UI_TEXT_PRINT_Y_FR); +TRANS(UI_TEXT_PRINT_Z_FR); +TRANS(UI_TEXT_PRINT_Z_DELTA_FR); +TRANS(UI_TEXT_MOVE_X_FR); +TRANS(UI_TEXT_MOVE_Y_FR); +TRANS(UI_TEXT_MOVE_Z_FR); +TRANS(UI_TEXT_MOVE_Z_DELTA_FR); +TRANS(UI_TEXT_JERK_FR); +TRANS(UI_TEXT_ZJERK_FR); +TRANS(UI_TEXT_ACCELERATION_FR); +TRANS(UI_TEXT_STORE_TO_EEPROM_FR); +TRANS(UI_TEXT_LOAD_EEPROM_FR); +TRANS(UI_TEXT_DBG_ECHO_FR); +TRANS(UI_TEXT_DBG_INFO_FR); +TRANS(UI_TEXT_DBG_ERROR_FR); +TRANS(UI_TEXT_DBG_DRYRUN_FR); +TRANS(UI_TEXT_OPS_OFF_FR); +TRANS(UI_TEXT_OPS_CLASSIC_FR); +TRANS(UI_TEXT_OPS_FAST_FR); +TRANS(UI_TEXT_OPS_RETRACT_FR); +TRANS(UI_TEXT_OPS_BACKSLASH_FR); +TRANS(UI_TEXT_OPS_MINDIST_FR); +TRANS(UI_TEXT_OPS_MOVE_AFTER_FR); +TRANS(UI_TEXT_ANTI_OOZE_FR); +TRANS(UI_TEXT_PRINT_FILE_FR); +TRANS(UI_TEXT_PAUSE_PRINT_FR); +TRANS(UI_TEXT_CONTINUE_PRINT_FR); +TRANS(UI_TEXT_UNMOUNT_CARD_FR); +TRANS(UI_TEXT_MOUNT_CARD_FR); +TRANS(UI_TEXT_DELETE_FILE_FR); +TRANS(UI_TEXT_FEEDRATE_FR); +TRANS(UI_TEXT_FEED_MAX_X_FR); +TRANS(UI_TEXT_FEED_MAX_Y_FR); +TRANS(UI_TEXT_FEED_MAX_Z_FR); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_FR); +TRANS(UI_TEXT_FEED_HOME_X_FR); +TRANS(UI_TEXT_FEED_HOME_Y_FR); +TRANS(UI_TEXT_FEED_HOME_Z_FR); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_FR); +TRANS(UI_TEXT_ACTION_XPOSITION4A_FR); +TRANS(UI_TEXT_ACTION_XPOSITION4B_FR); +TRANS(UI_TEXT_ACTION_XPOSITION4C_FR); +TRANS(UI_TEXT_ACTION_XPOSITION4D_FR); +TRANS(UI_TEXT_ACTION_YPOSITION4A_FR); +TRANS(UI_TEXT_ACTION_YPOSITION4B_FR); +TRANS(UI_TEXT_ACTION_YPOSITION4C_FR); +TRANS(UI_TEXT_ACTION_YPOSITION4D_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_FR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_FR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_FR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_FR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_FR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_FR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_FR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_FR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_FR); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_FR); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_FR); +TRANS(UI_TEXT_ACTION_XPOSITION2A_FR); +TRANS(UI_TEXT_ACTION_XPOSITION2B_FR); +TRANS(UI_TEXT_ACTION_YPOSITION2A_FR); +TRANS(UI_TEXT_ACTION_YPOSITION2B_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_FR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_FR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_FR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_FR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_FR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_FR); +TRANS(UI_TEXT_FANSPEED_FR); +TRANS(UI_TEXT_ACTION_FANSPEED_FR); +TRANS(UI_TEXT_FAN_OFF_FR); +TRANS(UI_TEXT_FAN_25_FR); +TRANS(UI_TEXT_FAN_50_FR); +TRANS(UI_TEXT_FAN_75_FR); +TRANS(UI_TEXT_FAN_FULL_FR); +TRANS(UI_TEXT_STEPPER_INACTIVE_FR); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_FR); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_FR); +TRANS(UI_TEXT_POWER_INACTIVE_FR); +TRANS(UI_TEXT_POWER_INACTIVE2A_FR); +TRANS(UI_TEXT_POWER_INACTIVE2B_FR); +TRANS(UI_TEXT_GENERAL_FR); +TRANS(UI_TEXT_BAUDRATE_FR); +TRANS(UI_TEXT_EXTR_STEPS_FR); +TRANS(UI_TEXT_EXTR_START_FEED_FR); +TRANS(UI_TEXT_EXTR_MAX_FEED_FR); +TRANS(UI_TEXT_EXTR_ACCEL_FR); +TRANS(UI_TEXT_EXTR_WATCH_FR); +TRANS(UI_TEXT_EXTR_ADVANCE_L_FR); +TRANS(UI_TEXT_EXTR_ADVANCE_K_FR); +TRANS(UI_TEXT_EXTR_MANAGER_FR); +TRANS(UI_TEXT_EXTR_PGAIN_FR); +TRANS(UI_TEXT_EXTR_DEADTIME_FR); +TRANS(UI_TEXT_EXTR_DMAX_DT_FR); +TRANS(UI_TEXT_EXTR_IGAIN_FR); +TRANS(UI_TEXT_EXTR_DGAIN_FR); +TRANS(UI_TEXT_EXTR_DMIN_FR); +TRANS(UI_TEXT_EXTR_DMAX_FR); +TRANS(UI_TEXT_EXTR_PMAX_FR); +TRANS(UI_TEXT_EXTR_XOFF_FR); +TRANS(UI_TEXT_EXTR_YOFF_FR); +TRANS(UI_TEXT_STRING_HM_BANGBANG_FR); +TRANS(UI_TEXT_STRING_HM_PID_FR); +TRANS(UI_TEXT_STRING_ACTION_FR); +TRANS(UI_TEXT_HEATING_EXTRUDER_FR); +TRANS(UI_TEXT_HEATING_BED_FR); +TRANS(UI_TEXT_KILLED_FR); +TRANS(UI_TEXT_STEPPER_DISABLED_FR); +TRANS(UI_TEXT_EEPROM_STOREDA_FR); +TRANS(UI_TEXT_EEPROM_STOREDB_FR); +TRANS(UI_TEXT_EEPROM_LOADEDA_FR); +TRANS(UI_TEXT_EEPROM_LOADEDB_FR); +TRANS(UI_TEXT_UPLOADING_FR); +TRANS(UI_TEXT_PAGE_BUFFER_FR); +TRANS(UI_TEXT_PAGE_EXTRUDER_FR); +TRANS(UI_TEXT_PAGE_EXTRUDER1_FR); +TRANS(UI_TEXT_PAGE_EXTRUDER2_FR); +TRANS(UI_TEXT_PAGE_EXTRUDER3_FR); +TRANS(UI_TEXT_PAGE_BED_FR); +TRANS(UI_TEXT_SPEED_MULTIPLY_FR); +TRANS(UI_TEXT_FLOW_MULTIPLY_FR); +TRANS(UI_TEXT_SHOW_MEASUREMENT_FR); +TRANS(UI_TEXT_RESET_MEASUREMENT_FR); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_FR); +TRANS(UI_TEXT_ZCALIB_FR); +TRANS(UI_TEXT_SET_P1_FR); +TRANS(UI_TEXT_SET_P2_FR); +TRANS(UI_TEXT_SET_P3_FR); +TRANS(UI_TEXT_CALCULATE_LEVELING_FR); +TRANS(UI_TEXT_LEVEL_FR); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_FR); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_FR); +TRANS(UI_TEXT_SD_REMOVED_FR); +TRANS(UI_TEXT_SD_INSERTED_FR); +TRANS(UI_TEXT_PRINTER_READY_FR); +TRANS(UI_TEXT_PRINTTIME_DAYS_FR); +TRANS(UI_TEXT_PRINTTIME_HOURS_FR); +TRANS(UI_TEXT_PRINTTIME_MINUTES_FR); +TRANS(UI_TEXT_PRINT_TIME_FR); +TRANS(UI_TEXT_PRINT_FILAMENT_FR); +TRANS(UI_TEXT_PRINTED_FR); +TRANS(UI_TEXT_POWER_FR); +TRANS(UI_TEXT_STRING_HM_DEADTIME_FR); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_FR); +TRANS(UI_TEXT_STOP_PRINT_FR); +TRANS(UI_TEXT_Z_BABYSTEPPING_FR); +TRANS(UI_TEXT_CHANGE_FILAMENT_FR); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_FR); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_FR); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_FR); +TRANS(UI_TEXT_CLICK_DONE_FR); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_FR); +TRANS(UI_TEXT_SERVOPOS_FR); +TRANS(UI_TEXT_IGNORE_M106_FR); +TRANS(UI_TEXT_WIZ_REHEAT1_FR); +TRANS(UI_TEXT_WIZ_REHEAT2_FR); +TRANS(UI_TEXT_WIZ_WAITTEMP1_FR); +TRANS(UI_TEXT_WIZ_WAITTEMP2_FR); +TRANS(UI_TEXT_EXTRUDER_JAM_FR); +TRANS(UI_TEXT_STANDBY_FR); +TRANS(UI_TEXT_BED_COATING_FR); +TRANS(UI_TEXT_BED_COATING_SET1_FR); +TRANS(UI_TEXT_BED_COATING_SET2_FR); +TRANS(UI_TEXT_NOCOATING_FR); +TRANS(UI_TEXT_BUILDTAK_FR); +TRANS(UI_TEXT_KAPTON_FR); +TRANS(UI_TEXT_BLUETAPE_FR); +TRANS(UI_TEXT_PETTAPE_FR); +TRANS(UI_TEXT_GLUESTICK_FR); +TRANS(UI_TEXT_CUSTOM_FR); +TRANS(UI_TEXT_COATING_CUSTOM_FR); +TRANS(UI_TEXT_LANGUAGE_FR); +TRANS(UI_TEXT_MAINPAGE6_1_FR); +TRANS(UI_TEXT_MAINPAGE6_2_FR); +TRANS(UI_TEXT_MAINPAGE6_3_FR); +TRANS(UI_TEXT_MAINPAGE6_4_FR); +TRANS(UI_TEXT_MAINPAGE6_5_FR); +TRANS(UI_TEXT_MAINPAGE6_6_FR); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_FR); +TRANS(UI_TEXT_MAINPAGE_BED_FR); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_FR); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_FR); +TRANS(UI_TEXT_MAINPAGE_XY_FR); +TRANS(UI_TEXT_PRINT_TIME_VALUE_FR); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_FR); +TRANS(UI_TEXT_METER_PRINTED_FR); +TRANS(UI_TEXT_STATUS_FR); +TRANS(UI_TEXT_EMPTY_FR); +TRANS(UI_TEXT_TEMP_SET_FR); +TRANS(UI_TEXT_CURRENT_TEMP_FR); +TRANS(UI_TEXT_COATING_THICKNESS_FR); +TRANS(UI_TEXT_EXTR3_TEMP_FR); +TRANS(UI_TEXT_EXTR4_TEMP_FR); +TRANS(UI_TEXT_EXTR5_TEMP_FR); +TRANS(UI_TEXT_EXTR3_OFF_FR); +TRANS(UI_TEXT_EXTR4_OFF_FR); +TRANS(UI_TEXT_EXTR5_OFF_FR); +TRANS(UI_TEXT_EXTR3_SELECT_FR); +TRANS(UI_TEXT_EXTR4_SELECT_FR); +TRANS(UI_TEXT_EXTR5_SELECT_FR); +TRANS(UI_TEXT_DITTO_0_FR); +TRANS(UI_TEXT_DITTO_1_FR); +TRANS(UI_TEXT_DITTO_2_FR); +TRANS(UI_TEXT_DITTO_3_FR); +TRANS(UI_TEXT_ZPROBE_HEIGHT_FR); +TRANS(UI_TEXT_OFFSETS_FR); +TRANS(UI_TEXT_X_OFFSET_FR); +TRANS(UI_TEXT_Y_OFFSET_FR); +TRANS(UI_TEXT_Z_OFFSET_FR); + +PGM_P const translations_fr[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_FR, + FUI_TEXT_OFF_FR, + FUI_TEXT_NA_FR, + FUI_TEXT_YES_FR, + FUI_TEXT_NO_FR, + FUI_TEXT_PRINT_POS_FR, + FUI_TEXT_PRINTING_FR, + FUI_TEXT_IDLE_FR, + FUI_TEXT_NOSDCARD_FR, + FUI_TEXT_ERROR_FR, + FUI_TEXT_BACK_FR, + FUI_TEXT_QUICK_SETTINGS_FR, + FUI_TEXT_ERRORMSG_FR, + FUI_TEXT_CONFIGURATION_FR, + FUI_TEXT_POSITION_FR, + FUI_TEXT_EXTRUDER_FR, + FUI_TEXT_SD_CARD_FR, + FUI_TEXT_DEBUGGING_FR, + FUI_TEXT_HOME_DELTA_FR, + FUI_TEXT_HOME_ALL_FR, + FUI_TEXT_HOME_X_FR, + FUI_TEXT_HOME_Y_FR, + FUI_TEXT_HOME_Z_FR, + FUI_TEXT_PREHEAT_PLA_FR, + FUI_TEXT_PREHEAT_ABS_FR, + FUI_TEXT_LIGHTS_ONOFF_FR, + FUI_TEXT_COOLDOWN_FR, + FUI_TEXT_SET_TO_ORIGIN_FR, + FUI_TEXT_DISABLE_STEPPER_FR, + FUI_TEXT_X_POSITION_FR, + FUI_TEXT_X_POS_FAST_FR, + FUI_TEXT_Y_POSITION_FR, + FUI_TEXT_Y_POS_FAST_FR, + FUI_TEXT_Z_POSITION_FR, + FUI_TEXT_Z_POS_FAST_FR, + FUI_TEXT_E_POSITION_FR, + FUI_TEXT_BED_TEMP_FR, + FUI_TEXT_EXTR0_TEMP_FR, + FUI_TEXT_EXTR1_TEMP_FR, + FUI_TEXT_EXTR2_TEMP_FR, + FUI_TEXT_EXTR0_OFF_FR, + FUI_TEXT_EXTR1_OFF_FR, + FUI_TEXT_EXTR2_OFF_FR, + FUI_TEXT_EXTR0_SELECT_FR, + FUI_TEXT_EXTR1_SELECT_FR, + FUI_TEXT_EXTR2_SELECT_FR, + FUI_TEXT_EXTR_ORIGIN_FR, + FUI_TEXT_PRINT_X_FR, + FUI_TEXT_PRINT_Y_FR, + FUI_TEXT_PRINT_Z_FR, + FUI_TEXT_PRINT_Z_DELTA_FR, + FUI_TEXT_MOVE_X_FR, + FUI_TEXT_MOVE_Y_FR, + FUI_TEXT_MOVE_Z_FR, + FUI_TEXT_MOVE_Z_DELTA_FR, + FUI_TEXT_JERK_FR, + FUI_TEXT_ZJERK_FR, + FUI_TEXT_ACCELERATION_FR, + FUI_TEXT_STORE_TO_EEPROM_FR, + FUI_TEXT_LOAD_EEPROM_FR, + FUI_TEXT_DBG_ECHO_FR, + FUI_TEXT_DBG_INFO_FR, + FUI_TEXT_DBG_ERROR_FR, + FUI_TEXT_DBG_DRYRUN_FR, + FUI_TEXT_OPS_OFF_FR, + FUI_TEXT_OPS_CLASSIC_FR, + FUI_TEXT_OPS_FAST_FR, + FUI_TEXT_OPS_RETRACT_FR, + FUI_TEXT_OPS_BACKSLASH_FR, + FUI_TEXT_OPS_MINDIST_FR, + FUI_TEXT_OPS_MOVE_AFTER_FR, + FUI_TEXT_ANTI_OOZE_FR, + FUI_TEXT_PRINT_FILE_FR, + FUI_TEXT_PAUSE_PRINT_FR, + FUI_TEXT_CONTINUE_PRINT_FR, + FUI_TEXT_UNMOUNT_CARD_FR, + FUI_TEXT_MOUNT_CARD_FR, + FUI_TEXT_DELETE_FILE_FR, + FUI_TEXT_FEEDRATE_FR, + FUI_TEXT_FEED_MAX_X_FR, + FUI_TEXT_FEED_MAX_Y_FR, + FUI_TEXT_FEED_MAX_Z_FR, + FUI_TEXT_FEED_MAX_Z_DELTA_FR, + FUI_TEXT_FEED_HOME_X_FR, + FUI_TEXT_FEED_HOME_Y_FR, + FUI_TEXT_FEED_HOME_Z_FR, + FUI_TEXT_FEED_HOME_Z_DELTA_FR, + FUI_TEXT_ACTION_XPOSITION4A_FR, + FUI_TEXT_ACTION_XPOSITION4B_FR, + FUI_TEXT_ACTION_XPOSITION4C_FR, + FUI_TEXT_ACTION_XPOSITION4D_FR, + FUI_TEXT_ACTION_YPOSITION4A_FR, + FUI_TEXT_ACTION_YPOSITION4B_FR, + FUI_TEXT_ACTION_YPOSITION4C_FR, + FUI_TEXT_ACTION_YPOSITION4D_FR, + FUI_TEXT_ACTION_ZPOSITION4A_FR, + FUI_TEXT_ACTION_ZPOSITION4B_FR, + FUI_TEXT_ACTION_ZPOSITION4C_FR, + FUI_TEXT_ACTION_ZPOSITION4D_FR, + FUI_TEXT_ACTION_XPOSITION_FAST4A_FR, + FUI_TEXT_ACTION_XPOSITION_FAST4B_FR, + FUI_TEXT_ACTION_XPOSITION_FAST4C_FR, + FUI_TEXT_ACTION_XPOSITION_FAST4D_FR, + FUI_TEXT_ACTION_YPOSITION_FAST4A_FR, + FUI_TEXT_ACTION_YPOSITION_FAST4B_FR, + FUI_TEXT_ACTION_YPOSITION_FAST4C_FR, + FUI_TEXT_ACTION_YPOSITION_FAST4D_FR, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_FR, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_FR, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_FR, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_FR, + FUI_TEXT_ACTION_EPOSITION_FAST2A_FR, + FUI_TEXT_ACTION_EPOSITION_FAST2B_FR, + FUI_TEXT_ACTION_XPOSITION2A_FR, + FUI_TEXT_ACTION_XPOSITION2B_FR, + FUI_TEXT_ACTION_YPOSITION2A_FR, + FUI_TEXT_ACTION_YPOSITION2B_FR, + FUI_TEXT_ACTION_ZPOSITION2A_FR, + FUI_TEXT_ACTION_ZPOSITION2B_FR, + FUI_TEXT_ACTION_XPOSITION_FAST2A_FR, + FUI_TEXT_ACTION_XPOSITION_FAST2B_FR, + FUI_TEXT_ACTION_YPOSITION_FAST2A_FR, + FUI_TEXT_ACTION_YPOSITION_FAST2B_FR, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_FR, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_FR, + FUI_TEXT_FANSPEED_FR, + FUI_TEXT_ACTION_FANSPEED_FR, + FUI_TEXT_FAN_OFF_FR, + FUI_TEXT_FAN_25_FR, + FUI_TEXT_FAN_50_FR, + FUI_TEXT_FAN_75_FR, + FUI_TEXT_FAN_FULL_FR, + FUI_TEXT_STEPPER_INACTIVE_FR, + FUI_TEXT_STEPPER_INACTIVE2A_FR, + FUI_TEXT_STEPPER_INACTIVE2B_FR, + FUI_TEXT_POWER_INACTIVE_FR, + FUI_TEXT_POWER_INACTIVE2A_FR, + FUI_TEXT_POWER_INACTIVE2B_FR, + FUI_TEXT_GENERAL_FR, + FUI_TEXT_BAUDRATE_FR, + FUI_TEXT_EXTR_STEPS_FR, + FUI_TEXT_EXTR_START_FEED_FR, + FUI_TEXT_EXTR_MAX_FEED_FR, + FUI_TEXT_EXTR_ACCEL_FR, + FUI_TEXT_EXTR_WATCH_FR, + FUI_TEXT_EXTR_ADVANCE_L_FR, + FUI_TEXT_EXTR_ADVANCE_K_FR, + FUI_TEXT_EXTR_MANAGER_FR, + FUI_TEXT_EXTR_PGAIN_FR, + FUI_TEXT_EXTR_DEADTIME_FR, + FUI_TEXT_EXTR_DMAX_DT_FR, + FUI_TEXT_EXTR_IGAIN_FR, + FUI_TEXT_EXTR_DGAIN_FR, + FUI_TEXT_EXTR_DMIN_FR, + FUI_TEXT_EXTR_DMAX_FR, + FUI_TEXT_EXTR_PMAX_FR, + FUI_TEXT_EXTR_XOFF_FR, + FUI_TEXT_EXTR_YOFF_FR, + FUI_TEXT_STRING_HM_BANGBANG_FR, + FUI_TEXT_STRING_HM_PID_FR, + FUI_TEXT_STRING_ACTION_FR, + FUI_TEXT_HEATING_EXTRUDER_FR, + FUI_TEXT_HEATING_BED_FR, + FUI_TEXT_KILLED_FR, + FUI_TEXT_STEPPER_DISABLED_FR, + FUI_TEXT_EEPROM_STOREDA_FR, + FUI_TEXT_EEPROM_STOREDB_FR, + FUI_TEXT_EEPROM_LOADEDA_FR, + FUI_TEXT_EEPROM_LOADEDB_FR, + FUI_TEXT_UPLOADING_FR, + FUI_TEXT_PAGE_BUFFER_FR, + FUI_TEXT_PAGE_EXTRUDER_FR, + FUI_TEXT_PAGE_EXTRUDER1_FR, + FUI_TEXT_PAGE_EXTRUDER2_FR, + FUI_TEXT_PAGE_EXTRUDER3_FR, + FUI_TEXT_PAGE_BED_FR, + FUI_TEXT_SPEED_MULTIPLY_FR, + FUI_TEXT_FLOW_MULTIPLY_FR, + FUI_TEXT_SHOW_MEASUREMENT_FR, + FUI_TEXT_RESET_MEASUREMENT_FR, + FUI_TEXT_SET_MEASURED_ORIGIN_FR, + FUI_TEXT_ZCALIB_FR, + FUI_TEXT_SET_P1_FR, + FUI_TEXT_SET_P2_FR, + FUI_TEXT_SET_P3_FR, + FUI_TEXT_CALCULATE_LEVELING_FR, + FUI_TEXT_LEVEL_FR, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_FR, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_FR, + FUI_TEXT_SD_REMOVED_FR, + FUI_TEXT_SD_INSERTED_FR, + FUI_TEXT_PRINTER_READY_FR, + FUI_TEXT_PRINTTIME_DAYS_FR, + FUI_TEXT_PRINTTIME_HOURS_FR, + FUI_TEXT_PRINTTIME_MINUTES_FR, + FUI_TEXT_PRINT_TIME_FR, + FUI_TEXT_PRINT_FILAMENT_FR, + FUI_TEXT_PRINTED_FR, + FUI_TEXT_POWER_FR, + FUI_TEXT_STRING_HM_DEADTIME_FR, + FUI_TEXT_STRING_HM_SLOWBANG_FR, + FUI_TEXT_STOP_PRINT_FR, + FUI_TEXT_Z_BABYSTEPPING_FR, + FUI_TEXT_CHANGE_FILAMENT_FR, + FUI_TEXT_WIZ_CH_FILAMENT1_FR, + FUI_TEXT_WIZ_CH_FILAMENT2_FR, + FUI_TEXT_WIZ_CH_FILAMENT3_FR, + FUI_TEXT_CLICK_DONE_FR, + FUI_TEXT_AUTOLEVEL_ONOFF_FR, + FUI_TEXT_SERVOPOS_FR, + FUI_TEXT_IGNORE_M106_FR, + FUI_TEXT_WIZ_REHEAT1_FR, + FUI_TEXT_WIZ_REHEAT2_FR, + FUI_TEXT_WIZ_WAITTEMP1_FR, + FUI_TEXT_WIZ_WAITTEMP2_FR, + FUI_TEXT_EXTRUDER_JAM_FR, + FUI_TEXT_STANDBY_FR, + FUI_TEXT_BED_COATING_FR, + FUI_TEXT_BED_COATING_SET1_FR, + FUI_TEXT_BED_COATING_SET2_FR, + FUI_TEXT_NOCOATING_FR, + FUI_TEXT_BUILDTAK_FR, + FUI_TEXT_KAPTON_FR, + FUI_TEXT_BLUETAPE_FR, + FUI_TEXT_PETTAPE_FR, + FUI_TEXT_GLUESTICK_FR, + FUI_TEXT_CUSTOM_FR, + FUI_TEXT_COATING_CUSTOM_FR, + FUI_TEXT_LANGUAGE_FR, + FUI_TEXT_MAINPAGE6_1_FR, + FUI_TEXT_MAINPAGE6_2_FR, + FUI_TEXT_MAINPAGE6_3_FR, + FUI_TEXT_MAINPAGE6_4_FR, + FUI_TEXT_MAINPAGE6_5_FR, + FUI_TEXT_MAINPAGE6_6_FR, + FUI_TEXT_MAINPAGE_TEMP_BED_FR, + FUI_TEXT_MAINPAGE_BED_FR, + FUI_TEXT_MAINPAGE_Z_BUF_FR, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_FR, + FUI_TEXT_MAINPAGE_XY_FR, + FUI_TEXT_PRINT_TIME_VALUE_FR, + FUI_TEXT_PRINT_FILAMENT_VALUE_FR, + FUI_TEXT_METER_PRINTED_FR, + FUI_TEXT_STATUS_FR, + FUI_TEXT_EMPTY_FR, + FUI_TEXT_TEMP_SET_FR, + FUI_TEXT_CURRENT_TEMP_FR, + FUI_TEXT_COATING_THICKNESS_FR, + FUI_TEXT_EXTR3_TEMP_FR, + FUI_TEXT_EXTR4_TEMP_FR, + FUI_TEXT_EXTR5_TEMP_FR, + FUI_TEXT_EXTR3_OFF_FR, + FUI_TEXT_EXTR4_OFF_FR, + FUI_TEXT_EXTR5_OFF_FR, + FUI_TEXT_EXTR3_SELECT_FR, + FUI_TEXT_EXTR4_SELECT_FR, + FUI_TEXT_EXTR5_SELECT_FR, + FUI_TEXT_DITTO_0_FR, + FUI_TEXT_DITTO_1_FR, + FUI_TEXT_DITTO_2_FR, + FUI_TEXT_DITTO_3_FR, + FUI_TEXT_ZPROBE_HEIGHT_FR, + FUI_TEXT_OFFSETS_FR, + FUI_TEXT_X_OFFSET_FR, + FUI_TEXT_Y_OFFSET_FR, + FUI_TEXT_Z_OFFSET_FR +}; +#define LANG_FR_TABLE translations_fr +#else +#define LANG_FR_TABLE NULL +#endif // LANGUAGE_FR_ACTIVE + + +#if LANGUAGE_CZ_ACTIVE +TRANS(UI_TEXT_ON_CZ); +TRANS(UI_TEXT_OFF_CZ); +TRANS(UI_TEXT_NA_CZ); +TRANS(UI_TEXT_YES_CZ); +TRANS(UI_TEXT_NO_CZ); +TRANS(UI_TEXT_PRINT_POS_CZ); +TRANS(UI_TEXT_PRINTING_CZ); +TRANS(UI_TEXT_IDLE_CZ); +TRANS(UI_TEXT_NOSDCARD_CZ); +TRANS(UI_TEXT_ERROR_CZ); +TRANS(UI_TEXT_BACK_CZ); +TRANS(UI_TEXT_QUICK_SETTINGS_CZ); +TRANS(UI_TEXT_ERRORMSG_CZ); +TRANS(UI_TEXT_CONFIGURATION_CZ); +TRANS(UI_TEXT_POSITION_CZ); +TRANS(UI_TEXT_EXTRUDER_CZ); +TRANS(UI_TEXT_SD_CARD_CZ); +TRANS(UI_TEXT_DEBUGGING_CZ); +TRANS(UI_TEXT_HOME_DELTA_CZ); +TRANS(UI_TEXT_HOME_ALL_CZ); +TRANS(UI_TEXT_HOME_X_CZ); +TRANS(UI_TEXT_HOME_Y_CZ); +TRANS(UI_TEXT_HOME_Z_CZ); +TRANS(UI_TEXT_PREHEAT_PLA_CZ); +TRANS(UI_TEXT_PREHEAT_ABS_CZ); +TRANS(UI_TEXT_LIGHTS_ONOFF_CZ); +TRANS(UI_TEXT_COOLDOWN_CZ); +TRANS(UI_TEXT_SET_TO_ORIGIN_CZ); +TRANS(UI_TEXT_DISABLE_STEPPER_CZ); +TRANS(UI_TEXT_X_POSITION_CZ); +TRANS(UI_TEXT_X_POS_FAST_CZ); +TRANS(UI_TEXT_Y_POSITION_CZ); +TRANS(UI_TEXT_Y_POS_FAST_CZ); +TRANS(UI_TEXT_Z_POSITION_CZ); +TRANS(UI_TEXT_Z_POS_FAST_CZ); +TRANS(UI_TEXT_E_POSITION_CZ); +TRANS(UI_TEXT_BED_TEMP_CZ); +TRANS(UI_TEXT_EXTR0_TEMP_CZ); +TRANS(UI_TEXT_EXTR1_TEMP_CZ); +TRANS(UI_TEXT_EXTR2_TEMP_CZ); +TRANS(UI_TEXT_EXTR0_OFF_CZ); +TRANS(UI_TEXT_EXTR1_OFF_CZ); +TRANS(UI_TEXT_EXTR2_OFF_CZ); +TRANS(UI_TEXT_EXTR0_SELECT_CZ); +TRANS(UI_TEXT_EXTR1_SELECT_CZ); +TRANS(UI_TEXT_EXTR2_SELECT_CZ); +TRANS(UI_TEXT_EXTR_ORIGIN_CZ); +TRANS(UI_TEXT_PRINT_X_CZ); +TRANS(UI_TEXT_PRINT_Y_CZ); +TRANS(UI_TEXT_PRINT_Z_CZ); +TRANS(UI_TEXT_PRINT_Z_DELTA_CZ); +TRANS(UI_TEXT_MOVE_X_CZ); +TRANS(UI_TEXT_MOVE_Y_CZ); +TRANS(UI_TEXT_MOVE_Z_CZ); +TRANS(UI_TEXT_MOVE_Z_DELTA_CZ); +TRANS(UI_TEXT_JERK_CZ); +TRANS(UI_TEXT_ZJERK_CZ); +TRANS(UI_TEXT_ACCELERATION_CZ); +TRANS(UI_TEXT_STORE_TO_EEPROM_CZ); +TRANS(UI_TEXT_LOAD_EEPROM_CZ); +TRANS(UI_TEXT_DBG_ECHO_CZ); +TRANS(UI_TEXT_DBG_INFO_CZ); +TRANS(UI_TEXT_DBG_ERROR_CZ); +TRANS(UI_TEXT_DBG_DRYRUN_CZ); +TRANS(UI_TEXT_OPS_OFF_CZ); +TRANS(UI_TEXT_OPS_CLASSIC_CZ); +TRANS(UI_TEXT_OPS_FAST_CZ); +TRANS(UI_TEXT_OPS_RETRACT_CZ); +TRANS(UI_TEXT_OPS_BACKSLASH_CZ); +TRANS(UI_TEXT_OPS_MINDIST_CZ); +TRANS(UI_TEXT_OPS_MOVE_AFTER_CZ); +TRANS(UI_TEXT_ANTI_OOZE_CZ); +TRANS(UI_TEXT_PRINT_FILE_CZ); +TRANS(UI_TEXT_PAUSE_PRINT_CZ); +TRANS(UI_TEXT_CONTINUE_PRINT_CZ); +TRANS(UI_TEXT_UNMOUNT_CARD_CZ); +TRANS(UI_TEXT_MOUNT_CARD_CZ); +TRANS(UI_TEXT_DELETE_FILE_CZ); +TRANS(UI_TEXT_FEEDRATE_CZ); +TRANS(UI_TEXT_FEED_MAX_X_CZ); +TRANS(UI_TEXT_FEED_MAX_Y_CZ); +TRANS(UI_TEXT_FEED_MAX_Z_CZ); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_CZ); +TRANS(UI_TEXT_FEED_HOME_X_CZ); +TRANS(UI_TEXT_FEED_HOME_Y_CZ); +TRANS(UI_TEXT_FEED_HOME_Z_CZ); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION4A_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION4B_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION4C_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION4D_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION4A_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION4B_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION4C_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION4D_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_CZ); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_CZ); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION2A_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION2B_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION2A_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION2B_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_CZ); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_CZ); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_CZ); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_CZ); +TRANS(UI_TEXT_FANSPEED_CZ); +TRANS(UI_TEXT_ACTION_FANSPEED_CZ); +TRANS(UI_TEXT_FAN_OFF_CZ); +TRANS(UI_TEXT_FAN_25_CZ); +TRANS(UI_TEXT_FAN_50_CZ); +TRANS(UI_TEXT_FAN_75_CZ); +TRANS(UI_TEXT_FAN_FULL_CZ); +TRANS(UI_TEXT_STEPPER_INACTIVE_CZ); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_CZ); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_CZ); +TRANS(UI_TEXT_POWER_INACTIVE_CZ); +TRANS(UI_TEXT_POWER_INACTIVE2A_CZ); +TRANS(UI_TEXT_POWER_INACTIVE2B_CZ); +TRANS(UI_TEXT_GENERAL_CZ); +TRANS(UI_TEXT_BAUDRATE_CZ); +TRANS(UI_TEXT_EXTR_STEPS_CZ); +TRANS(UI_TEXT_EXTR_START_FEED_CZ); +TRANS(UI_TEXT_EXTR_MAX_FEED_CZ); +TRANS(UI_TEXT_EXTR_ACCEL_CZ); +TRANS(UI_TEXT_EXTR_WATCH_CZ); +TRANS(UI_TEXT_EXTR_ADVANCE_L_CZ); +TRANS(UI_TEXT_EXTR_ADVANCE_K_CZ); +TRANS(UI_TEXT_EXTR_MANAGER_CZ); +TRANS(UI_TEXT_EXTR_PGAIN_CZ); +TRANS(UI_TEXT_EXTR_DEADTIME_CZ); +TRANS(UI_TEXT_EXTR_DMAX_DT_CZ); +TRANS(UI_TEXT_EXTR_IGAIN_CZ); +TRANS(UI_TEXT_EXTR_DGAIN_CZ); +TRANS(UI_TEXT_EXTR_DMIN_CZ); +TRANS(UI_TEXT_EXTR_DMAX_CZ); +TRANS(UI_TEXT_EXTR_PMAX_CZ); +TRANS(UI_TEXT_EXTR_XOFF_CZ); +TRANS(UI_TEXT_EXTR_YOFF_CZ); +TRANS(UI_TEXT_STRING_HM_BANGBANG_CZ); +TRANS(UI_TEXT_STRING_HM_PID_CZ); +TRANS(UI_TEXT_STRING_ACTION_CZ); +TRANS(UI_TEXT_HEATING_EXTRUDER_CZ); +TRANS(UI_TEXT_HEATING_BED_CZ); +TRANS(UI_TEXT_KILLED_CZ); +TRANS(UI_TEXT_STEPPER_DISABLED_CZ); +TRANS(UI_TEXT_EEPROM_STOREDA_CZ); +TRANS(UI_TEXT_EEPROM_STOREDB_CZ); +TRANS(UI_TEXT_EEPROM_LOADEDA_CZ); +TRANS(UI_TEXT_EEPROM_LOADEDB_CZ); +TRANS(UI_TEXT_UPLOADING_CZ); +TRANS(UI_TEXT_PAGE_BUFFER_CZ); +TRANS(UI_TEXT_PAGE_EXTRUDER_CZ); +TRANS(UI_TEXT_PAGE_EXTRUDER1_CZ); +TRANS(UI_TEXT_PAGE_EXTRUDER2_CZ); +TRANS(UI_TEXT_PAGE_EXTRUDER3_CZ); +TRANS(UI_TEXT_PAGE_BED_CZ); +TRANS(UI_TEXT_SPEED_MULTIPLY_CZ); +TRANS(UI_TEXT_FLOW_MULTIPLY_CZ); +TRANS(UI_TEXT_SHOW_MEASUREMENT_CZ); +TRANS(UI_TEXT_RESET_MEASUREMENT_CZ); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_CZ); +TRANS(UI_TEXT_ZCALIB_CZ); +TRANS(UI_TEXT_SET_P1_CZ); +TRANS(UI_TEXT_SET_P2_CZ); +TRANS(UI_TEXT_SET_P3_CZ); +TRANS(UI_TEXT_CALCULATE_LEVELING_CZ); +TRANS(UI_TEXT_LEVEL_CZ); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_CZ); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_CZ); +TRANS(UI_TEXT_SD_REMOVED_CZ); +TRANS(UI_TEXT_SD_INSERTED_CZ); +TRANS(UI_TEXT_PRINTER_READY_CZ); +TRANS(UI_TEXT_PRINTTIME_DAYS_CZ); +TRANS(UI_TEXT_PRINTTIME_HOURS_CZ); +TRANS(UI_TEXT_PRINTTIME_MINUTES_CZ); +TRANS(UI_TEXT_PRINT_TIME_CZ); +TRANS(UI_TEXT_PRINT_FILAMENT_CZ); +TRANS(UI_TEXT_PRINTED_CZ); +TRANS(UI_TEXT_POWER_CZ); +TRANS(UI_TEXT_STRING_HM_DEADTIME_CZ); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_CZ); +TRANS(UI_TEXT_STOP_PRINT_CZ); +TRANS(UI_TEXT_Z_BABYSTEPPING_CZ); +TRANS(UI_TEXT_CHANGE_FILAMENT_CZ); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_CZ); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_CZ); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_CZ); +TRANS(UI_TEXT_CLICK_DONE_CZ); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_CZ); +TRANS(UI_TEXT_SERVOPOS_CZ); +TRANS(UI_TEXT_IGNORE_M106_CZ); +TRANS(UI_TEXT_WIZ_REHEAT1_CZ); +TRANS(UI_TEXT_WIZ_REHEAT2_CZ); +TRANS(UI_TEXT_WIZ_WAITTEMP1_CZ); +TRANS(UI_TEXT_WIZ_WAITTEMP2_CZ); +TRANS(UI_TEXT_EXTRUDER_JAM_CZ); +TRANS(UI_TEXT_STANDBY_CZ); +TRANS(UI_TEXT_BED_COATING_CZ); +TRANS(UI_TEXT_BED_COATING_SET1_CZ); +TRANS(UI_TEXT_BED_COATING_SET2_CZ); +TRANS(UI_TEXT_NOCOATING_CZ); +TRANS(UI_TEXT_BUILDTAK_CZ); +TRANS(UI_TEXT_KAPTON_CZ); +TRANS(UI_TEXT_BLUETAPE_CZ); +TRANS(UI_TEXT_PETTAPE_CZ); +TRANS(UI_TEXT_GLUESTICK_CZ); +TRANS(UI_TEXT_CUSTOM_CZ); +TRANS(UI_TEXT_COATING_CUSTOM_CZ); +TRANS(UI_TEXT_LANGUAGE_CZ); +TRANS(UI_TEXT_MAINPAGE6_1_CZ); +TRANS(UI_TEXT_MAINPAGE6_2_CZ); +TRANS(UI_TEXT_MAINPAGE6_3_CZ); +TRANS(UI_TEXT_MAINPAGE6_4_CZ); +TRANS(UI_TEXT_MAINPAGE6_5_CZ); +TRANS(UI_TEXT_MAINPAGE6_6_CZ); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_CZ); +TRANS(UI_TEXT_MAINPAGE_BED_CZ); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_CZ); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_CZ); +TRANS(UI_TEXT_MAINPAGE_XY_CZ); +TRANS(UI_TEXT_PRINT_TIME_VALUE_CZ); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_CZ); +TRANS(UI_TEXT_METER_PRINTED_CZ); +TRANS(UI_TEXT_STATUS_CZ); +TRANS(UI_TEXT_EMPTY_CZ); +TRANS(UI_TEXT_TEMP_SET_CZ); +TRANS(UI_TEXT_CURRENT_TEMP_CZ); +TRANS(UI_TEXT_COATING_THICKNESS_CZ); +TRANS(UI_TEXT_EXTR3_TEMP_CZ); +TRANS(UI_TEXT_EXTR4_TEMP_CZ); +TRANS(UI_TEXT_EXTR5_TEMP_CZ); +TRANS(UI_TEXT_EXTR3_OFF_CZ); +TRANS(UI_TEXT_EXTR4_OFF_CZ); +TRANS(UI_TEXT_EXTR5_OFF_CZ); +TRANS(UI_TEXT_EXTR3_SELECT_CZ); +TRANS(UI_TEXT_EXTR4_SELECT_CZ); +TRANS(UI_TEXT_EXTR5_SELECT_CZ); +TRANS(UI_TEXT_DITTO_0_CZ); +TRANS(UI_TEXT_DITTO_1_CZ); +TRANS(UI_TEXT_DITTO_2_CZ); +TRANS(UI_TEXT_DITTO_3_CZ); +TRANS(UI_TEXT_ZPROBE_HEIGHT_CZ); +TRANS(UI_TEXT_OFFSETS_CZ); +TRANS(UI_TEXT_X_OFFSET_CZ); +TRANS(UI_TEXT_Y_OFFSET_CZ); +TRANS(UI_TEXT_Z_OFFSET_CZ); + +PGM_P const translations_cz[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_CZ, + FUI_TEXT_OFF_CZ, + FUI_TEXT_NA_CZ, + FUI_TEXT_YES_CZ, + FUI_TEXT_NO_CZ, + FUI_TEXT_PRINT_POS_CZ, + FUI_TEXT_PRINTING_CZ, + FUI_TEXT_IDLE_CZ, + FUI_TEXT_NOSDCARD_CZ, + FUI_TEXT_ERROR_CZ, + FUI_TEXT_BACK_CZ, + FUI_TEXT_QUICK_SETTINGS_CZ, + FUI_TEXT_ERRORMSG_CZ, + FUI_TEXT_CONFIGURATION_CZ, + FUI_TEXT_POSITION_CZ, + FUI_TEXT_EXTRUDER_CZ, + FUI_TEXT_SD_CARD_CZ, + FUI_TEXT_DEBUGGING_CZ, + FUI_TEXT_HOME_DELTA_CZ, + FUI_TEXT_HOME_ALL_CZ, + FUI_TEXT_HOME_X_CZ, + FUI_TEXT_HOME_Y_CZ, + FUI_TEXT_HOME_Z_CZ, + FUI_TEXT_PREHEAT_PLA_CZ, + FUI_TEXT_PREHEAT_ABS_CZ, + FUI_TEXT_LIGHTS_ONOFF_CZ, + FUI_TEXT_COOLDOWN_CZ, + FUI_TEXT_SET_TO_ORIGIN_CZ, + FUI_TEXT_DISABLE_STEPPER_CZ, + FUI_TEXT_X_POSITION_CZ, + FUI_TEXT_X_POS_FAST_CZ, + FUI_TEXT_Y_POSITION_CZ, + FUI_TEXT_Y_POS_FAST_CZ, + FUI_TEXT_Z_POSITION_CZ, + FUI_TEXT_Z_POS_FAST_CZ, + FUI_TEXT_E_POSITION_CZ, + FUI_TEXT_BED_TEMP_CZ, + FUI_TEXT_EXTR0_TEMP_CZ, + FUI_TEXT_EXTR1_TEMP_CZ, + FUI_TEXT_EXTR2_TEMP_CZ, + FUI_TEXT_EXTR0_OFF_CZ, + FUI_TEXT_EXTR1_OFF_CZ, + FUI_TEXT_EXTR2_OFF_CZ, + FUI_TEXT_EXTR0_SELECT_CZ, + FUI_TEXT_EXTR1_SELECT_CZ, + FUI_TEXT_EXTR2_SELECT_CZ, + FUI_TEXT_EXTR_ORIGIN_CZ, + FUI_TEXT_PRINT_X_CZ, + FUI_TEXT_PRINT_Y_CZ, + FUI_TEXT_PRINT_Z_CZ, + FUI_TEXT_PRINT_Z_DELTA_CZ, + FUI_TEXT_MOVE_X_CZ, + FUI_TEXT_MOVE_Y_CZ, + FUI_TEXT_MOVE_Z_CZ, + FUI_TEXT_MOVE_Z_DELTA_CZ, + FUI_TEXT_JERK_CZ, + FUI_TEXT_ZJERK_CZ, + FUI_TEXT_ACCELERATION_CZ, + FUI_TEXT_STORE_TO_EEPROM_CZ, + FUI_TEXT_LOAD_EEPROM_CZ, + FUI_TEXT_DBG_ECHO_CZ, + FUI_TEXT_DBG_INFO_CZ, + FUI_TEXT_DBG_ERROR_CZ, + FUI_TEXT_DBG_DRYRUN_CZ, + FUI_TEXT_OPS_OFF_CZ, + FUI_TEXT_OPS_CLASSIC_CZ, + FUI_TEXT_OPS_FAST_CZ, + FUI_TEXT_OPS_RETRACT_CZ, + FUI_TEXT_OPS_BACKSLASH_CZ, + FUI_TEXT_OPS_MINDIST_CZ, + FUI_TEXT_OPS_MOVE_AFTER_CZ, + FUI_TEXT_ANTI_OOZE_CZ, + FUI_TEXT_PRINT_FILE_CZ, + FUI_TEXT_PAUSE_PRINT_CZ, + FUI_TEXT_CONTINUE_PRINT_CZ, + FUI_TEXT_UNMOUNT_CARD_CZ, + FUI_TEXT_MOUNT_CARD_CZ, + FUI_TEXT_DELETE_FILE_CZ, + FUI_TEXT_FEEDRATE_CZ, + FUI_TEXT_FEED_MAX_X_CZ, + FUI_TEXT_FEED_MAX_Y_CZ, + FUI_TEXT_FEED_MAX_Z_CZ, + FUI_TEXT_FEED_MAX_Z_DELTA_CZ, + FUI_TEXT_FEED_HOME_X_CZ, + FUI_TEXT_FEED_HOME_Y_CZ, + FUI_TEXT_FEED_HOME_Z_CZ, + FUI_TEXT_FEED_HOME_Z_DELTA_CZ, + FUI_TEXT_ACTION_XPOSITION4A_CZ, + FUI_TEXT_ACTION_XPOSITION4B_CZ, + FUI_TEXT_ACTION_XPOSITION4C_CZ, + FUI_TEXT_ACTION_XPOSITION4D_CZ, + FUI_TEXT_ACTION_YPOSITION4A_CZ, + FUI_TEXT_ACTION_YPOSITION4B_CZ, + FUI_TEXT_ACTION_YPOSITION4C_CZ, + FUI_TEXT_ACTION_YPOSITION4D_CZ, + FUI_TEXT_ACTION_ZPOSITION4A_CZ, + FUI_TEXT_ACTION_ZPOSITION4B_CZ, + FUI_TEXT_ACTION_ZPOSITION4C_CZ, + FUI_TEXT_ACTION_ZPOSITION4D_CZ, + FUI_TEXT_ACTION_XPOSITION_FAST4A_CZ, + FUI_TEXT_ACTION_XPOSITION_FAST4B_CZ, + FUI_TEXT_ACTION_XPOSITION_FAST4C_CZ, + FUI_TEXT_ACTION_XPOSITION_FAST4D_CZ, + FUI_TEXT_ACTION_YPOSITION_FAST4A_CZ, + FUI_TEXT_ACTION_YPOSITION_FAST4B_CZ, + FUI_TEXT_ACTION_YPOSITION_FAST4C_CZ, + FUI_TEXT_ACTION_YPOSITION_FAST4D_CZ, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_CZ, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_CZ, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_CZ, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_CZ, + FUI_TEXT_ACTION_EPOSITION_FAST2A_CZ, + FUI_TEXT_ACTION_EPOSITION_FAST2B_CZ, + FUI_TEXT_ACTION_XPOSITION2A_CZ, + FUI_TEXT_ACTION_XPOSITION2B_CZ, + FUI_TEXT_ACTION_YPOSITION2A_CZ, + FUI_TEXT_ACTION_YPOSITION2B_CZ, + FUI_TEXT_ACTION_ZPOSITION2A_CZ, + FUI_TEXT_ACTION_ZPOSITION2B_CZ, + FUI_TEXT_ACTION_XPOSITION_FAST2A_CZ, + FUI_TEXT_ACTION_XPOSITION_FAST2B_CZ, + FUI_TEXT_ACTION_YPOSITION_FAST2A_CZ, + FUI_TEXT_ACTION_YPOSITION_FAST2B_CZ, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_CZ, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_CZ, + FUI_TEXT_FANSPEED_CZ, + FUI_TEXT_ACTION_FANSPEED_CZ, + FUI_TEXT_FAN_OFF_CZ, + FUI_TEXT_FAN_25_CZ, + FUI_TEXT_FAN_50_CZ, + FUI_TEXT_FAN_75_CZ, + FUI_TEXT_FAN_FULL_CZ, + FUI_TEXT_STEPPER_INACTIVE_CZ, + FUI_TEXT_STEPPER_INACTIVE2A_CZ, + FUI_TEXT_STEPPER_INACTIVE2B_CZ, + FUI_TEXT_POWER_INACTIVE_CZ, + FUI_TEXT_POWER_INACTIVE2A_CZ, + FUI_TEXT_POWER_INACTIVE2B_CZ, + FUI_TEXT_GENERAL_CZ, + FUI_TEXT_BAUDRATE_CZ, + FUI_TEXT_EXTR_STEPS_CZ, + FUI_TEXT_EXTR_START_FEED_CZ, + FUI_TEXT_EXTR_MAX_FEED_CZ, + FUI_TEXT_EXTR_ACCEL_CZ, + FUI_TEXT_EXTR_WATCH_CZ, + FUI_TEXT_EXTR_ADVANCE_L_CZ, + FUI_TEXT_EXTR_ADVANCE_K_CZ, + FUI_TEXT_EXTR_MANAGER_CZ, + FUI_TEXT_EXTR_PGAIN_CZ, + FUI_TEXT_EXTR_DEADTIME_CZ, + FUI_TEXT_EXTR_DMAX_DT_CZ, + FUI_TEXT_EXTR_IGAIN_CZ, + FUI_TEXT_EXTR_DGAIN_CZ, + FUI_TEXT_EXTR_DMIN_CZ, + FUI_TEXT_EXTR_DMAX_CZ, + FUI_TEXT_EXTR_PMAX_CZ, + FUI_TEXT_EXTR_XOFF_CZ, + FUI_TEXT_EXTR_YOFF_CZ, + FUI_TEXT_STRING_HM_BANGBANG_CZ, + FUI_TEXT_STRING_HM_PID_CZ, + FUI_TEXT_STRING_ACTION_CZ, + FUI_TEXT_HEATING_EXTRUDER_CZ, + FUI_TEXT_HEATING_BED_CZ, + FUI_TEXT_KILLED_CZ, + FUI_TEXT_STEPPER_DISABLED_CZ, + FUI_TEXT_EEPROM_STOREDA_CZ, + FUI_TEXT_EEPROM_STOREDB_CZ, + FUI_TEXT_EEPROM_LOADEDA_CZ, + FUI_TEXT_EEPROM_LOADEDB_CZ, + FUI_TEXT_UPLOADING_CZ, + FUI_TEXT_PAGE_BUFFER_CZ, + FUI_TEXT_PAGE_EXTRUDER_CZ, + FUI_TEXT_PAGE_EXTRUDER1_CZ, + FUI_TEXT_PAGE_EXTRUDER2_CZ, + FUI_TEXT_PAGE_EXTRUDER3_CZ, + FUI_TEXT_PAGE_BED_CZ, + FUI_TEXT_SPEED_MULTIPLY_CZ, + FUI_TEXT_FLOW_MULTIPLY_CZ, + FUI_TEXT_SHOW_MEASUREMENT_CZ, + FUI_TEXT_RESET_MEASUREMENT_CZ, + FUI_TEXT_SET_MEASURED_ORIGIN_CZ, + FUI_TEXT_ZCALIB_CZ, + FUI_TEXT_SET_P1_CZ, + FUI_TEXT_SET_P2_CZ, + FUI_TEXT_SET_P3_CZ, + FUI_TEXT_CALCULATE_LEVELING_CZ, + FUI_TEXT_LEVEL_CZ, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_CZ, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_CZ, + FUI_TEXT_SD_REMOVED_CZ, + FUI_TEXT_SD_INSERTED_CZ, + FUI_TEXT_PRINTER_READY_CZ, + FUI_TEXT_PRINTTIME_DAYS_CZ, + FUI_TEXT_PRINTTIME_HOURS_CZ, + FUI_TEXT_PRINTTIME_MINUTES_CZ, + FUI_TEXT_PRINT_TIME_CZ, + FUI_TEXT_PRINT_FILAMENT_CZ, + FUI_TEXT_PRINTED_CZ, + FUI_TEXT_POWER_CZ, + FUI_TEXT_STRING_HM_DEADTIME_CZ, + FUI_TEXT_STRING_HM_SLOWBANG_CZ, + FUI_TEXT_STOP_PRINT_CZ, + FUI_TEXT_Z_BABYSTEPPING_CZ, + FUI_TEXT_CHANGE_FILAMENT_CZ, + FUI_TEXT_WIZ_CH_FILAMENT1_CZ, + FUI_TEXT_WIZ_CH_FILAMENT2_CZ, + FUI_TEXT_WIZ_CH_FILAMENT3_CZ, + FUI_TEXT_CLICK_DONE_CZ, + FUI_TEXT_AUTOLEVEL_ONOFF_CZ, + FUI_TEXT_SERVOPOS_CZ, + FUI_TEXT_IGNORE_M106_CZ, + FUI_TEXT_WIZ_REHEAT1_CZ, + FUI_TEXT_WIZ_REHEAT2_CZ, + FUI_TEXT_WIZ_WAITTEMP1_CZ, + FUI_TEXT_WIZ_WAITTEMP2_CZ, + FUI_TEXT_EXTRUDER_JAM_CZ, + FUI_TEXT_STANDBY_CZ, + FUI_TEXT_BED_COATING_CZ, + FUI_TEXT_BED_COATING_SET1_CZ, + FUI_TEXT_BED_COATING_SET2_CZ, + FUI_TEXT_NOCOATING_CZ, + FUI_TEXT_BUILDTAK_CZ, + FUI_TEXT_KAPTON_CZ, + FUI_TEXT_BLUETAPE_CZ, + FUI_TEXT_PETTAPE_CZ, + FUI_TEXT_GLUESTICK_CZ, + FUI_TEXT_CUSTOM_CZ, + FUI_TEXT_COATING_CUSTOM_CZ, + FUI_TEXT_LANGUAGE_CZ, + FUI_TEXT_MAINPAGE6_1_CZ, + FUI_TEXT_MAINPAGE6_2_CZ, + FUI_TEXT_MAINPAGE6_3_CZ, + FUI_TEXT_MAINPAGE6_4_CZ, + FUI_TEXT_MAINPAGE6_5_CZ, + FUI_TEXT_MAINPAGE6_6_CZ, + FUI_TEXT_MAINPAGE_TEMP_BED_CZ, + FUI_TEXT_MAINPAGE_BED_CZ, + FUI_TEXT_MAINPAGE_Z_BUF_CZ, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_CZ, + FUI_TEXT_MAINPAGE_XY_CZ, + FUI_TEXT_PRINT_TIME_VALUE_CZ, + FUI_TEXT_PRINT_FILAMENT_VALUE_CZ, + FUI_TEXT_METER_PRINTED_CZ, + FUI_TEXT_STATUS_CZ, + FUI_TEXT_EMPTY_CZ, + FUI_TEXT_TEMP_SET_CZ, + FUI_TEXT_CURRENT_TEMP_CZ, + FUI_TEXT_COATING_THICKNESS_CZ, + FUI_TEXT_EXTR3_TEMP_CZ, + FUI_TEXT_EXTR4_TEMP_CZ, + FUI_TEXT_EXTR5_TEMP_CZ, + FUI_TEXT_EXTR3_OFF_CZ, + FUI_TEXT_EXTR4_OFF_CZ, + FUI_TEXT_EXTR5_OFF_CZ, + FUI_TEXT_EXTR3_SELECT_CZ, + FUI_TEXT_EXTR4_SELECT_CZ, + FUI_TEXT_EXTR5_SELECT_CZ, + FUI_TEXT_DITTO_0_CZ, + FUI_TEXT_DITTO_1_CZ, + FUI_TEXT_DITTO_2_CZ, + FUI_TEXT_DITTO_3_CZ, + FUI_TEXT_ZPROBE_HEIGHT_CZ, + FUI_TEXT_OFFSETS_CZ, + FUI_TEXT_X_OFFSET_CZ, + FUI_TEXT_Y_OFFSET_CZ, + FUI_TEXT_Z_OFFSET_CZ +}; +#define LANG_CZ_TABLE translations_cz +#else +#define LANG_CZ_TABLE NULL +#endif // LANGUAGE_CZ_ACTIVE + + +#if LANGUAGE_PL_ACTIVE +TRANS(UI_TEXT_ON_PL); +TRANS(UI_TEXT_OFF_PL); +TRANS(UI_TEXT_NA_PL); +TRANS(UI_TEXT_YES_PL); +TRANS(UI_TEXT_NO_PL); +TRANS(UI_TEXT_PRINT_POS_PL); +TRANS(UI_TEXT_PRINTING_PL); +TRANS(UI_TEXT_IDLE_PL); +TRANS(UI_TEXT_NOSDCARD_PL); +TRANS(UI_TEXT_ERROR_PL); +TRANS(UI_TEXT_BACK_PL); +TRANS(UI_TEXT_QUICK_SETTINGS_PL); +TRANS(UI_TEXT_ERRORMSG_PL); +TRANS(UI_TEXT_CONFIGURATION_PL); +TRANS(UI_TEXT_POSITION_PL); +TRANS(UI_TEXT_EXTRUDER_PL); +TRANS(UI_TEXT_SD_CARD_PL); +TRANS(UI_TEXT_DEBUGGING_PL); +TRANS(UI_TEXT_HOME_DELTA_PL); +TRANS(UI_TEXT_HOME_ALL_PL); +TRANS(UI_TEXT_HOME_X_PL); +TRANS(UI_TEXT_HOME_Y_PL); +TRANS(UI_TEXT_HOME_Z_PL); +TRANS(UI_TEXT_PREHEAT_PLA_PL); +TRANS(UI_TEXT_PREHEAT_ABS_PL); +TRANS(UI_TEXT_LIGHTS_ONOFF_PL); +TRANS(UI_TEXT_COOLDOWN_PL); +TRANS(UI_TEXT_SET_TO_ORIGIN_PL); +TRANS(UI_TEXT_DISABLE_STEPPER_PL); +TRANS(UI_TEXT_X_POSITION_PL); +TRANS(UI_TEXT_X_POS_FAST_PL); +TRANS(UI_TEXT_Y_POSITION_PL); +TRANS(UI_TEXT_Y_POS_FAST_PL); +TRANS(UI_TEXT_Z_POSITION_PL); +TRANS(UI_TEXT_Z_POS_FAST_PL); +TRANS(UI_TEXT_E_POSITION_PL); +TRANS(UI_TEXT_BED_TEMP_PL); +TRANS(UI_TEXT_EXTR0_TEMP_PL); +TRANS(UI_TEXT_EXTR1_TEMP_PL); +TRANS(UI_TEXT_EXTR2_TEMP_PL); +TRANS(UI_TEXT_EXTR0_OFF_PL); +TRANS(UI_TEXT_EXTR1_OFF_PL); +TRANS(UI_TEXT_EXTR2_OFF_PL); +TRANS(UI_TEXT_EXTR0_SELECT_PL); +TRANS(UI_TEXT_EXTR1_SELECT_PL); +TRANS(UI_TEXT_EXTR2_SELECT_PL); +TRANS(UI_TEXT_EXTR_ORIGIN_PL); +TRANS(UI_TEXT_PRINT_X_PL); +TRANS(UI_TEXT_PRINT_Y_PL); +TRANS(UI_TEXT_PRINT_Z_PL); +TRANS(UI_TEXT_PRINT_Z_DELTA_PL); +TRANS(UI_TEXT_MOVE_X_PL); +TRANS(UI_TEXT_MOVE_Y_PL); +TRANS(UI_TEXT_MOVE_Z_PL); +TRANS(UI_TEXT_MOVE_Z_DELTA_PL); +TRANS(UI_TEXT_JERK_PL); +TRANS(UI_TEXT_ZJERK_PL); +TRANS(UI_TEXT_ACCELERATION_PL); +TRANS(UI_TEXT_STORE_TO_EEPROM_PL); +TRANS(UI_TEXT_LOAD_EEPROM_PL); +TRANS(UI_TEXT_DBG_ECHO_PL); +TRANS(UI_TEXT_DBG_INFO_PL); +TRANS(UI_TEXT_DBG_ERROR_PL); +TRANS(UI_TEXT_DBG_DRYRUN_PL); +TRANS(UI_TEXT_OPS_OFF_PL); +TRANS(UI_TEXT_OPS_CLASSIC_PL); +TRANS(UI_TEXT_OPS_FAST_PL); +TRANS(UI_TEXT_OPS_RETRACT_PL); +TRANS(UI_TEXT_OPS_BACKSLASH_PL); +TRANS(UI_TEXT_OPS_MINDIST_PL); +TRANS(UI_TEXT_OPS_MOVE_AFTER_PL); +TRANS(UI_TEXT_ANTI_OOZE_PL); +TRANS(UI_TEXT_PRINT_FILE_PL); +TRANS(UI_TEXT_PAUSE_PRINT_PL); +TRANS(UI_TEXT_CONTINUE_PRINT_PL); +TRANS(UI_TEXT_UNMOUNT_CARD_PL); +TRANS(UI_TEXT_MOUNT_CARD_PL); +TRANS(UI_TEXT_DELETE_FILE_PL); +TRANS(UI_TEXT_FEEDRATE_PL); +TRANS(UI_TEXT_FEED_MAX_X_PL); +TRANS(UI_TEXT_FEED_MAX_Y_PL); +TRANS(UI_TEXT_FEED_MAX_Z_PL); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_PL); +TRANS(UI_TEXT_FEED_HOME_X_PL); +TRANS(UI_TEXT_FEED_HOME_Y_PL); +TRANS(UI_TEXT_FEED_HOME_Z_PL); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_PL); +TRANS(UI_TEXT_ACTION_XPOSITION4A_PL); +TRANS(UI_TEXT_ACTION_XPOSITION4B_PL); +TRANS(UI_TEXT_ACTION_XPOSITION4C_PL); +TRANS(UI_TEXT_ACTION_XPOSITION4D_PL); +TRANS(UI_TEXT_ACTION_YPOSITION4A_PL); +TRANS(UI_TEXT_ACTION_YPOSITION4B_PL); +TRANS(UI_TEXT_ACTION_YPOSITION4C_PL); +TRANS(UI_TEXT_ACTION_YPOSITION4D_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_PL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_PL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_PL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_PL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_PL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_PL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_PL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_PL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_PL); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_PL); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_PL); +TRANS(UI_TEXT_ACTION_XPOSITION2A_PL); +TRANS(UI_TEXT_ACTION_XPOSITION2B_PL); +TRANS(UI_TEXT_ACTION_YPOSITION2A_PL); +TRANS(UI_TEXT_ACTION_YPOSITION2B_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_PL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_PL); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_PL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_PL); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_PL); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_PL); +TRANS(UI_TEXT_FANSPEED_PL); +TRANS(UI_TEXT_ACTION_FANSPEED_PL); +TRANS(UI_TEXT_FAN_OFF_PL); +TRANS(UI_TEXT_FAN_25_PL); +TRANS(UI_TEXT_FAN_50_PL); +TRANS(UI_TEXT_FAN_75_PL); +TRANS(UI_TEXT_FAN_FULL_PL); +TRANS(UI_TEXT_STEPPER_INACTIVE_PL); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_PL); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_PL); +TRANS(UI_TEXT_POWER_INACTIVE_PL); +TRANS(UI_TEXT_POWER_INACTIVE2A_PL); +TRANS(UI_TEXT_POWER_INACTIVE2B_PL); +TRANS(UI_TEXT_GENERAL_PL); +TRANS(UI_TEXT_BAUDRATE_PL); +TRANS(UI_TEXT_EXTR_STEPS_PL); +TRANS(UI_TEXT_EXTR_START_FEED_PL); +TRANS(UI_TEXT_EXTR_MAX_FEED_PL); +TRANS(UI_TEXT_EXTR_ACCEL_PL); +TRANS(UI_TEXT_EXTR_WATCH_PL); +TRANS(UI_TEXT_EXTR_ADVANCE_L_PL); +TRANS(UI_TEXT_EXTR_ADVANCE_K_PL); +TRANS(UI_TEXT_EXTR_MANAGER_PL); +TRANS(UI_TEXT_EXTR_PGAIN_PL); +TRANS(UI_TEXT_EXTR_DEADTIME_PL); +TRANS(UI_TEXT_EXTR_DMAX_DT_PL); +TRANS(UI_TEXT_EXTR_IGAIN_PL); +TRANS(UI_TEXT_EXTR_DGAIN_PL); +TRANS(UI_TEXT_EXTR_DMIN_PL); +TRANS(UI_TEXT_EXTR_DMAX_PL); +TRANS(UI_TEXT_EXTR_PMAX_PL); +TRANS(UI_TEXT_EXTR_XOFF_PL); +TRANS(UI_TEXT_EXTR_YOFF_PL); +TRANS(UI_TEXT_STRING_HM_BANGBANG_PL); +TRANS(UI_TEXT_STRING_HM_PID_PL); +TRANS(UI_TEXT_STRING_ACTION_PL); +TRANS(UI_TEXT_HEATING_EXTRUDER_PL); +TRANS(UI_TEXT_HEATING_BED_PL); +TRANS(UI_TEXT_KILLED_PL); +TRANS(UI_TEXT_STEPPER_DISABLED_PL); +TRANS(UI_TEXT_EEPROM_STOREDA_PL); +TRANS(UI_TEXT_EEPROM_STOREDB_PL); +TRANS(UI_TEXT_EEPROM_LOADEDA_PL); +TRANS(UI_TEXT_EEPROM_LOADEDB_PL); +TRANS(UI_TEXT_UPLOADING_PL); +TRANS(UI_TEXT_PAGE_BUFFER_PL); +TRANS(UI_TEXT_PAGE_EXTRUDER_PL); +TRANS(UI_TEXT_PAGE_EXTRUDER1_PL); +TRANS(UI_TEXT_PAGE_EXTRUDER2_PL); +TRANS(UI_TEXT_PAGE_EXTRUDER3_PL); +TRANS(UI_TEXT_PAGE_BED_PL); +TRANS(UI_TEXT_SPEED_MULTIPLY_PL); +TRANS(UI_TEXT_FLOW_MULTIPLY_PL); +TRANS(UI_TEXT_SHOW_MEASUREMENT_PL); +TRANS(UI_TEXT_RESET_MEASUREMENT_PL); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_PL); +TRANS(UI_TEXT_ZCALIB_PL); +TRANS(UI_TEXT_SET_P1_PL); +TRANS(UI_TEXT_SET_P2_PL); +TRANS(UI_TEXT_SET_P3_PL); +TRANS(UI_TEXT_CALCULATE_LEVELING_PL); +TRANS(UI_TEXT_LEVEL_PL); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_PL); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_PL); +TRANS(UI_TEXT_SD_REMOVED_PL); +TRANS(UI_TEXT_SD_INSERTED_PL); +TRANS(UI_TEXT_PRINTER_READY_PL); +TRANS(UI_TEXT_PRINTTIME_DAYS_PL); +TRANS(UI_TEXT_PRINTTIME_HOURS_PL); +TRANS(UI_TEXT_PRINTTIME_MINUTES_PL); +TRANS(UI_TEXT_PRINT_TIME_PL); +TRANS(UI_TEXT_PRINT_FILAMENT_PL); +TRANS(UI_TEXT_PRINTED_PL); +TRANS(UI_TEXT_POWER_PL); +TRANS(UI_TEXT_STRING_HM_DEADTIME_PL); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_PL); +TRANS(UI_TEXT_STOP_PRINT_PL); +TRANS(UI_TEXT_Z_BABYSTEPPING_PL); +TRANS(UI_TEXT_CHANGE_FILAMENT_PL); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_PL); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_PL); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_PL); +TRANS(UI_TEXT_CLICK_DONE_PL); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_PL); +TRANS(UI_TEXT_SERVOPOS_PL); +TRANS(UI_TEXT_IGNORE_M106_PL); +TRANS(UI_TEXT_WIZ_REHEAT1_PL); +TRANS(UI_TEXT_WIZ_REHEAT2_PL); +TRANS(UI_TEXT_WIZ_WAITTEMP1_PL); +TRANS(UI_TEXT_WIZ_WAITTEMP2_PL); +TRANS(UI_TEXT_EXTRUDER_JAM_PL); +TRANS(UI_TEXT_STANDBY_PL); +TRANS(UI_TEXT_BED_COATING_PL); +TRANS(UI_TEXT_BED_COATING_SET1_PL); +TRANS(UI_TEXT_BED_COATING_SET2_PL); +TRANS(UI_TEXT_NOCOATING_PL); +TRANS(UI_TEXT_BUILDTAK_PL); +TRANS(UI_TEXT_KAPTON_PL); +TRANS(UI_TEXT_BLUETAPE_PL); +TRANS(UI_TEXT_PETTAPE_PL); +TRANS(UI_TEXT_GLUESTICK_PL); +TRANS(UI_TEXT_CUSTOM_PL); +TRANS(UI_TEXT_COATING_CUSTOM_PL); +TRANS(UI_TEXT_LANGUAGE_PL); +TRANS(UI_TEXT_MAINPAGE6_1_PL); +TRANS(UI_TEXT_MAINPAGE6_2_PL); +TRANS(UI_TEXT_MAINPAGE6_3_PL); +TRANS(UI_TEXT_MAINPAGE6_4_PL); +TRANS(UI_TEXT_MAINPAGE6_5_PL); +TRANS(UI_TEXT_MAINPAGE6_6_PL); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_PL); +TRANS(UI_TEXT_MAINPAGE_BED_PL); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_PL); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_PL); +TRANS(UI_TEXT_MAINPAGE_XY_PL); +TRANS(UI_TEXT_PRINT_TIME_VALUE_PL); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_PL); +TRANS(UI_TEXT_METER_PRINTED_PL); +TRANS(UI_TEXT_STATUS_PL); +TRANS(UI_TEXT_EMPTY_PL); +TRANS(UI_TEXT_TEMP_SET_PL); +TRANS(UI_TEXT_CURRENT_TEMP_PL); +TRANS(UI_TEXT_COATING_THICKNESS_PL); +TRANS(UI_TEXT_EXTR3_TEMP_PL); +TRANS(UI_TEXT_EXTR4_TEMP_PL); +TRANS(UI_TEXT_EXTR5_TEMP_PL); +TRANS(UI_TEXT_EXTR3_OFF_PL); +TRANS(UI_TEXT_EXTR4_OFF_PL); +TRANS(UI_TEXT_EXTR5_OFF_PL); +TRANS(UI_TEXT_EXTR3_SELECT_PL); +TRANS(UI_TEXT_EXTR4_SELECT_PL); +TRANS(UI_TEXT_EXTR5_SELECT_PL); +TRANS(UI_TEXT_DITTO_0_PL); +TRANS(UI_TEXT_DITTO_1_PL); +TRANS(UI_TEXT_DITTO_2_PL); +TRANS(UI_TEXT_DITTO_3_PL); +TRANS(UI_TEXT_ZPROBE_HEIGHT_PL); +TRANS(UI_TEXT_OFFSETS_PL); +TRANS(UI_TEXT_X_OFFSET_PL); +TRANS(UI_TEXT_Y_OFFSET_PL); +TRANS(UI_TEXT_Z_OFFSET_PL); + +PGM_P const translations_pl[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_PL, + FUI_TEXT_OFF_PL, + FUI_TEXT_NA_PL, + FUI_TEXT_YES_PL, + FUI_TEXT_NO_PL, + FUI_TEXT_PRINT_POS_PL, + FUI_TEXT_PRINTING_PL, + FUI_TEXT_IDLE_PL, + FUI_TEXT_NOSDCARD_PL, + FUI_TEXT_ERROR_PL, + FUI_TEXT_BACK_PL, + FUI_TEXT_QUICK_SETTINGS_PL, + FUI_TEXT_ERRORMSG_PL, + FUI_TEXT_CONFIGURATION_PL, + FUI_TEXT_POSITION_PL, + FUI_TEXT_EXTRUDER_PL, + FUI_TEXT_SD_CARD_PL, + FUI_TEXT_DEBUGGING_PL, + FUI_TEXT_HOME_DELTA_PL, + FUI_TEXT_HOME_ALL_PL, + FUI_TEXT_HOME_X_PL, + FUI_TEXT_HOME_Y_PL, + FUI_TEXT_HOME_Z_PL, + FUI_TEXT_PREHEAT_PLA_PL, + FUI_TEXT_PREHEAT_ABS_PL, + FUI_TEXT_LIGHTS_ONOFF_PL, + FUI_TEXT_COOLDOWN_PL, + FUI_TEXT_SET_TO_ORIGIN_PL, + FUI_TEXT_DISABLE_STEPPER_PL, + FUI_TEXT_X_POSITION_PL, + FUI_TEXT_X_POS_FAST_PL, + FUI_TEXT_Y_POSITION_PL, + FUI_TEXT_Y_POS_FAST_PL, + FUI_TEXT_Z_POSITION_PL, + FUI_TEXT_Z_POS_FAST_PL, + FUI_TEXT_E_POSITION_PL, + FUI_TEXT_BED_TEMP_PL, + FUI_TEXT_EXTR0_TEMP_PL, + FUI_TEXT_EXTR1_TEMP_PL, + FUI_TEXT_EXTR2_TEMP_PL, + FUI_TEXT_EXTR0_OFF_PL, + FUI_TEXT_EXTR1_OFF_PL, + FUI_TEXT_EXTR2_OFF_PL, + FUI_TEXT_EXTR0_SELECT_PL, + FUI_TEXT_EXTR1_SELECT_PL, + FUI_TEXT_EXTR2_SELECT_PL, + FUI_TEXT_EXTR_ORIGIN_PL, + FUI_TEXT_PRINT_X_PL, + FUI_TEXT_PRINT_Y_PL, + FUI_TEXT_PRINT_Z_PL, + FUI_TEXT_PRINT_Z_DELTA_PL, + FUI_TEXT_MOVE_X_PL, + FUI_TEXT_MOVE_Y_PL, + FUI_TEXT_MOVE_Z_PL, + FUI_TEXT_MOVE_Z_DELTA_PL, + FUI_TEXT_JERK_PL, + FUI_TEXT_ZJERK_PL, + FUI_TEXT_ACCELERATION_PL, + FUI_TEXT_STORE_TO_EEPROM_PL, + FUI_TEXT_LOAD_EEPROM_PL, + FUI_TEXT_DBG_ECHO_PL, + FUI_TEXT_DBG_INFO_PL, + FUI_TEXT_DBG_ERROR_PL, + FUI_TEXT_DBG_DRYRUN_PL, + FUI_TEXT_OPS_OFF_PL, + FUI_TEXT_OPS_CLASSIC_PL, + FUI_TEXT_OPS_FAST_PL, + FUI_TEXT_OPS_RETRACT_PL, + FUI_TEXT_OPS_BACKSLASH_PL, + FUI_TEXT_OPS_MINDIST_PL, + FUI_TEXT_OPS_MOVE_AFTER_PL, + FUI_TEXT_ANTI_OOZE_PL, + FUI_TEXT_PRINT_FILE_PL, + FUI_TEXT_PAUSE_PRINT_PL, + FUI_TEXT_CONTINUE_PRINT_PL, + FUI_TEXT_UNMOUNT_CARD_PL, + FUI_TEXT_MOUNT_CARD_PL, + FUI_TEXT_DELETE_FILE_PL, + FUI_TEXT_FEEDRATE_PL, + FUI_TEXT_FEED_MAX_X_PL, + FUI_TEXT_FEED_MAX_Y_PL, + FUI_TEXT_FEED_MAX_Z_PL, + FUI_TEXT_FEED_MAX_Z_DELTA_PL, + FUI_TEXT_FEED_HOME_X_PL, + FUI_TEXT_FEED_HOME_Y_PL, + FUI_TEXT_FEED_HOME_Z_PL, + FUI_TEXT_FEED_HOME_Z_DELTA_PL, + FUI_TEXT_ACTION_XPOSITION4A_PL, + FUI_TEXT_ACTION_XPOSITION4B_PL, + FUI_TEXT_ACTION_XPOSITION4C_PL, + FUI_TEXT_ACTION_XPOSITION4D_PL, + FUI_TEXT_ACTION_YPOSITION4A_PL, + FUI_TEXT_ACTION_YPOSITION4B_PL, + FUI_TEXT_ACTION_YPOSITION4C_PL, + FUI_TEXT_ACTION_YPOSITION4D_PL, + FUI_TEXT_ACTION_ZPOSITION4A_PL, + FUI_TEXT_ACTION_ZPOSITION4B_PL, + FUI_TEXT_ACTION_ZPOSITION4C_PL, + FUI_TEXT_ACTION_ZPOSITION4D_PL, + FUI_TEXT_ACTION_XPOSITION_FAST4A_PL, + FUI_TEXT_ACTION_XPOSITION_FAST4B_PL, + FUI_TEXT_ACTION_XPOSITION_FAST4C_PL, + FUI_TEXT_ACTION_XPOSITION_FAST4D_PL, + FUI_TEXT_ACTION_YPOSITION_FAST4A_PL, + FUI_TEXT_ACTION_YPOSITION_FAST4B_PL, + FUI_TEXT_ACTION_YPOSITION_FAST4C_PL, + FUI_TEXT_ACTION_YPOSITION_FAST4D_PL, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_PL, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_PL, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_PL, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_PL, + FUI_TEXT_ACTION_EPOSITION_FAST2A_PL, + FUI_TEXT_ACTION_EPOSITION_FAST2B_PL, + FUI_TEXT_ACTION_XPOSITION2A_PL, + FUI_TEXT_ACTION_XPOSITION2B_PL, + FUI_TEXT_ACTION_YPOSITION2A_PL, + FUI_TEXT_ACTION_YPOSITION2B_PL, + FUI_TEXT_ACTION_ZPOSITION2A_PL, + FUI_TEXT_ACTION_ZPOSITION2B_PL, + FUI_TEXT_ACTION_XPOSITION_FAST2A_PL, + FUI_TEXT_ACTION_XPOSITION_FAST2B_PL, + FUI_TEXT_ACTION_YPOSITION_FAST2A_PL, + FUI_TEXT_ACTION_YPOSITION_FAST2B_PL, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_PL, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_PL, + FUI_TEXT_FANSPEED_PL, + FUI_TEXT_ACTION_FANSPEED_PL, + FUI_TEXT_FAN_OFF_PL, + FUI_TEXT_FAN_25_PL, + FUI_TEXT_FAN_50_PL, + FUI_TEXT_FAN_75_PL, + FUI_TEXT_FAN_FULL_PL, + FUI_TEXT_STEPPER_INACTIVE_PL, + FUI_TEXT_STEPPER_INACTIVE2A_PL, + FUI_TEXT_STEPPER_INACTIVE2B_PL, + FUI_TEXT_POWER_INACTIVE_PL, + FUI_TEXT_POWER_INACTIVE2A_PL, + FUI_TEXT_POWER_INACTIVE2B_PL, + FUI_TEXT_GENERAL_PL, + FUI_TEXT_BAUDRATE_PL, + FUI_TEXT_EXTR_STEPS_PL, + FUI_TEXT_EXTR_START_FEED_PL, + FUI_TEXT_EXTR_MAX_FEED_PL, + FUI_TEXT_EXTR_ACCEL_PL, + FUI_TEXT_EXTR_WATCH_PL, + FUI_TEXT_EXTR_ADVANCE_L_PL, + FUI_TEXT_EXTR_ADVANCE_K_PL, + FUI_TEXT_EXTR_MANAGER_PL, + FUI_TEXT_EXTR_PGAIN_PL, + FUI_TEXT_EXTR_DEADTIME_PL, + FUI_TEXT_EXTR_DMAX_DT_PL, + FUI_TEXT_EXTR_IGAIN_PL, + FUI_TEXT_EXTR_DGAIN_PL, + FUI_TEXT_EXTR_DMIN_PL, + FUI_TEXT_EXTR_DMAX_PL, + FUI_TEXT_EXTR_PMAX_PL, + FUI_TEXT_EXTR_XOFF_PL, + FUI_TEXT_EXTR_YOFF_PL, + FUI_TEXT_STRING_HM_BANGBANG_PL, + FUI_TEXT_STRING_HM_PID_PL, + FUI_TEXT_STRING_ACTION_PL, + FUI_TEXT_HEATING_EXTRUDER_PL, + FUI_TEXT_HEATING_BED_PL, + FUI_TEXT_KILLED_PL, + FUI_TEXT_STEPPER_DISABLED_PL, + FUI_TEXT_EEPROM_STOREDA_PL, + FUI_TEXT_EEPROM_STOREDB_PL, + FUI_TEXT_EEPROM_LOADEDA_PL, + FUI_TEXT_EEPROM_LOADEDB_PL, + FUI_TEXT_UPLOADING_PL, + FUI_TEXT_PAGE_BUFFER_PL, + FUI_TEXT_PAGE_EXTRUDER_PL, + FUI_TEXT_PAGE_EXTRUDER1_PL, + FUI_TEXT_PAGE_EXTRUDER2_PL, + FUI_TEXT_PAGE_EXTRUDER3_PL, + FUI_TEXT_PAGE_BED_PL, + FUI_TEXT_SPEED_MULTIPLY_PL, + FUI_TEXT_FLOW_MULTIPLY_PL, + FUI_TEXT_SHOW_MEASUREMENT_PL, + FUI_TEXT_RESET_MEASUREMENT_PL, + FUI_TEXT_SET_MEASURED_ORIGIN_PL, + FUI_TEXT_ZCALIB_PL, + FUI_TEXT_SET_P1_PL, + FUI_TEXT_SET_P2_PL, + FUI_TEXT_SET_P3_PL, + FUI_TEXT_CALCULATE_LEVELING_PL, + FUI_TEXT_LEVEL_PL, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_PL, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_PL, + FUI_TEXT_SD_REMOVED_PL, + FUI_TEXT_SD_INSERTED_PL, + FUI_TEXT_PRINTER_READY_PL, + FUI_TEXT_PRINTTIME_DAYS_PL, + FUI_TEXT_PRINTTIME_HOURS_PL, + FUI_TEXT_PRINTTIME_MINUTES_PL, + FUI_TEXT_PRINT_TIME_PL, + FUI_TEXT_PRINT_FILAMENT_PL, + FUI_TEXT_PRINTED_PL, + FUI_TEXT_POWER_PL, + FUI_TEXT_STRING_HM_DEADTIME_PL, + FUI_TEXT_STRING_HM_SLOWBANG_PL, + FUI_TEXT_STOP_PRINT_PL, + FUI_TEXT_Z_BABYSTEPPING_PL, + FUI_TEXT_CHANGE_FILAMENT_PL, + FUI_TEXT_WIZ_CH_FILAMENT1_PL, + FUI_TEXT_WIZ_CH_FILAMENT2_PL, + FUI_TEXT_WIZ_CH_FILAMENT3_PL, + FUI_TEXT_CLICK_DONE_PL, + FUI_TEXT_AUTOLEVEL_ONOFF_PL, + FUI_TEXT_SERVOPOS_PL, + FUI_TEXT_IGNORE_M106_PL, + FUI_TEXT_WIZ_REHEAT1_PL, + FUI_TEXT_WIZ_REHEAT2_PL, + FUI_TEXT_WIZ_WAITTEMP1_PL, + FUI_TEXT_WIZ_WAITTEMP2_PL, + FUI_TEXT_EXTRUDER_JAM_PL, + FUI_TEXT_STANDBY_PL, + FUI_TEXT_BED_COATING_PL, + FUI_TEXT_BED_COATING_SET1_PL, + FUI_TEXT_BED_COATING_SET2_PL, + FUI_TEXT_NOCOATING_PL, + FUI_TEXT_BUILDTAK_PL, + FUI_TEXT_KAPTON_PL, + FUI_TEXT_BLUETAPE_PL, + FUI_TEXT_PETTAPE_PL, + FUI_TEXT_GLUESTICK_PL, + FUI_TEXT_CUSTOM_PL, + FUI_TEXT_COATING_CUSTOM_PL, + FUI_TEXT_LANGUAGE_PL, + FUI_TEXT_MAINPAGE6_1_PL, + FUI_TEXT_MAINPAGE6_2_PL, + FUI_TEXT_MAINPAGE6_3_PL, + FUI_TEXT_MAINPAGE6_4_PL, + FUI_TEXT_MAINPAGE6_5_PL, + FUI_TEXT_MAINPAGE6_6_PL, + FUI_TEXT_MAINPAGE_TEMP_BED_PL, + FUI_TEXT_MAINPAGE_BED_PL, + FUI_TEXT_MAINPAGE_Z_BUF_PL, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_PL, + FUI_TEXT_MAINPAGE_XY_PL, + FUI_TEXT_PRINT_TIME_VALUE_PL, + FUI_TEXT_PRINT_FILAMENT_VALUE_PL, + FUI_TEXT_METER_PRINTED_PL, + FUI_TEXT_STATUS_PL, + FUI_TEXT_EMPTY_PL, + FUI_TEXT_TEMP_SET_PL, + FUI_TEXT_CURRENT_TEMP_PL, + FUI_TEXT_COATING_THICKNESS_PL, + FUI_TEXT_EXTR3_TEMP_PL, + FUI_TEXT_EXTR4_TEMP_PL, + FUI_TEXT_EXTR5_TEMP_PL, + FUI_TEXT_EXTR3_OFF_PL, + FUI_TEXT_EXTR4_OFF_PL, + FUI_TEXT_EXTR5_OFF_PL, + FUI_TEXT_EXTR3_SELECT_PL, + FUI_TEXT_EXTR4_SELECT_PL, + FUI_TEXT_EXTR5_SELECT_PL, + FUI_TEXT_DITTO_0_PL, + FUI_TEXT_DITTO_1_PL, + FUI_TEXT_DITTO_2_PL, + FUI_TEXT_DITTO_3_PL, + FUI_TEXT_ZPROBE_HEIGHT_PL, + FUI_TEXT_OFFSETS_PL, + FUI_TEXT_X_OFFSET_PL, + FUI_TEXT_Y_OFFSET_PL, + FUI_TEXT_Z_OFFSET_PL +}; +#define LANG_PL_TABLE translations_pl +#else +#define LANG_PL_TABLE NULL +#endif // LANGUAGE_PL_ACTIVE + +#if LANGUAGE_TR_ACTIVE +TRANS(UI_TEXT_ON_TR); +TRANS(UI_TEXT_OFF_TR); +TRANS(UI_TEXT_NA_TR); +TRANS(UI_TEXT_YES_TR); +TRANS(UI_TEXT_NO_TR); +TRANS(UI_TEXT_PRINT_POS_TR); +TRANS(UI_TEXT_PRINTING_TR); +TRANS(UI_TEXT_IDLE_TR); +TRANS(UI_TEXT_NOSDCARD_TR); +TRANS(UI_TEXT_ERROR_TR); +TRANS(UI_TEXT_BACK_TR); +TRANS(UI_TEXT_QUICK_SETTINGS_TR); +TRANS(UI_TEXT_ERRORMSG_TR); +TRANS(UI_TEXT_CONFIGURATION_TR); +TRANS(UI_TEXT_POSITION_TR); +TRANS(UI_TEXT_EXTRUDER_TR); +TRANS(UI_TEXT_SD_CARD_TR); +TRANS(UI_TEXT_DEBUGGING_TR); +TRANS(UI_TEXT_HOME_DELTA_TR); +TRANS(UI_TEXT_HOME_ALL_TR); +TRANS(UI_TEXT_HOME_X_TR); +TRANS(UI_TEXT_HOME_Y_TR); +TRANS(UI_TEXT_HOME_Z_TR); +TRANS(UI_TEXT_PREHEAT_PLA_TR); +TRANS(UI_TEXT_PREHEAT_ABS_TR); +TRANS(UI_TEXT_LIGHTS_ONOFF_TR); +TRANS(UI_TEXT_COOLDOWN_TR); +TRANS(UI_TEXT_SET_TO_ORIGIN_TR); +TRANS(UI_TEXT_DISABLE_STEPPER_TR); +TRANS(UI_TEXT_X_POSITION_TR); +TRANS(UI_TEXT_X_POS_FAST_TR); +TRANS(UI_TEXT_Y_POSITION_TR); +TRANS(UI_TEXT_Y_POS_FAST_TR); +TRANS(UI_TEXT_Z_POSITION_TR); +TRANS(UI_TEXT_Z_POS_FAST_TR); +TRANS(UI_TEXT_E_POSITION_TR); +TRANS(UI_TEXT_BED_TEMP_TR); +TRANS(UI_TEXT_EXTR0_TEMP_TR); +TRANS(UI_TEXT_EXTR1_TEMP_TR); +TRANS(UI_TEXT_EXTR2_TEMP_TR); +TRANS(UI_TEXT_EXTR0_OFF_TR); +TRANS(UI_TEXT_EXTR1_OFF_TR); +TRANS(UI_TEXT_EXTR2_OFF_TR); +TRANS(UI_TEXT_EXTR0_SELECT_TR); +TRANS(UI_TEXT_EXTR1_SELECT_TR); +TRANS(UI_TEXT_EXTR2_SELECT_TR); +TRANS(UI_TEXT_EXTR_ORIGIN_TR); +TRANS(UI_TEXT_PRINT_X_TR); +TRANS(UI_TEXT_PRINT_Y_TR); +TRANS(UI_TEXT_PRINT_Z_TR); +TRANS(UI_TEXT_PRINT_Z_DELTA_TR); +TRANS(UI_TEXT_MOVE_X_TR); +TRANS(UI_TEXT_MOVE_Y_TR); +TRANS(UI_TEXT_MOVE_Z_TR); +TRANS(UI_TEXT_MOVE_Z_DELTA_TR); +TRANS(UI_TEXT_JERK_TR); +TRANS(UI_TEXT_ZJERK_TR); +TRANS(UI_TEXT_ACCELERATION_TR); +TRANS(UI_TEXT_STORE_TO_EEPROM_TR); +TRANS(UI_TEXT_LOAD_EEPROM_TR); +TRANS(UI_TEXT_DBG_ECHO_TR); +TRANS(UI_TEXT_DBG_INFO_TR); +TRANS(UI_TEXT_DBG_ERROR_TR); +TRANS(UI_TEXT_DBG_DRYRUN_TR); +TRANS(UI_TEXT_OPS_OFF_TR); +TRANS(UI_TEXT_OPS_CLASSIC_TR); +TRANS(UI_TEXT_OPS_FAST_TR); +TRANS(UI_TEXT_OPS_RETRACT_TR); +TRANS(UI_TEXT_OPS_BACKSLASH_TR); +TRANS(UI_TEXT_OPS_MINDIST_TR); +TRANS(UI_TEXT_OPS_MOVE_AFTER_TR); +TRANS(UI_TEXT_ANTI_OOZE_TR); +TRANS(UI_TEXT_PRINT_FILE_TR); +TRANS(UI_TEXT_PAUSE_PRINT_TR); +TRANS(UI_TEXT_CONTINUE_PRINT_TR); +TRANS(UI_TEXT_UNMOUNT_CARD_TR); +TRANS(UI_TEXT_MOUNT_CARD_TR); +TRANS(UI_TEXT_DELETE_FILE_TR); +TRANS(UI_TEXT_FEEDRATE_TR); +TRANS(UI_TEXT_FEED_MAX_X_TR); +TRANS(UI_TEXT_FEED_MAX_Y_TR); +TRANS(UI_TEXT_FEED_MAX_Z_TR); +TRANS(UI_TEXT_FEED_MAX_Z_DELTA_TR); +TRANS(UI_TEXT_FEED_HOME_X_TR); +TRANS(UI_TEXT_FEED_HOME_Y_TR); +TRANS(UI_TEXT_FEED_HOME_Z_TR); +TRANS(UI_TEXT_FEED_HOME_Z_DELTA_TR); +TRANS(UI_TEXT_ACTION_XPOSITION4A_TR); +TRANS(UI_TEXT_ACTION_XPOSITION4B_TR); +TRANS(UI_TEXT_ACTION_XPOSITION4C_TR); +TRANS(UI_TEXT_ACTION_XPOSITION4D_TR); +TRANS(UI_TEXT_ACTION_YPOSITION4A_TR); +TRANS(UI_TEXT_ACTION_YPOSITION4B_TR); +TRANS(UI_TEXT_ACTION_YPOSITION4C_TR); +TRANS(UI_TEXT_ACTION_YPOSITION4D_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION4A_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION4B_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION4C_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION4D_TR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4A_TR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4B_TR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4C_TR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST4D_TR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4A_TR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4B_TR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4C_TR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST4D_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4A_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4B_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4C_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST4D_TR); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2A_TR); +TRANS(UI_TEXT_ACTION_EPOSITION_FAST2B_TR); +TRANS(UI_TEXT_ACTION_XPOSITION2A_TR); +TRANS(UI_TEXT_ACTION_XPOSITION2B_TR); +TRANS(UI_TEXT_ACTION_YPOSITION2A_TR); +TRANS(UI_TEXT_ACTION_YPOSITION2B_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION2A_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION2B_TR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2A_TR); +TRANS(UI_TEXT_ACTION_XPOSITION_FAST2B_TR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2A_TR); +TRANS(UI_TEXT_ACTION_YPOSITION_FAST2B_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2A_TR); +TRANS(UI_TEXT_ACTION_ZPOSITION_FAST2B_TR); +TRANS(UI_TEXT_FANSPEED_TR); +TRANS(UI_TEXT_ACTION_FANSPEED_TR); +TRANS(UI_TEXT_FAN_OFF_TR); +TRANS(UI_TEXT_FAN_25_TR); +TRANS(UI_TEXT_FAN_50_TR); +TRANS(UI_TEXT_FAN_75_TR); +TRANS(UI_TEXT_FAN_FULL_TR); +TRANS(UI_TEXT_STEPPER_INACTIVE_TR); +TRANS(UI_TEXT_STEPPER_INACTIVE2A_TR); +TRANS(UI_TEXT_STEPPER_INACTIVE2B_TR); +TRANS(UI_TEXT_POWER_INACTIVE_TR); +TRANS(UI_TEXT_POWER_INACTIVE2A_TR); +TRANS(UI_TEXT_POWER_INACTIVE2B_TR); +TRANS(UI_TEXT_GENERAL_TR); +TRANS(UI_TEXT_BAUDRATE_TR); +TRANS(UI_TEXT_EXTR_STEPS_TR); +TRANS(UI_TEXT_EXTR_START_FEED_TR); +TRANS(UI_TEXT_EXTR_MAX_FEED_TR); +TRANS(UI_TEXT_EXTR_ACCEL_TR); +TRANS(UI_TEXT_EXTR_WATCH_TR); +TRANS(UI_TEXT_EXTR_ADVANCE_L_TR); +TRANS(UI_TEXT_EXTR_ADVANCE_K_TR); +TRANS(UI_TEXT_EXTR_MANAGER_TR); +TRANS(UI_TEXT_EXTR_PGAIN_TR); +TRANS(UI_TEXT_EXTR_DEADTIME_TR); +TRANS(UI_TEXT_EXTR_DMAX_DT_TR); +TRANS(UI_TEXT_EXTR_IGAIN_TR); +TRANS(UI_TEXT_EXTR_DGAIN_TR); +TRANS(UI_TEXT_EXTR_DMIN_TR); +TRANS(UI_TEXT_EXTR_DMAX_TR); +TRANS(UI_TEXT_EXTR_PMAX_TR); +TRANS(UI_TEXT_EXTR_XOFF_TR); +TRANS(UI_TEXT_EXTR_YOFF_TR); +TRANS(UI_TEXT_STRING_HM_BANGBANG_TR); +TRANS(UI_TEXT_STRING_HM_PID_TR); +TRANS(UI_TEXT_STRING_ACTION_TR); +TRANS(UI_TEXT_HEATING_EXTRUDER_TR); +TRANS(UI_TEXT_HEATING_BED_TR); +TRANS(UI_TEXT_KILLED_TR); +TRANS(UI_TEXT_STEPPER_DISABLED_TR); +TRANS(UI_TEXT_EEPROM_STOREDA_TR); +TRANS(UI_TEXT_EEPROM_STOREDB_TR); +TRANS(UI_TEXT_EEPROM_LOADEDA_TR); +TRANS(UI_TEXT_EEPROM_LOADEDB_TR); +TRANS(UI_TEXT_UPLOADING_TR); +TRANS(UI_TEXT_PAGE_BUFFER_TR); +TRANS(UI_TEXT_PAGE_EXTRUDER_TR); +TRANS(UI_TEXT_PAGE_EXTRUDER1_TR); +TRANS(UI_TEXT_PAGE_EXTRUDER2_TR); +TRANS(UI_TEXT_PAGE_EXTRUDER3_TR); +TRANS(UI_TEXT_PAGE_BED_TR); +TRANS(UI_TEXT_SPEED_MULTIPLY_TR); +TRANS(UI_TEXT_FLOW_MULTIPLY_TR); +TRANS(UI_TEXT_SHOW_MEASUREMENT_TR); +TRANS(UI_TEXT_RESET_MEASUREMENT_TR); +TRANS(UI_TEXT_SET_MEASURED_ORIGIN_TR); +TRANS(UI_TEXT_ZCALIB_TR); +TRANS(UI_TEXT_SET_P1_TR); +TRANS(UI_TEXT_SET_P2_TR); +TRANS(UI_TEXT_SET_P3_TR); +TRANS(UI_TEXT_CALCULATE_LEVELING_TR); +TRANS(UI_TEXT_LEVEL_TR); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_TEMP_TR); +TRANS(UI_TEXT_EXTR_WAIT_RETRACT_UNITS_TR); +TRANS(UI_TEXT_SD_REMOVED_TR); +TRANS(UI_TEXT_SD_INSERTED_TR); +TRANS(UI_TEXT_PRINTER_READY_TR); +TRANS(UI_TEXT_PRINTTIME_DAYS_TR); +TRANS(UI_TEXT_PRINTTIME_HOURS_TR); +TRANS(UI_TEXT_PRINTTIME_MINUTES_TR); +TRANS(UI_TEXT_PRINT_TIME_TR); +TRANS(UI_TEXT_PRINT_FILAMENT_TR); +TRANS(UI_TEXT_PRINTED_TR); +TRANS(UI_TEXT_POWER_TR); +TRANS(UI_TEXT_STRING_HM_DEADTIME_TR); +TRANS(UI_TEXT_STRING_HM_SLOWBANG_TR); +TRANS(UI_TEXT_STOP_PRINT_TR); +TRANS(UI_TEXT_Z_BABYSTEPPING_TR); +TRANS(UI_TEXT_CHANGE_FILAMENT_TR); +TRANS(UI_TEXT_WIZ_CH_FILAMENT1_TR); +TRANS(UI_TEXT_WIZ_CH_FILAMENT2_TR); +TRANS(UI_TEXT_WIZ_CH_FILAMENT3_TR); +TRANS(UI_TEXT_CLICK_DONE_TR); +TRANS(UI_TEXT_AUTOLEVEL_ONOFF_TR); +TRANS(UI_TEXT_SERVOPOS_TR); +TRANS(UI_TEXT_IGNORE_M106_TR); +TRANS(UI_TEXT_WIZ_REHEAT1_TR); +TRANS(UI_TEXT_WIZ_REHEAT2_TR); +TRANS(UI_TEXT_WIZ_WAITTEMP1_TR); +TRANS(UI_TEXT_WIZ_WAITTEMP2_TR); +TRANS(UI_TEXT_EXTRUDER_JAM_TR); +TRANS(UI_TEXT_STANDBY_TR); +TRANS(UI_TEXT_BED_COATING_TR); +TRANS(UI_TEXT_BED_COATING_SET1_TR); +TRANS(UI_TEXT_BED_COATING_SET2_TR); +TRANS(UI_TEXT_NOCOATING_TR); +TRANS(UI_TEXT_BUILDTAK_TR); +TRANS(UI_TEXT_KAPTON_TR); +TRANS(UI_TEXT_BLUETAPE_TR); +TRANS(UI_TEXT_PETTAPE_TR); +TRANS(UI_TEXT_GLUESTICK_TR); +TRANS(UI_TEXT_CUSTOM_TR); +TRANS(UI_TEXT_COATING_CUSTOM_TR); +TRANS(UI_TEXT_LANGUAGE_TR); +TRANS(UI_TEXT_MAINPAGE6_1_TR); +TRANS(UI_TEXT_MAINPAGE6_2_TR); +TRANS(UI_TEXT_MAINPAGE6_3_TR); +TRANS(UI_TEXT_MAINPAGE6_4_TR); +TRANS(UI_TEXT_MAINPAGE6_5_TR); +TRANS(UI_TEXT_MAINPAGE6_6_TR); +TRANS(UI_TEXT_MAINPAGE_TEMP_BED_TR); +TRANS(UI_TEXT_MAINPAGE_BED_TR); +TRANS(UI_TEXT_MAINPAGE_Z_BUF_TR); +TRANS(UI_TEXT_MAINPAGE_MUL_EUSAGE_TR); +TRANS(UI_TEXT_MAINPAGE_XY_TR); +TRANS(UI_TEXT_PRINT_TIME_VALUE_TR); +TRANS(UI_TEXT_PRINT_FILAMENT_VALUE_TR); +TRANS(UI_TEXT_METER_PRINTED_TR); +TRANS(UI_TEXT_STATUS_TR); +TRANS(UI_TEXT_EMPTY_TR); +TRANS(UI_TEXT_TEMP_SET_TR); +TRANS(UI_TEXT_CURRENT_TEMP_TR); +TRANS(UI_TEXT_COATING_THICKNESS_TR); +TRANS(UI_TEXT_EXTR3_TEMP_TR); +TRANS(UI_TEXT_EXTR4_TEMP_TR); +TRANS(UI_TEXT_EXTR5_TEMP_TR); +TRANS(UI_TEXT_EXTR3_OFF_TR); +TRANS(UI_TEXT_EXTR4_OFF_TR); +TRANS(UI_TEXT_EXTR5_OFF_TR); +TRANS(UI_TEXT_EXTR3_SELECT_TR); +TRANS(UI_TEXT_EXTR4_SELECT_TR); +TRANS(UI_TEXT_EXTR5_SELECT_TR); +TRANS(UI_TEXT_DITTO_0_TR); +TRANS(UI_TEXT_DITTO_1_TR); +TRANS(UI_TEXT_DITTO_2_TR); +TRANS(UI_TEXT_DITTO_3_TR); +TRANS(UI_TEXT_ZPROBE_HEIGHT_TR); +TRANS(UI_TEXT_OFFSETS_TR); +TRANS(UI_TEXT_X_OFFSET_TR); +TRANS(UI_TEXT_Y_OFFSET_TR); +TRANS(UI_TEXT_Z_OFFSET_TR); + + +PGM_P const translations_TR[NUM_TRANSLATED_WORDS] PROGMEM = { + FUI_TEXT_ON_TR, + FUI_TEXT_OFF_TR, + FUI_TEXT_NA_TR, + FUI_TEXT_YES_TR, + FUI_TEXT_NO_TR, + FUI_TEXT_PRINT_POS_TR, + FUI_TEXT_PRINTING_TR, + FUI_TEXT_IDLE_TR, + FUI_TEXT_NOSDCARD_TR, + FUI_TEXT_ERROR_TR, + FUI_TEXT_BACK_TR, + FUI_TEXT_QUICK_SETTINGS_TR, + FUI_TEXT_ERRORMSG_TR, + FUI_TEXT_CONFIGURATION_TR, + FUI_TEXT_POSITION_TR, + FUI_TEXT_EXTRUDER_TR, + FUI_TEXT_SD_CARD_TR, + FUI_TEXT_DEBUGGING_TR, + FUI_TEXT_HOME_DELTA_TR, + FUI_TEXT_HOME_ALL_TR, + FUI_TEXT_HOME_X_TR, + FUI_TEXT_HOME_Y_TR, + FUI_TEXT_HOME_Z_TR, + FUI_TEXT_PREHEAT_PLA_TR, + FUI_TEXT_PREHEAT_ABS_TR, + FUI_TEXT_LIGHTS_ONOFF_TR, + FUI_TEXT_COOLDOWN_TR, + FUI_TEXT_SET_TO_ORIGIN_TR, + FUI_TEXT_DISABLE_STEPPER_TR, + FUI_TEXT_X_POSITION_TR, + FUI_TEXT_X_POS_FAST_TR, + FUI_TEXT_Y_POSITION_TR, + FUI_TEXT_Y_POS_FAST_TR, + FUI_TEXT_Z_POSITION_TR, + FUI_TEXT_Z_POS_FAST_TR, + FUI_TEXT_E_POSITION_TR, + FUI_TEXT_BED_TEMP_TR, + FUI_TEXT_EXTR0_TEMP_TR, + FUI_TEXT_EXTR1_TEMP_TR, + FUI_TEXT_EXTR2_TEMP_TR, + FUI_TEXT_EXTR0_OFF_TR, + FUI_TEXT_EXTR1_OFF_TR, + FUI_TEXT_EXTR2_OFF_TR, + FUI_TEXT_EXTR0_SELECT_TR, + FUI_TEXT_EXTR1_SELECT_TR, + FUI_TEXT_EXTR2_SELECT_TR, + FUI_TEXT_EXTR_ORIGIN_TR, + FUI_TEXT_PRINT_X_TR, + FUI_TEXT_PRINT_Y_TR, + FUI_TEXT_PRINT_Z_TR, + FUI_TEXT_PRINT_Z_DELTA_TR, + FUI_TEXT_MOVE_X_TR, + FUI_TEXT_MOVE_Y_TR, + FUI_TEXT_MOVE_Z_TR, + FUI_TEXT_MOVE_Z_DELTA_TR, + FUI_TEXT_JERK_TR, + FUI_TEXT_ZJERK_TR, + FUI_TEXT_ACCELERATION_TR, + FUI_TEXT_STORE_TO_EEPROM_TR, + FUI_TEXT_LOAD_EEPROM_TR, + FUI_TEXT_DBG_ECHO_TR, + FUI_TEXT_DBG_INFO_TR, + FUI_TEXT_DBG_ERROR_TR, + FUI_TEXT_DBG_DRYRUN_TR, + FUI_TEXT_OPS_OFF_TR, + FUI_TEXT_OPS_CLASSIC_TR, + FUI_TEXT_OPS_FAST_TR, + FUI_TEXT_OPS_RETRACT_TR, + FUI_TEXT_OPS_BACKSLASH_TR, + FUI_TEXT_OPS_MINDIST_TR, + FUI_TEXT_OPS_MOVE_AFTER_TR, + FUI_TEXT_ANTI_OOZE_TR, + FUI_TEXT_PRINT_FILE_TR, + FUI_TEXT_PAUSE_PRINT_TR, + FUI_TEXT_CONTINUE_PRINT_TR, + FUI_TEXT_UNMOUNT_CARD_TR, + FUI_TEXT_MOUNT_CARD_TR, + FUI_TEXT_DELETE_FILE_TR, + FUI_TEXT_FEEDRATE_TR, + FUI_TEXT_FEED_MAX_X_TR, + FUI_TEXT_FEED_MAX_Y_TR, + FUI_TEXT_FEED_MAX_Z_TR, + FUI_TEXT_FEED_MAX_Z_DELTA_TR, + FUI_TEXT_FEED_HOME_X_TR, + FUI_TEXT_FEED_HOME_Y_TR, + FUI_TEXT_FEED_HOME_Z_TR, + FUI_TEXT_FEED_HOME_Z_DELTA_TR, + FUI_TEXT_ACTION_XPOSITION4A_TR, + FUI_TEXT_ACTION_XPOSITION4B_TR, + FUI_TEXT_ACTION_XPOSITION4C_TR, + FUI_TEXT_ACTION_XPOSITION4D_TR, + FUI_TEXT_ACTION_YPOSITION4A_TR, + FUI_TEXT_ACTION_YPOSITION4B_TR, + FUI_TEXT_ACTION_YPOSITION4C_TR, + FUI_TEXT_ACTION_YPOSITION4D_TR, + FUI_TEXT_ACTION_ZPOSITION4A_TR, + FUI_TEXT_ACTION_ZPOSITION4B_TR, + FUI_TEXT_ACTION_ZPOSITION4C_TR, + FUI_TEXT_ACTION_ZPOSITION4D_TR, + FUI_TEXT_ACTION_XPOSITION_FAST4A_TR, + FUI_TEXT_ACTION_XPOSITION_FAST4B_TR, + FUI_TEXT_ACTION_XPOSITION_FAST4C_TR, + FUI_TEXT_ACTION_XPOSITION_FAST4D_TR, + FUI_TEXT_ACTION_YPOSITION_FAST4A_TR, + FUI_TEXT_ACTION_YPOSITION_FAST4B_TR, + FUI_TEXT_ACTION_YPOSITION_FAST4C_TR, + FUI_TEXT_ACTION_YPOSITION_FAST4D_TR, + FUI_TEXT_ACTION_ZPOSITION_FAST4A_TR, + FUI_TEXT_ACTION_ZPOSITION_FAST4B_TR, + FUI_TEXT_ACTION_ZPOSITION_FAST4C_TR, + FUI_TEXT_ACTION_ZPOSITION_FAST4D_TR, + FUI_TEXT_ACTION_EPOSITION_FAST2A_TR, + FUI_TEXT_ACTION_EPOSITION_FAST2B_TR, + FUI_TEXT_ACTION_XPOSITION2A_TR, + FUI_TEXT_ACTION_XPOSITION2B_TR, + FUI_TEXT_ACTION_YPOSITION2A_TR, + FUI_TEXT_ACTION_YPOSITION2B_TR, + FUI_TEXT_ACTION_ZPOSITION2A_TR, + FUI_TEXT_ACTION_ZPOSITION2B_TR, + FUI_TEXT_ACTION_XPOSITION_FAST2A_TR, + FUI_TEXT_ACTION_XPOSITION_FAST2B_TR, + FUI_TEXT_ACTION_YPOSITION_FAST2A_TR, + FUI_TEXT_ACTION_YPOSITION_FAST2B_TR, + FUI_TEXT_ACTION_ZPOSITION_FAST2A_TR, + FUI_TEXT_ACTION_ZPOSITION_FAST2B_TR, + FUI_TEXT_FANSPEED_TR, + FUI_TEXT_ACTION_FANSPEED_TR, + FUI_TEXT_FAN_OFF_TR, + FUI_TEXT_FAN_25_TR, + FUI_TEXT_FAN_50_TR, + FUI_TEXT_FAN_75_TR, + FUI_TEXT_FAN_FULL_TR, + FUI_TEXT_STEPPER_INACTIVE_TR, + FUI_TEXT_STEPPER_INACTIVE2A_TR, + FUI_TEXT_STEPPER_INACTIVE2B_TR, + FUI_TEXT_POWER_INACTIVE_TR, + FUI_TEXT_POWER_INACTIVE2A_TR, + FUI_TEXT_POWER_INACTIVE2B_TR, + FUI_TEXT_GENERAL_TR, + FUI_TEXT_BAUDRATE_TR, + FUI_TEXT_EXTR_STEPS_TR, + FUI_TEXT_EXTR_START_FEED_TR, + FUI_TEXT_EXTR_MAX_FEED_TR, + FUI_TEXT_EXTR_ACCEL_TR, + FUI_TEXT_EXTR_WATCH_TR, + FUI_TEXT_EXTR_ADVANCE_L_TR, + FUI_TEXT_EXTR_ADVANCE_K_TR, + FUI_TEXT_EXTR_MANAGER_TR, + FUI_TEXT_EXTR_PGAIN_TR, + FUI_TEXT_EXTR_DEADTIME_TR, + FUI_TEXT_EXTR_DMAX_DT_TR, + FUI_TEXT_EXTR_IGAIN_TR, + FUI_TEXT_EXTR_DGAIN_TR, + FUI_TEXT_EXTR_DMIN_TR, + FUI_TEXT_EXTR_DMAX_TR, + FUI_TEXT_EXTR_PMAX_TR, + FUI_TEXT_EXTR_XOFF_TR, + FUI_TEXT_EXTR_YOFF_TR, + FUI_TEXT_STRING_HM_BANGBANG_TR, + FUI_TEXT_STRING_HM_PID_TR, + FUI_TEXT_STRING_ACTION_TR, + FUI_TEXT_HEATING_EXTRUDER_TR, + FUI_TEXT_HEATING_BED_TR, + FUI_TEXT_KILLED_TR, + FUI_TEXT_STEPPER_DISABLED_TR, + FUI_TEXT_EEPROM_STOREDA_TR, + FUI_TEXT_EEPROM_STOREDB_TR, + FUI_TEXT_EEPROM_LOADEDA_TR, + FUI_TEXT_EEPROM_LOADEDB_TR, + FUI_TEXT_UPLOADING_TR, + FUI_TEXT_PAGE_BUFFER_TR, + FUI_TEXT_PAGE_EXTRUDER_TR, + FUI_TEXT_PAGE_EXTRUDER1_TR, + FUI_TEXT_PAGE_EXTRUDER2_TR, + FUI_TEXT_PAGE_EXTRUDER3_TR, + FUI_TEXT_PAGE_BED_TR, + FUI_TEXT_SPEED_MULTIPLY_TR, + FUI_TEXT_FLOW_MULTIPLY_TR, + FUI_TEXT_SHOW_MEASUREMENT_TR, + FUI_TEXT_RESET_MEASUREMENT_TR, + FUI_TEXT_SET_MEASURED_ORIGIN_TR, + FUI_TEXT_ZCALIB_TR, + FUI_TEXT_SET_P1_TR, + FUI_TEXT_SET_P2_TR, + FUI_TEXT_SET_P3_TR, + FUI_TEXT_CALCULATE_LEVELING_TR, + FUI_TEXT_LEVEL_TR, + FUI_TEXT_EXTR_WAIT_RETRACT_TEMP_TR, + FUI_TEXT_EXTR_WAIT_RETRACT_UNITS_TR, + FUI_TEXT_SD_REMOVED_TR, + FUI_TEXT_SD_INSERTED_TR, + FUI_TEXT_PRINTER_READY_TR, + FUI_TEXT_PRINTTIME_DAYS_TR, + FUI_TEXT_PRINTTIME_HOURS_TR, + FUI_TEXT_PRINTTIME_MINUTES_TR, + FUI_TEXT_PRINT_TIME_TR, + FUI_TEXT_PRINT_FILAMENT_TR, + FUI_TEXT_PRINTED_TR, + FUI_TEXT_POWER_TR, + FUI_TEXT_STRING_HM_DEADTIME_TR, + FUI_TEXT_STRING_HM_SLOWBANG_TR, + FUI_TEXT_STOP_PRINT_TR, + FUI_TEXT_Z_BABYSTEPPING_TR, + FUI_TEXT_CHANGE_FILAMENT_TR, + FUI_TEXT_WIZ_CH_FILAMENT1_TR, + FUI_TEXT_WIZ_CH_FILAMENT2_TR, + FUI_TEXT_WIZ_CH_FILAMENT3_TR, + FUI_TEXT_CLICK_DONE_TR, + FUI_TEXT_AUTOLEVEL_ONOFF_TR, + FUI_TEXT_SERVOPOS_TR, + FUI_TEXT_IGNORE_M106_TR, + FUI_TEXT_WIZ_REHEAT1_TR, + FUI_TEXT_WIZ_REHEAT2_TR, + FUI_TEXT_WIZ_WAITTEMP1_TR, + FUI_TEXT_WIZ_WAITTEMP2_TR, + FUI_TEXT_EXTRUDER_JAM_TR, + FUI_TEXT_STANDBY_TR, + FUI_TEXT_BED_COATING_TR, + FUI_TEXT_BED_COATING_SET1_TR, + FUI_TEXT_BED_COATING_SET2_TR, + FUI_TEXT_NOCOATING_TR, + FUI_TEXT_BUILDTAK_TR, + FUI_TEXT_KAPTON_TR, + FUI_TEXT_BLUETAPE_TR, + FUI_TEXT_PETTAPE_TR, + FUI_TEXT_GLUESTICK_TR, + FUI_TEXT_CUSTOM_TR, + FUI_TEXT_COATING_CUSTOM_TR, + FUI_TEXT_LANGUAGE_TR, + FUI_TEXT_MAINPAGE6_1_TR, + FUI_TEXT_MAINPAGE6_2_TR, + FUI_TEXT_MAINPAGE6_3_TR, + FUI_TEXT_MAINPAGE6_4_TR, + FUI_TEXT_MAINPAGE6_5_TR, + FUI_TEXT_MAINPAGE6_6_TR, + FUI_TEXT_MAINPAGE_TEMP_BED_TR, + FUI_TEXT_MAINPAGE_BED_TR, + FUI_TEXT_MAINPAGE_Z_BUF_TR, + FUI_TEXT_MAINPAGE_MUL_EUSAGE_TR, + FUI_TEXT_MAINPAGE_XY_TR, + FUI_TEXT_PRINT_TIME_VALUE_TR, + FUI_TEXT_PRINT_FILAMENT_VALUE_TR, + FUI_TEXT_METER_PRINTED_TR, + FUI_TEXT_STATUS_TR, + FUI_TEXT_EMPTY_TR, + FUI_TEXT_TEMP_SET_TR, + FUI_TEXT_CURRENT_TEMP_TR, + FUI_TEXT_COATING_THICKNESS_TR, + FUI_TEXT_EXTR3_TEMP_TR, + FUI_TEXT_EXTR4_TEMP_TR, + FUI_TEXT_EXTR5_TEMP_TR, + FUI_TEXT_EXTR3_OFF_TR, + FUI_TEXT_EXTR4_OFF_TR, + FUI_TEXT_EXTR5_OFF_TR, + FUI_TEXT_EXTR3_SELECT_TR, + FUI_TEXT_EXTR4_SELECT_TR, + FUI_TEXT_EXTR5_SELECT_TR, + FUI_TEXT_DITTO_0_TR, + FUI_TEXT_DITTO_1_TR, + FUI_TEXT_DITTO_2_TR, + FUI_TEXT_DITTO_3_TR, + FUI_TEXT_ZPROBE_HEIGHT_TR, + FUI_TEXT_OFFSETS_TR, + FUI_TEXT_X_OFFSET_TR, + FUI_TEXT_Y_OFFSET_TR, + FUI_TEXT_Z_OFFSET_TR +}; +#define LANG_TR_TABLE translations_TR +#else +#define LANG_TR_TABLE NULL +#endif // LANGUAGE_TR_ACTIVE + +// References to the possible languages + +PGM_P const * const translations[NUM_LANGUAGES_KNOWN] PROGMEM = { + LANG_EN_TABLE, + LANG_DE_TABLE, + LANG_NL_TABLE, + LANG_PT_TABLE, + LANG_IT_TABLE, + LANG_ES_TABLE, + LANG_SE_TABLE, + LANG_FR_TABLE, + LANG_CZ_TABLE, + LANG_PL_TABLE, + LANG_TR_TABLE +}; + +// Array in flash to select only valid languages + +const uint8_t availableLanguages[] PROGMEM = { +#if LANGUAGE_EN_ACTIVE + 0, +#endif // LANGUAGE_EN_ACTIVE +#if LANGUAGE_DE_ACTIVE + 1, +#endif // LANGUAGE_DE_ACTIVE +#if LANGUAGE_NL_ACTIVE + 2, +#endif // LANGUAGE_NL_ACTIVE +#if LANGUAGE_PT_ACTIVE + 3, +#endif // LANGUAGE_PT_ACTIVE +#if LANGUAGE_IT_ACTIVE + 4, +#endif // LANGUAGE_IT_ACTIVE +#if LANGUAGE_ES_ACTIVE + 5, +#endif // LANGUAGE_ES_ACTIVE +#if LANGUAGE_SE_ACTIVE + 6, +#endif // LANGUAGE_SE_ACTIVE +#if LANGUAGE_FR_ACTIVE + 7, +#endif // LANGUAGE_FR_ACTIVE +#if LANGUAGE_CZ_ACTIVE + 8, +#endif // LANGUAGE_CZ_ACTIVE +#if LANGUAGE_PL_ACTIVE + 9, +#endif // LANGUAGE_PL_ACTIVE +#if LANGUAGE_TR_ACTIVE + 10, +#endif // LANGUAGE_TR_ACTIVE + 255 +}; + +void Com::selectLanguage(fast8_t lang) { + unsigned int pos = (unsigned int)&availableLanguages; + uint8_t best = 255,cur; + while((cur = HAL::readFlashByte((PGM_P)pos)) != 255) { + if(best == 255 || cur == lang) + best = cur; + pos++; + } + Com::selectedLanguage = best; +} + +const char* Com::translatedF(int textId) { + PGM_P *adr = (PGM_P*)pgm_read_word(&translations[selectedLanguage]); + return (const char *)pgm_read_word(&adr[textId]); +} + +#endif diff --git a/Repetier/uilang.h b/Repetier/uilang.h index fe194bf..b279522 100644 --- a/Repetier/uilang.h +++ b/Repetier/uilang.h @@ -1,1953 +1,3590 @@ -/* - This file is part of Repetier-Firmware. +/* + 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 . + +*/ + +#if !defined(UI_DISPLAY_CHARSET) || UI_DISPLAY_CHARSET > 3 +#define UI_DISPLAY_CHARSET 1 +#endif + +//Symbolic character values for specific symbols. +//May be overridden for different controllers, charactersets, etc. +#define cUP "\001" +#define cDEG "\002" +#define cSEL "\003" +#define cUNSEL "\004" +#define cTEMP "\005" +#define cFOLD "\006" +#define bFOLD 6 +#define cARROW "\176" + +#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 + + +#if UI_DISPLAY_CHARSET==3 // U8glib +#define CHAR_RIGHT 187 //>> +#define CHAR_SELECTOR 255 //'>' +#define CHAR_SELECTED 254 //'*' +#define STR_auml "\344" +#define STR_Auml "\304" +#define STR_uuml "\374" +#define STR_Uuml "\334" +#define STR_ouml "\366" +#define STR_Ouml "\326" +#define STR_szlig "\337" +#endif + +#define LANGUAGE_EN_ID 0 +#define LANGUAGE_DE_ID 1 +#define LANGUAGE_NL_ID 2 +#define LANGUAGE_PT_ID 3 +#define LANGAUGE_IT_ID 4 +#define LANGUAGE_ES_ID 5 +#define LANGUAGE_SE_ID 6 +#define LANGUAGE_FR_ID 7 +#define LANGUAGE_CZ_ID 8 +#define LANGUAGE_PL_ID 9 +#define LANGUAGE_TR_ID 10 + +#define NUM_LANGUAGES_KNOWN 11 +#define NUM_TRANSLATED_WORDS 266 + +// For selectable translations we refer to each text by a id which gets +// defined here. The list starts at 0 and defines the position in the +// translation index. + +#define UI_TEXT_ON_ID 0 // "On" +#define UI_TEXT_OFF_ID 1 // "Off" +#define UI_TEXT_NA_ID 2 // "N/A" // Output for not available +#define UI_TEXT_YES_ID 3 // "Yes" +#define UI_TEXT_NO_ID 4 // "No" +#define UI_TEXT_PRINT_POS_ID 5 // "Printing..." +#define UI_TEXT_PRINTING_ID 6 // "Printing" +#define UI_TEXT_IDLE_ID 7 // "Idle" +#define UI_TEXT_NOSDCARD_ID 8 // "No SD Card" +#define UI_TEXT_ERROR_ID 9 // "**** ERROR ****" +#define UI_TEXT_BACK_ID 10 // "Back " cUP +#define UI_TEXT_QUICK_SETTINGS_ID 11 // "Quick Settings" +#define UI_TEXT_ERRORMSG_ID 12 // "%oe" +#define UI_TEXT_CONFIGURATION_ID 13 // "Configuration" +#define UI_TEXT_POSITION_ID 14 // "Position" +#define UI_TEXT_EXTRUDER_ID 15 // "Extruder" +#define UI_TEXT_SD_CARD_ID 16 // "SD Card" +#define UI_TEXT_DEBUGGING_ID 17 // "Debugging" +#define UI_TEXT_HOME_DELTA_ID 18 // "Home Delta" +#define UI_TEXT_HOME_ALL_ID 19 // "Home All" +#define UI_TEXT_HOME_X_ID 20 // "Home X" +#define UI_TEXT_HOME_Y_ID 21 // "Home Y" +#define UI_TEXT_HOME_Z_ID 22 // "Home Z" +#define UI_TEXT_PREHEAT_PLA_ID 23 // "Preheat PLA" +#define UI_TEXT_PREHEAT_ABS_ID 24 // "Preheat ABS" +#define UI_TEXT_LIGHTS_ONOFF_ID 25 // "Lights :%lo" +#define UI_TEXT_COOLDOWN_ID 26 // "Cooldown" +#define UI_TEXT_SET_TO_ORIGIN_ID 27 // "Set to Origin" +#define UI_TEXT_DISABLE_STEPPER_ID 28 // "Disable stepper" +#define UI_TEXT_X_POSITION_ID 29 // "X Position" +#define UI_TEXT_X_POS_FAST_ID 30 // "X Pos. Fast" +#define UI_TEXT_Y_POSITION_ID 31 // "Y Position" +#define UI_TEXT_Y_POS_FAST_ID 32 // "Y Pos. Fast" +#define UI_TEXT_Z_POSITION_ID 33 // "Z Position" +#define UI_TEXT_Z_POS_FAST_ID 34 // "Z Pos. Fast" +#define UI_TEXT_E_POSITION_ID 35 // "Extr. position" +#define UI_TEXT_BED_TEMP_ID 36 // "Bed Temp: %Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_ID 37 // "Temp. 1 : %E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_ID 38 // "Temp. 2 : %E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_ID 39 // "Temp. 3 : %E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_ID 40 // "Turn Extr. 1 Off" +#define UI_TEXT_EXTR1_OFF_ID 41 // "Turn Extr. 2 Off" +#define UI_TEXT_EXTR2_OFF_ID 42 // "Turn Extr. 3 Off" +#define UI_TEXT_EXTR0_SELECT_ID 43 // "%X0 Select Extr. 1" +#define UI_TEXT_EXTR1_SELECT_ID 44 // "%X1 Select Extr. 2" +#define UI_TEXT_EXTR2_SELECT_ID 45 // "%X2 Select Extr. 3" +#define UI_TEXT_EXTR_ORIGIN_ID 46 // "Set Origin" +#define UI_TEXT_PRINT_X_ID 47 // "Print X:%ax" +#define UI_TEXT_PRINT_Y_ID 48 // "Print Y:%ay" +#define UI_TEXT_PRINT_Z_ID 49 // "Print Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_ID 50 // "Print:%az" +#define UI_TEXT_MOVE_X_ID 51 // "Move X :%aX" +#define UI_TEXT_MOVE_Y_ID 52 // "Move Y :%aY" +#define UI_TEXT_MOVE_Z_ID 53 // "Move Z :%aZ" +#define UI_TEXT_MOVE_Z_DELTA_ID 54 // "Move:%aZ" +#define UI_TEXT_JERK_ID 55 // "Jerk :%aj" +#define UI_TEXT_ZJERK_ID 56 // "Z-Jerk :%aJ" +#define UI_TEXT_ACCELERATION_ID 57 // "Acceleration" +#define UI_TEXT_STORE_TO_EEPROM_ID 58 // "Store to EEPROM" +#define UI_TEXT_LOAD_EEPROM_ID 59 // "Load f. EEPROM" +#define UI_TEXT_DBG_ECHO_ID 60 // "Echo :%do" +#define UI_TEXT_DBG_INFO_ID 61 // "Info :%di" +#define UI_TEXT_DBG_ERROR_ID 62 // "Errors :%de" +#define UI_TEXT_DBG_DRYRUN_ID 63 // "Dry run:%dd" +#define UI_TEXT_OPS_OFF_ID 64 // "%O0 OPS Off" +#define UI_TEXT_OPS_CLASSIC_ID 65 // "%O1 OPS Classic" +#define UI_TEXT_OPS_FAST_ID 66 // "%O2 OPS Fast" +#define UI_TEXT_OPS_RETRACT_ID 67 // "Retract :%Or" +#define UI_TEXT_OPS_BACKSLASH_ID 68 // "Backsl. :%Ob" +#define UI_TEXT_OPS_MINDIST_ID 69 // "Min.dist :%Od" +#define UI_TEXT_OPS_MOVE_AFTER_ID 70 // "Move after:%Oa" +#define UI_TEXT_ANTI_OOZE_ID 71 // "Anti Ooze" +#define UI_TEXT_PRINT_FILE_ID 72 // "Print file" +#define UI_TEXT_PAUSE_PRINT_ID 73 // "Pause Print" +#define UI_TEXT_CONTINUE_PRINT_ID 74 // "Continue Print" +#define UI_TEXT_UNMOUNT_CARD_ID 75 // "Unmount Card" +#define UI_TEXT_MOUNT_CARD_ID 76 // "Mount Card" +#define UI_TEXT_DELETE_FILE_ID 77 // "Delete file" +#define UI_TEXT_FEEDRATE_ID 78 // "Feedrate" +#define UI_TEXT_FEED_MAX_X_ID 79 // "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_ID 80 // "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_ID 81 // "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_ID 82 // "Max:%fz" +#define UI_TEXT_FEED_HOME_X_ID 83 // "Home X:%fX" +#define UI_TEXT_FEED_HOME_Y_ID 84 // "Home Y:%fY" +#define UI_TEXT_FEED_HOME_Z_ID 85 // "Home Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_ID 86 // "Home:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_ID 87 // "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_ID 88 // "Min endstop:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_ID 89 // "Max endstop:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_ID 90 // "" +#define UI_TEXT_ACTION_YPOSITION4A_ID 91 // "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_ID 92 // "Min endstop:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_ID 93 // "Max endstop:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_ID 94 // "" +#define UI_TEXT_ACTION_ZPOSITION4A_ID 95 // "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_ID 96 // "Min endstop:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_ID 97 // "Max endstop:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_ID 98 // "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_ID 99 // "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_ID 100 // "Min endstop:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_ID 101 // "Max endstop:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_ID 102 // "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_ID 103 // "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_ID 104 // "Min endstop:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_ID 105 // "Max endstop:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_ID 106 // "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_ID 107 // "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_ID 108 // "Min endstop:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_ID 109 // "Max endstop:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_ID 110 // "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_ID 111 // "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_ID 112 // "1 click = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_ID 113 // "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_ID 114 // "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_ID 115 // "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_ID 116 // "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_ID 117 // "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_ID 118 // "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_ID 119 // "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_ID 120 // "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_ID 121 // "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_ID 122 // "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_ID 123 // "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_ID 124 // "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_ID 125 // "Fan speed" +#define UI_TEXT_ACTION_FANSPEED_ID 126 // "Fan speed:%Fs%%%" +#define UI_TEXT_FAN_OFF_ID 127 // "Turn Fan Off" +#define UI_TEXT_FAN_25_ID 128 // "Set Fan 25%%%" +#define UI_TEXT_FAN_50_ID 129 // "Set Fan 50%%%" +#define UI_TEXT_FAN_75_ID 130 // "Set Fan 75%%%" +#define UI_TEXT_FAN_FULL_ID 131 // "Set Fan Full" +#define UI_TEXT_STEPPER_INACTIVE_ID 132 // "Stepper Inactive" +#define UI_TEXT_STEPPER_INACTIVE2A_ID 133 // "Dis. After: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_ID 134 // "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_ID 135 // "Max. Inactive" +#define UI_TEXT_POWER_INACTIVE2A_ID 136 // "Dis. After: %ip" +#define UI_TEXT_POWER_INACTIVE2B_ID 137 // "[min] 0=Off" +#define UI_TEXT_GENERAL_ID 138 // "General" +#define UI_TEXT_BAUDRATE_ID 139 // "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_ID 140 // "Steps/MM:%Se" +#define UI_TEXT_EXTR_START_FEED_ID 141 // "Start FR:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_ID 142 // "Max FR:%XF" +#define UI_TEXT_EXTR_ACCEL_ID 143 // "Accel:%XA" +#define UI_TEXT_EXTR_WATCH_ID 144 // "Stab.Time:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_ID 145 // "Advance lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_ID 146 // "Advance quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_ID 147 // "Control:%Xh" +#define UI_TEXT_EXTR_PGAIN_ID 148 // "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_ID 149 // "Deadtime:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_ID 150 // "Control PWM:%XM" +#define UI_TEXT_EXTR_IGAIN_ID 151 // "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_ID 152 // "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_ID 153 // "Drive Min:%Xm" +#define UI_TEXT_EXTR_DMAX_ID 154 // "Drive Max:%XM" +#define UI_TEXT_EXTR_PMAX_ID 155 // "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_ID 156 // "X-Offset:%Xx" +#define UI_TEXT_EXTR_YOFF_ID 157 // "Y-Offset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_ID 158 // "BangBang" +#define UI_TEXT_STRING_HM_PID_ID 159 // "PID" +#define UI_TEXT_STRING_ACTION_ID 160 // "Action:%la" +#define UI_TEXT_HEATING_EXTRUDER_ID 161// "Heating Extruder" +#define UI_TEXT_HEATING_BED_ID 162 // "Heating Bed" +#define UI_TEXT_KILLED_ID 163 // "Killed" +#define UI_TEXT_STEPPER_DISABLED_ID 164 // "Stepper Disabled" +#define UI_TEXT_EEPROM_STOREDA_ID 165 // "Configuration" +#define UI_TEXT_EEPROM_STOREDB_ID 166 // "stored in EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_ID 167 // "Configuration" +#define UI_TEXT_EEPROM_LOADEDB_ID 168 // "loaded f. EEPROM" +#define UI_TEXT_UPLOADING_ID 169 // "Uploading..." +#define UI_TEXT_PAGE_BUFFER_ID 170 // "Buffer:%oB" +#define UI_TEXT_PAGE_EXTRUDER_ID 171 // " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_ID 172 // "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_ID 173 // "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_ID 174 // "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_ID 175 // " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_ID 176 // "Speed Mul.:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_ID 177 // "Flow Mul. :%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_ID 178 // "Show meas." +#define UI_TEXT_RESET_MEASUREMENT_ID 179 // "Reset meas." +#define UI_TEXT_SET_MEASURED_ORIGIN_ID 180 // "Set Z=0" +#define UI_TEXT_ZCALIB_ID 181 // "Z Calib." +#define UI_TEXT_SET_P1_ID 182 // "Set P1" +#define UI_TEXT_SET_P2_ID 183 // "Set P2" +#define UI_TEXT_SET_P3_ID 184 // "Set P3" +#define UI_TEXT_CALCULATE_LEVELING_ID 185 // "Calculate Leveling" +#define UI_TEXT_LEVEL_ID 186 // "Level delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_ID 187 // "Wait Temp. %XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_ID 188 // "Wait Units: %XU mm" +#define UI_TEXT_SD_REMOVED_ID 189 // "SD Card removed" +#define UI_TEXT_SD_INSERTED_ID 190 // "SD Card inserted" +#define UI_TEXT_PRINTER_READY_ID 191 // "Printer ready." +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_ID 192 // " days " +#define UI_TEXT_PRINTTIME_HOURS_ID 193 // ":" +#define UI_TEXT_PRINTTIME_MINUTES_ID 194 // "" +#define UI_TEXT_PRINT_TIME_ID 195 // "Printing time" +#define UI_TEXT_PRINT_FILAMENT_ID 196 // "Filament printed" +#define UI_TEXT_PRINTED_ID 197 // "printed" +#define UI_TEXT_POWER_ID 198 // "ATX power on/off" +#define UI_TEXT_STRING_HM_DEADTIME_ID 199 // "Dead Time" +#define UI_TEXT_STRING_HM_SLOWBANG_ID 200 // "SlowBang" +#define UI_TEXT_STOP_PRINT_ID 201 // "Stop Print" +#define UI_TEXT_Z_BABYSTEPPING_ID 202 // "Z Babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_ID 203 // "Change filament" +#define UI_TEXT_WIZ_CH_FILAMENT1_ID 204 // "Change filament" +#define UI_TEXT_WIZ_CH_FILAMENT2_ID 205 // "Rotate to move" +#define UI_TEXT_WIZ_CH_FILAMENT3_ID 206 // "filament up/down" +#define UI_TEXT_CLICK_DONE_ID 207 // "Click when done" +#define UI_TEXT_AUTOLEVEL_ONOFF_ID 208 // "Autolevel: %ll" +#define UI_TEXT_SERVOPOS_ID 209 // "Servo pos.: %oS" +#define UI_TEXT_IGNORE_M106_ID 210 // "Ignore M106 cmd %Fi" +#define UI_TEXT_WIZ_REHEAT1_ID 211 // "Click to reheat" +#define UI_TEXT_WIZ_REHEAT2_ID 212 // "extruders." +#define UI_TEXT_WIZ_WAITTEMP1_ID 213 // "Wait for target" +#define UI_TEXT_WIZ_WAITTEMP2_ID 214 // "temperatures ..." +#define UI_TEXT_EXTRUDER_JAM_ID 215 // "Extruder Jam" +#define UI_TEXT_STANDBY_ID 216 // "Standby" +#define UI_TEXT_BED_COATING_ID 217 // "Bed Coating" +#define UI_TEXT_BED_COATING_SET1_ID 218 // "Bed coating set to","" +#define UI_TEXT_BED_COATING_SET2_ID 219 // "Bed coating set to","" +#define UI_TEXT_NOCOATING_ID 220 // "No Coating" +#define UI_TEXT_BUILDTAK_ID 221 // "BuildTak" +#define UI_TEXT_KAPTON_ID 222 // "Kapton" +#define UI_TEXT_BLUETAPE_ID 223 // "Blue Paper Tape" +#define UI_TEXT_PETTAPE_ID 224 // "Green PET Tape" +#define UI_TEXT_GLUESTICK_ID 225 // "Glue Stick" +#define UI_TEXT_CUSTOM_ID 226 // "Custom" +#define UI_TEXT_COATING_CUSTOM_ID 227 // "Custom : %oCmm" +#define UI_TEXT_LANGUAGE_ID 228 // "Language" +#define UI_TEXT_MAINPAGE6_1_ID 229 //"\xa %e0/%E0\xb0 X:%x0" +#define UI_TEXT_MAINPAGE6_2_ID 230 //"\xa %e1/%E1\xb0 Y:%x1" +#define UI_TEXT_MAINPAGE6_3_ID 231 //"\xe %eb/%Eb\xb0 Z:%x2", +#define UI_TEXT_MAINPAGE6_4_ID 232 //"Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_ID 233 //"Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_ID 234 //"%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_ID 235 //cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_ID 236 //"B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_ID 237 //"Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_ID 238 //"Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_ID 239 //"X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_ID 240 //"%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_ID 241 //"%Uf m" +#define UI_TEXT_METER_PRINTED_ID 242 //"%Uf m " UI_TEXT_PRINTED +#define UI_TEXT_STATUS_ID 243 //"%os" +#define UI_TEXT_EMPTY_ID 244 //"" +#define UI_TEXT_TEMP_SET_ID 245 //cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_ID 246 //cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_ID 247 //" %oCmm" +#define UI_TEXT_EXTR3_TEMP_ID 248 // "Temp. 4 : %E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_ID 249 // "Temp. 5 : %E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_ID 250 // "Temp. 6 : %E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_ID 251 +#define UI_TEXT_EXTR4_OFF_ID 252 +#define UI_TEXT_EXTR5_OFF_ID 253 +#define UI_TEXT_EXTR3_SELECT_ID 254 +#define UI_TEXT_EXTR4_SELECT_ID 255 +#define UI_TEXT_EXTR5_SELECT_ID 256 +#define UI_TEXT_DITTO_0_ID 257 +#define UI_TEXT_DITTO_1_ID 258 +#define UI_TEXT_DITTO_2_ID 259 +#define UI_TEXT_DITTO_3_ID 260 +#define UI_TEXT_ZPROBE_HEIGHT_ID 261 +#define UI_TEXT_OFFSETS_ID 262 +#define UI_TEXT_X_OFFSET_ID 263 +#define UI_TEXT_Y_OFFSET_ID 264 +#define UI_TEXT_Z_OFFSET_ID 265 - 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 . - -*/ - -#if !defined(UI_DISPLAY_CHARSET) || UI_DISPLAY_CHARSET>3 -#define UI_DISPLAY_CHARSET 1 -#endif - -//Symbolic character values for specific symbols. -//May be overridden for different controllers, charactersets, etc. -#define cUP "\001" -#define cDEG "\002" -#define cSEL "\003" -#define cUNSEL "\004" -#define cTEMP "\005" -#define cFOLD "\006" -#define bFOLD 6 -#define cARROW "\176" - -#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 +// Universal definitions + +#define UI_TEXT_SEL cSEL +#define UI_TEXT_NOSEL cUNSEL + + +// 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_EN "On" +#define UI_TEXT_OFF_EN "Off" +#define UI_TEXT_NA_EN "N/A" // Output for not available +#define UI_TEXT_YES_EN "Yes" +#define UI_TEXT_NO_EN "No" +#define UI_TEXT_PRINT_POS_EN "Printing..." +#define UI_TEXT_PRINTING_EN "Printing" +#define UI_TEXT_IDLE_EN "Idle" +#define UI_TEXT_NOSDCARD_EN "No SD card" +#define UI_TEXT_ERROR_EN "**** ERROR ****" +#define UI_TEXT_BACK_EN "Back " cUP +#define UI_TEXT_QUICK_SETTINGS_EN "Quick settings" +#define UI_TEXT_ERRORMSG_EN "%oe" +#define UI_TEXT_CONFIGURATION_EN "Configuration" +#define UI_TEXT_POSITION_EN "Position" +#define UI_TEXT_EXTRUDER_EN "Extruder" +#define UI_TEXT_SD_CARD_EN "SD card" +#define UI_TEXT_DEBUGGING_EN "Debugging" +#define UI_TEXT_HOME_DELTA_EN "Home delta" +#define UI_TEXT_HOME_ALL_EN "Home all" +#define UI_TEXT_HOME_X_EN "Home X" +#define UI_TEXT_HOME_Y_EN "Home Y" +#define UI_TEXT_HOME_Z_EN "Home Z" +#define UI_TEXT_PREHEAT_PLA_EN "Preheat PLA" +#define UI_TEXT_PREHEAT_ABS_EN "Preheat ABS" +#define UI_TEXT_LIGHTS_ONOFF_EN "Lights:%lo" +#define UI_TEXT_COOLDOWN_EN "Cooldown" +#define UI_TEXT_SET_TO_ORIGIN_EN "Set to origin" +#define UI_TEXT_DISABLE_STEPPER_EN "Disable stepper" +#define UI_TEXT_X_POSITION_EN "X position" +#define UI_TEXT_X_POS_FAST_EN "X pos. fast" +#define UI_TEXT_Y_POSITION_EN "Y position" +#define UI_TEXT_Y_POS_FAST_EN "Y pos. fast" +#define UI_TEXT_Z_POSITION_EN "Z position" +#define UI_TEXT_Z_POS_FAST_EN "Z pos. fast" +#define UI_TEXT_E_POSITION_EN "Extr. position" +#define UI_TEXT_BED_TEMP_EN "Bed temp:%eb/%Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_EN "Temp. 1 :%e0/%E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_EN "Temp. 2 :%e1/%E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_EN "Temp. 3 :%e2/%E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_EN "Turn extr. 1 off" +#define UI_TEXT_EXTR1_OFF_EN "Turn extr. 2 off" +#define UI_TEXT_EXTR2_OFF_EN "Turn extr. 3 off" +#define UI_TEXT_EXTR0_SELECT_EN "%X0 Select extr. 1" +#define UI_TEXT_EXTR1_SELECT_EN "%X1 Select extr. 2" +#define UI_TEXT_EXTR2_SELECT_EN "%X2 Select extr. 3" +#define UI_TEXT_EXTR_ORIGIN_EN "Set Origin" +#define UI_TEXT_PRINT_X_EN "Print X:%ax" +#define UI_TEXT_PRINT_Y_EN "Print Y:%ay" +#define UI_TEXT_PRINT_Z_EN "Print Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_EN "Print:%az" +#define UI_TEXT_MOVE_X_EN "Move X :%aX" +#define UI_TEXT_MOVE_Y_EN "Move Y :%aY" +#define UI_TEXT_MOVE_Z_EN "Move Z :%aZ" +#define UI_TEXT_MOVE_Z_DELTA_EN "Move:%aZ" +#define UI_TEXT_JERK_EN "Jerk :%aj" +#define UI_TEXT_ZJERK_EN "Z-Jerk :%aJ" +#define UI_TEXT_ACCELERATION_EN "Acceleration" +#define UI_TEXT_STORE_TO_EEPROM_EN "Store to EEPROM" +#define UI_TEXT_LOAD_EEPROM_EN "Load f. EEPROM" +#define UI_TEXT_DBG_ECHO_EN "Echo :%do" +#define UI_TEXT_DBG_INFO_EN "Info :%di" +#define UI_TEXT_DBG_ERROR_EN "Errors :%de" +#define UI_TEXT_DBG_DRYRUN_EN "Dry run:%dd" +#define UI_TEXT_OPS_OFF_EN "%O0 OPS off" +#define UI_TEXT_OPS_CLASSIC_EN "%O1 OPS classic" +#define UI_TEXT_OPS_FAST_EN "%O2 OPS fast" +#define UI_TEXT_OPS_RETRACT_EN "Retract :%Or" +#define UI_TEXT_OPS_BACKSLASH_EN "Backsl. :%Ob" +#define UI_TEXT_OPS_MINDIST_EN "Min.dist :%Od" +#define UI_TEXT_OPS_MOVE_AFTER_EN "Move after:%Oa" +#define UI_TEXT_ANTI_OOZE_EN "Anti ooze" +#define UI_TEXT_PRINT_FILE_EN "Print file" +#define UI_TEXT_PAUSE_PRINT_EN "Pause print" +#define UI_TEXT_CONTINUE_PRINT_EN "Continue print" +#define UI_TEXT_UNMOUNT_CARD_EN "Unmount card" +#define UI_TEXT_MOUNT_CARD_EN "Mount card" +#define UI_TEXT_DELETE_FILE_EN "Delete file" +#define UI_TEXT_FEEDRATE_EN "Feedrate" +#define UI_TEXT_FEED_MAX_X_EN "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_EN "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_EN "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_EN "Max:%fz" +#define UI_TEXT_FEED_HOME_X_EN "Home X:%fX" +#define UI_TEXT_FEED_HOME_Y_EN "Home Y:%fY" +#define UI_TEXT_FEED_HOME_Z_EN "Home Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_EN "Home:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_EN "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_EN "Min endstop:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_EN "Max endstop:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_EN "" +#define UI_TEXT_ACTION_YPOSITION4A_EN "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_EN "Min endstop:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_EN "Max endstop:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_EN "" +#define UI_TEXT_ACTION_ZPOSITION4A_EN "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_EN "Min endstop:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_EN "Max endstop:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_EN "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_EN "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_EN "Min endstop:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_EN "Max endstop:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_EN "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_EN "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_EN "Min endstop:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_EN "Max endstop:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_EN "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_EN "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_EN "Min endstop:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_EN "Max endstop:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_EN "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_EN "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_EN "1 click = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_EN "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_EN "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_EN "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_EN "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_EN "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_EN "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_EN "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_EN "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_EN "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_EN "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_EN "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_EN "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_EN "Fan speed" +#define UI_TEXT_ACTION_FANSPEED_EN "Fan speed:%Fs%%%" +#define UI_TEXT_FAN_OFF_EN "Turn fan Off" +#define UI_TEXT_FAN_25_EN "Set fan 25%%%" +#define UI_TEXT_FAN_50_EN "Set fan 50%%%" +#define UI_TEXT_FAN_75_EN "Set fan 75%%%" +#define UI_TEXT_FAN_FULL_EN "Set fan full" +#define UI_TEXT_STEPPER_INACTIVE_EN "Stepper inactive" +#define UI_TEXT_STEPPER_INACTIVE2A_EN "Dis. after: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_EN "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_EN "Max. inactive" +#define UI_TEXT_POWER_INACTIVE2A_EN "Dis. after: %ip" +#define UI_TEXT_POWER_INACTIVE2B_EN "[min] 0=Off" +#define UI_TEXT_GENERAL_EN "General" +#define UI_TEXT_BAUDRATE_EN "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_EN "Steps/MM:%Se" +#define UI_TEXT_EXTR_START_FEED_EN "Start FR:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_EN "Max FR:%XF" +#define UI_TEXT_EXTR_ACCEL_EN "Accel:%XA" +#define UI_TEXT_EXTR_WATCH_EN "Stab.Time:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_EN "Advance lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_EN "Advance quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_EN "Control:%Xh" +#define UI_TEXT_EXTR_PGAIN_EN "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_EN "Deadtime:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_EN "Control PWM:%XM" +#define UI_TEXT_EXTR_IGAIN_EN "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_EN "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_EN "Drive Min:%Xm" +#define UI_TEXT_EXTR_DMAX_EN "Drive Max:%XM" +#define UI_TEXT_EXTR_PMAX_EN "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_EN "X-Offset:%Xx" +#define UI_TEXT_EXTR_YOFF_EN "Y-Offset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_EN "BangBang" +#define UI_TEXT_STRING_HM_PID_EN "PID" +#define UI_TEXT_STRING_ACTION_EN "Action:%la" +#define UI_TEXT_HEATING_EXTRUDER_EN "Heating extruder" +#define UI_TEXT_HEATING_BED_EN "Heating bed" +#define UI_TEXT_KILLED_EN "Killed" +#define UI_TEXT_STEPPER_DISABLED_EN "Stepper disabled" +#define UI_TEXT_EEPROM_STOREDA_EN "Configuration" +#define UI_TEXT_EEPROM_STOREDB_EN "stored in EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_EN "Configuration" +#define UI_TEXT_EEPROM_LOADEDB_EN "loaded f. EEPROM" +#define UI_TEXT_UPLOADING_EN "Uploading..." +#define UI_TEXT_PAGE_BUFFER_EN "Buffer:%oB" +#define UI_TEXT_PAGE_EXTRUDER_EN " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_EN "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_EN "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_EN "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_EN " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_EN "Speed mul.:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_EN "Flow mul. :%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_EN "Show meas." +#define UI_TEXT_RESET_MEASUREMENT_EN "Reset meas." +#define UI_TEXT_SET_MEASURED_ORIGIN_EN "Set Z=0" +#define UI_TEXT_ZCALIB_EN "Z calib." +#define UI_TEXT_SET_P1_EN "Set P1" +#define UI_TEXT_SET_P2_EN "Set P2" +#define UI_TEXT_SET_P3_EN "Set P3" +#define UI_TEXT_CALCULATE_LEVELING_EN "Calculate leveling" +#define UI_TEXT_LEVEL_EN "Level delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_EN "Wait temp. %XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_EN "Wait retr.:%XU mm" +#define UI_TEXT_SD_REMOVED_EN "SD card removed" +#define UI_TEXT_SD_INSERTED_EN "SD card inserted" +#define UI_TEXT_PRINTER_READY_EN "Printer ready." +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_EN " days " +#define UI_TEXT_PRINTTIME_HOURS_EN ":" +#define UI_TEXT_PRINTTIME_MINUTES_EN "" +#define UI_TEXT_PRINT_TIME_EN "Printing time" +#define UI_TEXT_PRINT_FILAMENT_EN "Filament printed" +#define UI_TEXT_PRINTED_EN "printed" +#define UI_TEXT_POWER_EN "ATX power on/off" +#define UI_TEXT_STRING_HM_DEADTIME_EN "Dead time" +#define UI_TEXT_STRING_HM_SLOWBANG_EN "SlowBang" +#define UI_TEXT_STOP_PRINT_EN "Stop Print" +#define UI_TEXT_Z_BABYSTEPPING_EN "Z babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_EN "Change filament" +#define UI_TEXT_WIZ_CH_FILAMENT1_EN "Change filament" +#define UI_TEXT_WIZ_CH_FILAMENT2_EN "Rotate to move" +#define UI_TEXT_WIZ_CH_FILAMENT3_EN "filament up/down" +#define UI_TEXT_CLICK_DONE_EN "Click when done" +#define UI_TEXT_AUTOLEVEL_ONOFF_EN "Autolevel: %ll" +#define UI_TEXT_SERVOPOS_EN "Servo pos.: %oS" +#define UI_TEXT_IGNORE_M106_EN "Ignore M106 cmd %Fi" +#define UI_TEXT_WIZ_REHEAT1_EN "Click to reheat" +#define UI_TEXT_WIZ_REHEAT2_EN "extruders." +#define UI_TEXT_WIZ_WAITTEMP1_EN "Wait for target" +#define UI_TEXT_WIZ_WAITTEMP2_EN "temperatures ..." +#define UI_TEXT_EXTRUDER_JAM_EN "Extruder jam" +#define UI_TEXT_STANDBY_EN "Standby" +#define UI_TEXT_BED_COATING_EN "Bed coating" +#define UI_TEXT_BED_COATING_SET1_EN "Bed coating set to" +#define UI_TEXT_BED_COATING_SET2_EN "" +#define UI_TEXT_NOCOATING_EN "No coating" +#define UI_TEXT_BUILDTAK_EN "BuildTak" +#define UI_TEXT_KAPTON_EN "Kapton" +#define UI_TEXT_BLUETAPE_EN "Blue paper tape" +#define UI_TEXT_PETTAPE_EN "Green PET tape" +#define UI_TEXT_GLUESTICK_EN "Glue stick" +#define UI_TEXT_CUSTOM_EN "Custom" +#define UI_TEXT_COATING_CUSTOM_EN "Custom:%BCmm" +#define UI_TEXT_LANGUAGE_EN "Language" + +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_EN "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_EN "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_EN "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_EN "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_EN " Y:%x1" +#endif +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_EN "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_EN "Copies: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_EN "Flow:\xfd %of%%% Z:%x2" +#endif +#define UI_TEXT_MAINPAGE6_4_EN "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_EN "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_EN "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_EN cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_EN "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_EN "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_EN "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_EN "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_EN "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_EN "%Uf m" +#define UI_TEXT_METER_PRINTED_EN "%Uf m " UI_TEXT_PRINTED_EN +#define UI_TEXT_STATUS_EN "%os" +#define UI_TEXT_EMPTY_EN "" +#define UI_TEXT_TEMP_SET_EN cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_EN cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_EN " %BCmm" +#define UI_TEXT_EXTR3_TEMP_EN "Temp. 4 :%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_EN "Temp. 5 :%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_EN "Temp. 6 :%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_EN "Turn extr. 4 off" +#define UI_TEXT_EXTR4_OFF_EN "Turn extr. 5 off" +#define UI_TEXT_EXTR5_OFF_EN "Turn extr. 6 off" +#define UI_TEXT_EXTR3_SELECT_EN "%X3 Select extr. 4" +#define UI_TEXT_EXTR4_SELECT_EN "%X4 Select extr. 5" +#define UI_TEXT_EXTR5_SELECT_EN "%X5 Select extr. 6" +#define UI_TEXT_DITTO_0_EN "%D0 No copies" +#define UI_TEXT_DITTO_1_EN "%D1 1 copy" +#define UI_TEXT_DITTO_2_EN "%D2 2 copies" +#define UI_TEXT_DITTO_3_EN "%D3 3 copies" +#define UI_TEXT_ZPROBE_HEIGHT_EN "Z-probe height:%zh" + +#define UI_TEXT_OFFSETS_EN "Set print offsets" +#define UI_TEXT_X_OFFSET_EN "Set X offset:%T0mm" +#define UI_TEXT_Y_OFFSET_EN "Set Y offset:%T1mm" +#define UI_TEXT_Z_OFFSET_EN "Set Z offset:%T2mm" -#if UI_DISPLAY_CHARSET==3 // U8glib -#define CHAR_RIGHT 187 //>> -#define CHAR_SELECTOR 255 //'>' -#define CHAR_SELECTED 254 //'*' -#define STR_auml "\344" -#define STR_Auml "\304" -#define STR_uuml "\374" -#define STR_Uuml "\334" -#define STR_ouml "\366" -#define STR_Ouml "\326" -#define STR_szlig "\337" -#endif -#define TEST176 "176\260\261\262\263\264\265\266\267\270\271\272\273\274\275\276\277" -#define TEST192 "192\300\301\302\303\304\305\306\307\310\311\312\313\314\315\316\317" -#define TEST208 "208\320\321\322\323\324\325\326\327\330\331\332\333\334\335\336\337" -#define TEST224 "224\340\341\342\343\344\345\346\347\350\351\352\353\354\355\356\357" + +// *************** German translation **************** + +#define UI_TEXT_ON_DE "An" +#define UI_TEXT_OFF_DE "Aus" +#define UI_TEXT_NA_DE "nv" +#define UI_TEXT_YES_DE "Ja" +#define UI_TEXT_NO_DE "Nein" +#define UI_TEXT_PRINT_POS_DE "Drucke..." +#define UI_TEXT_PRINTING_DE "Drucken" +#define UI_TEXT_IDLE_DE "Leerlauf" +#define UI_TEXT_NOSDCARD_DE "Keine SD Karte" +#define UI_TEXT_ERROR_DE "**** FEHLER ****" +#define UI_TEXT_BACK_DE "Zur" STR_uuml "ck " cUP +#define UI_TEXT_QUICK_SETTINGS_DE "Schnelleinst." +#define UI_TEXT_ERRORMSG_DE "%oe" +#define UI_TEXT_CONFIGURATION_DE "Konfiguration" +#define UI_TEXT_POSITION_DE "Position" +#define UI_TEXT_EXTRUDER_DE "Extruder" +#define UI_TEXT_SD_CARD_DE "SD Karte" +#define UI_TEXT_DEBUGGING_DE "Debugging" +#define UI_TEXT_HOME_DELTA_DE "Home Delta" +#define UI_TEXT_HOME_ALL_DE "Home Alle" +#define UI_TEXT_HOME_X_DE "Home X" +#define UI_TEXT_HOME_Y_DE "Home Y" +#define UI_TEXT_HOME_Z_DE "Home Z" +#define UI_TEXT_PREHEAT_PLA_DE "Vorheizen PLA" +#define UI_TEXT_PREHEAT_ABS_DE "Vorheizen ABS" +#define UI_TEXT_LIGHTS_ONOFF_DE "Lampen: %lo" +#define UI_TEXT_COOLDOWN_DE "Abk" STR_uuml "hlen" +#define UI_TEXT_SET_TO_ORIGIN_DE "Setze Nullpunkt" +#define UI_TEXT_DISABLE_STEPPER_DE "Motoren Aussch." +#define UI_TEXT_X_POSITION_DE "X Position" +#define UI_TEXT_X_POS_FAST_DE "X Pos. Schnell" +#define UI_TEXT_Y_POSITION_DE "Y Position" +#define UI_TEXT_Y_POS_FAST_DE "Y Pos. Schnell" +#define UI_TEXT_Z_POSITION_DE "Z Position" +#define UI_TEXT_Z_POS_FAST_DE "Z Pos. Schnell" +#define UI_TEXT_E_POSITION_DE "Extr. Position" +#define UI_TEXT_BED_TEMP_DE "Bed Temp:%eb/%Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_DE "Temp. 1 :%e0/%E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_DE "Temp. 2 :%e1/%E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_DE "Temp. 3 :%e2/%E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_DE "Extruder 1 Aus" +#define UI_TEXT_EXTR1_OFF_DE "Extruder 2 Aus" +#define UI_TEXT_EXTR2_OFF_DE "Extruder 3 Aus" +#define UI_TEXT_EXTR0_SELECT_DE "%X0 W" STR_auml "hle Extr. 1" +#define UI_TEXT_EXTR1_SELECT_DE "%X1 W" STR_auml "hle Extr. 2" +#define UI_TEXT_EXTR2_SELECT_DE "%X2 W" STR_auml "hle Extr. 3" +#define UI_TEXT_EXTR_ORIGIN_DE "Setze Nullpunkt" +#define UI_TEXT_PRINT_X_DE "Drucken X:%ax" +#define UI_TEXT_PRINT_Y_DE "Drucken Y:%ay" +#define UI_TEXT_PRINT_Z_DE "Drucken Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_DE "Drucken:%az" +#define UI_TEXT_MOVE_X_DE "Bewegen X:%aX" +#define UI_TEXT_MOVE_Y_DE "Bewegen Y:%aY" +#define UI_TEXT_MOVE_Z_DE "Bewegen Z:%aZ" +#define UI_TEXT_MOVE_Z_DELTA_DE "Bewegen:%aZ" +#define UI_TEXT_JERK_DE "Ruck :%aj" +#define UI_TEXT_ZJERK_DE "Z-Ruck :%aJ" +#define UI_TEXT_ACCELERATION_DE "Beschleunigung" +#define UI_TEXT_STORE_TO_EEPROM_DE "Sichere EEPROM" +#define UI_TEXT_LOAD_EEPROM_DE "Lade vom EEPROM" +#define UI_TEXT_DBG_ECHO_DE "Echo :%do" +#define UI_TEXT_DBG_INFO_DE "Info :%di" +#define UI_TEXT_DBG_ERROR_DE "Fehler :%de" +#define UI_TEXT_DBG_DRYRUN_DE "Trockenlauf:%dd" +#define UI_TEXT_OPS_OFF_DE "%O0 OPS Aus" +#define UI_TEXT_OPS_CLASSIC_DE "%O1 OPS Klassisch" +#define UI_TEXT_OPS_FAST_DE "%O2 OPS Schnell" +#define UI_TEXT_OPS_RETRACT_DE "Einfahren :%Or" +#define UI_TEXT_OPS_BACKSLASH_DE "Backsl. :%Ob" +#define UI_TEXT_OPS_MINDIST_DE "Min.Abst. :%Od" +#define UI_TEXT_OPS_MOVE_AFTER_DE "Start nach:%Oa" +#define UI_TEXT_ANTI_OOZE_DE "Anti Ooze" +#define UI_TEXT_PRINT_FILE_DE "Drucke Datei" +#define UI_TEXT_PAUSE_PRINT_DE "Druck Pausieren" +#define UI_TEXT_CONTINUE_PRINT_DE "Druck Forts." +#define UI_TEXT_UNMOUNT_CARD_DE "Unmount Karte" +#define UI_TEXT_MOUNT_CARD_DE "Mount Karte" +#define UI_TEXT_DELETE_FILE_DE "Datei l" STR_ouml "schen" +#define UI_TEXT_FEEDRATE_DE "Feedrate" +#define UI_TEXT_FEED_MAX_X_DE "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_DE "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_DE "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_DE "Max:%fz" +#define UI_TEXT_FEED_HOME_X_DE "Home X:%fX" +#define UI_TEXT_FEED_HOME_Y_DE "Home Y:%fY" +#define UI_TEXT_FEED_HOME_Z_DE "Home Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_DE "Home:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_DE "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_DE "Min Endstopp:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_DE "Max Endstopp:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_DE "" +#define UI_TEXT_ACTION_YPOSITION4A_DE "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_DE "Min Endstopp:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_DE "Max Endstopp:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_DE "" +#define UI_TEXT_ACTION_ZPOSITION4A_DE "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_DE "Min Endstopp:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_DE "Max Endstopp:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_DE "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_DE "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_DE "Min Endstopp:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_DE "Max Endstopp:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_DE "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_DE "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_DE "Min Endstopp:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_DE "Max Endstopp:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_DE "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_DE "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_DE "Min Endstopp:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_DE "Max Endstopp:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_DE "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_DE "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_DE "1 klick = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_DE "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_DE "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_DE "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_DE "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_DE "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_DE "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_DE "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_DE "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_DE "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_DE "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_DE "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_DE "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_DE "L" STR_uuml "fter" +#define UI_TEXT_ACTION_FANSPEED_DE "L" STR_uuml "fter:%Fs%%%" +#define UI_TEXT_FAN_OFF_DE "L" STR_uuml "fter Aus" +#define UI_TEXT_FAN_25_DE "L" STR_uuml "fter auf 25%%%" +#define UI_TEXT_FAN_50_DE "L" STR_uuml "fter auf 50%%%" +#define UI_TEXT_FAN_75_DE "L" STR_uuml "fter auf 75%%%" +#define UI_TEXT_FAN_FULL_DE "L" STR_uuml "fter Voll" +#define UI_TEXT_STEPPER_INACTIVE_DE "Motor Inaktiv" +#define UI_TEXT_STEPPER_INACTIVE2A_DE "Aus nach: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_DE "[min] 0=Aus" +#define UI_TEXT_POWER_INACTIVE_DE "Max. Inaktiv" +#define UI_TEXT_POWER_INACTIVE2A_DE "Aus nach: %ip" +#define UI_TEXT_POWER_INACTIVE2B_DE "[min] 0=Aus" +#define UI_TEXT_GENERAL_DE "Allgemein" +#define UI_TEXT_BAUDRATE_DE "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_DE "Schr/MM:%Se" +#define UI_TEXT_EXTR_START_FEED_DE "Start FR:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_DE "Max FR:%XF" +#define UI_TEXT_EXTR_ACCEL_DE "Beschl.:%XA" +#define UI_TEXT_EXTR_WATCH_DE "Stab.Zeit:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_DE "Advance lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_DE "Advance quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_DE "Regler:%Xh" +#define UI_TEXT_EXTR_PGAIN_DE "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_DE "Totzeit:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_DE "Controll-PWM:%XM" +#define UI_TEXT_EXTR_IGAIN_DE "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_DE "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_DE "Drive Min:%Xm" +#define UI_TEXT_EXTR_DMAX_DE "Drive Max:%XM" +#define UI_TEXT_EXTR_PMAX_DE "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_DE "X-Offset:%Xx" +#define UI_TEXT_EXTR_YOFF_DE "Y-Offset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_DE "BangBang" +#define UI_TEXT_STRING_HM_PID_DE "PID" +#define UI_TEXT_STRING_ACTION_DE "Aktion:%la" +#define UI_TEXT_HEATING_EXTRUDER_DE "Heize Extruder" +#define UI_TEXT_HEATING_BED_DE "Heize Druckbett" +#define UI_TEXT_KILLED_DE "Angehalten" +#define UI_TEXT_STEPPER_DISABLED_DE "Motoren Aus" +#define UI_TEXT_EEPROM_STOREDA_DE "Konfiguration" +#define UI_TEXT_EEPROM_STOREDB_DE "gespeichert." +#define UI_TEXT_EEPROM_LOADEDA_DE "Konfiguration" +#define UI_TEXT_EEPROM_LOADEDB_DE "geladen." +#define UI_TEXT_UPLOADING_DE "Hochladen..." +#define UI_TEXT_PAGE_BUFFER_DE "Puffer:%oB" +#define UI_TEXT_PAGE_EXTRUDER_DE " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_DE "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_DE "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_DE "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_DE " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_DE "Geschw.Mul:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_DE "Flow Mul.:%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_DE "Zeige Messung" +#define UI_TEXT_RESET_MEASUREMENT_DE "Reset Messung" +#define UI_TEXT_SET_MEASURED_ORIGIN_DE "Setze Z=0" +#define UI_TEXT_ZCALIB_DE "Z Kalib." +#define UI_TEXT_SET_P1_DE "Setze P1" +#define UI_TEXT_SET_P2_DE "Setze P2" +#define UI_TEXT_SET_P3_DE "Setze P3" +#define UI_TEXT_CALCULATE_LEVELING_DE "Berechne Leveling" +#define UI_TEXT_LEVEL_DE "Level delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_DE "Wartetemp.%XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_DE "R" STR_uuml "ckz. um:%XU mm" +#define UI_TEXT_SD_REMOVED_DE "SD Karte entfernt" +#define UI_TEXT_SD_INSERTED_DE "SD Karte eingelegt" +#define UI_TEXT_PRINTER_READY_DE "Drucker bereit." +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_DE " Tage " +#define UI_TEXT_PRINTTIME_HOURS_DE ":" +#define UI_TEXT_PRINTTIME_MINUTES_DE "" +#define UI_TEXT_PRINT_TIME_DE "Ges. Druckzeit" +#define UI_TEXT_PRINT_FILAMENT_DE "Filament gedruckt" +#define UI_TEXT_PRINTED_DE "gedruckt" +#define UI_TEXT_POWER_DE "ATX Netzteil an/aus" +#define UI_TEXT_STRING_HM_DEADTIME_DE "Totzeit" +#define UI_TEXT_STRING_HM_SLOWBANG_DE "Langs.BB" +#define UI_TEXT_STOP_PRINT_DE "Druck abbrechen" +#define UI_TEXT_Z_BABYSTEPPING_DE "Z Babyschr.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_DE "Filamentwechsel" +#define UI_TEXT_WIZ_CH_FILAMENT1_DE "Filamentwechsel:" +#define UI_TEXT_WIZ_CH_FILAMENT2_DE "Zum man. f" STR_ouml "rdern" +#define UI_TEXT_WIZ_CH_FILAMENT3_DE "Men" STR_uuml "knopf drehen" +#define UI_TEXT_CLICK_DONE_DE "Weiter mit Klick" +#define UI_TEXT_AUTOLEVEL_ONOFF_DE "Autolevel: %ll" +#define UI_TEXT_SERVOPOS_DE "Servo Pos.: %oS" +#define UI_TEXT_IGNORE_M106_DE "Ignoriere M106 %Fi" +#define UI_TEXT_WIZ_REHEAT1_DE "Klicke zum Aufw" STR_auml "rmen" +#define UI_TEXT_WIZ_REHEAT2_DE "der Extruder." +#define UI_TEXT_WIZ_WAITTEMP1_DE "Warte auf" +#define UI_TEXT_WIZ_WAITTEMP2_DE "Zieltemperatur..." +#define UI_TEXT_EXTRUDER_JAM_DE "Extruderstau" +#define UI_TEXT_STANDBY_DE "Standby" +#define UI_TEXT_BED_COATING_DE "Bettbeschichtung" +#define UI_TEXT_BED_COATING_SET1_DE "Bettbeschichtung:" +#define UI_TEXT_BED_COATING_SET2_DE "" +#define UI_TEXT_NOCOATING_DE "Unbeschichtet" +#define UI_TEXT_BUILDTAK_DE "BuildTak" +#define UI_TEXT_KAPTON_DE "Kapton" +#define UI_TEXT_BLUETAPE_DE "Blaues Kreppband" +#define UI_TEXT_PETTAPE_DE "Gr" STR_uuml "nes PET Band" +#define UI_TEXT_GLUESTICK_DE "Klebestift" +#define UI_TEXT_CUSTOM_DE "Individuell" +#define UI_TEXT_COATING_CUSTOM_DE "Indiv.:%BCmm" +#define UI_TEXT_LANGUAGE_DE "Sprache" + +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_DE "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_DE "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_DE "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_DE "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_DE " Y:%x1" +#endif +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_DE "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_DE "Kopien: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_DE "Fluss:\xfd %of%%% Z:%x2" +#endif +#define UI_TEXT_MAINPAGE6_4_DE "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_DE "Puf: %oB" +#define UI_TEXT_MAINPAGE6_6_DE "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_DE cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_DE "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_DE "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_DE "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_DE "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_DE "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_DE "%Uf m" +#define UI_TEXT_METER_PRINTED_DE "%Uf m " UI_TEXT_PRINTED_DE +#define UI_TEXT_STATUS_DE "%os" +#define UI_TEXT_EMPTY_DE "" +#define UI_TEXT_TEMP_SET_DE cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_DE cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_DE " %BCmm" +#define UI_TEXT_EXTR3_TEMP_DE "Temp. 4 :%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_DE "Temp. 5 :%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_DE "Temp. 6 :%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_DE "Extruder 4 Aus" +#define UI_TEXT_EXTR4_OFF_DE "Extruder 5 Aus" +#define UI_TEXT_EXTR5_OFF_DE "Extruder 6 Aus" +#define UI_TEXT_EXTR3_SELECT_DE "%X3 W" STR_auml "hle Extr. 4" +#define UI_TEXT_EXTR4_SELECT_DE "%X4 W" STR_auml "hle Extr. 5" +#define UI_TEXT_EXTR5_SELECT_DE "%X5 W" STR_auml "hle Extr. 6" +#define UI_TEXT_DITTO_0_DE "%D0 Keine Kopien" +#define UI_TEXT_DITTO_1_DE "%D1 1 Kopie" +#define UI_TEXT_DITTO_2_DE "%D2 2 Kopien" +#define UI_TEXT_DITTO_3_DE "%D3 3 Kopien" +#define UI_TEXT_ZPROBE_HEIGHT_DE "Z-Probenh" STR_ouml "he:%zh" + + + +#define UI_TEXT_OFFSETS_DE "Set print offsets" +#define UI_TEXT_X_OFFSET_DE "X-Offset:%T0mm" +#define UI_TEXT_Y_OFFSET_DE "Y-Offset:%T1mm" +#define UI_TEXT_Z_OFFSET_DE "Z-Offset:%T2mm" -// 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. +// Dutch translation + +#define UI_TEXT_ON_NL "Aan" +#define UI_TEXT_OFF_NL "Uit" +#define UI_TEXT_NA_NL "N/A" // Output for not available +#define UI_TEXT_YES_NL "Ja" +#define UI_TEXT_NO_NL "Nee" +#define UI_TEXT_PRINT_POS_NL "Printen..." +#define UI_TEXT_PRINTING_NL "Printen" +#define UI_TEXT_IDLE_NL "Rust" +#define UI_TEXT_NOSDCARD_NL "Geen SD Kaart" +#define UI_TEXT_ERROR_NL "**** FOUT ****" +#define UI_TEXT_BACK_NL "Terug " cUP +#define UI_TEXT_QUICK_SETTINGS_NL "Snel Instelling" +#define UI_TEXT_ERRORMSG_NL "%oe" +#define UI_TEXT_CONFIGURATION_NL "Configuratie" +#define UI_TEXT_POSITION_NL "Positie" +#define UI_TEXT_EXTRUDER_NL "Extruder" +#define UI_TEXT_SD_CARD_NL "SD Kaart" +#define UI_TEXT_DEBUGGING_NL "Debugging" +#define UI_TEXT_HOME_DELTA_NL "Home Delta" +#define UI_TEXT_HOME_ALL_NL "Home Alles" +#define UI_TEXT_HOME_X_NL "Home X" +#define UI_TEXT_HOME_Y_NL "Home Y" +#define UI_TEXT_HOME_Z_NL "Home Z" +#define UI_TEXT_PREHEAT_PLA_NL "Voorverwarmen PLA" +#define UI_TEXT_PREHEAT_ABS_NL "Voorverwarmen ABS" +#define UI_TEXT_LIGHTS_ONOFF_NL "Lichten:%lo" +#define UI_TEXT_COOLDOWN_NL "Koelen" +#define UI_TEXT_SET_TO_ORIGIN_NL "Zet oorsprong" +#define UI_TEXT_DISABLE_STEPPER_NL "Zet motor uit" +#define UI_TEXT_X_POSITION_NL "X Positie" +#define UI_TEXT_X_POS_FAST_NL "X Pos. Snel" +#define UI_TEXT_Y_POSITION_NL "Y Positie" +#define UI_TEXT_Y_POS_FAST_NL "Y Pos. Snel" +#define UI_TEXT_Z_POSITION_NL "Z Positie" +#define UI_TEXT_Z_POS_FAST_NL "Z Pos. Snel" +#define UI_TEXT_E_POSITION_NL "Extr. positie" +#define UI_TEXT_BED_TEMP_NL "Bed Temp:%eb/%Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_NL "Temp. 1 :%e0/%E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_NL "Temp. 2 :%e1/%E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_NL "Temp. 3 :%e2/%E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_NL "Extruder 1 Uit" +#define UI_TEXT_EXTR1_OFF_NL "Extruder 2 Uit" +#define UI_TEXT_EXTR2_OFF_NL "Extruder 3 Uit" +#define UI_TEXT_EXTR0_SELECT_NL "%X0 Select Extr. 1" +#define UI_TEXT_EXTR1_SELECT_NL "%X1 Select Extr. 2" +#define UI_TEXT_EXTR2_SELECT_NL "%X2 Select Extr. 3" +#define UI_TEXT_EXTR_ORIGIN_NL "Zet oorsprong" +#define UI_TEXT_PRINT_X_NL "Print X:%ax" +#define UI_TEXT_PRINT_Y_NL "Print Y:%ay" +#define UI_TEXT_PRINT_Z_NL "Print Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_NL "Print:%az" +#define UI_TEXT_MOVE_X_NL "Beweeg X:%aX" +#define UI_TEXT_MOVE_Y_NL "Beweeg Y:%aY" +#define UI_TEXT_MOVE_Z_NL "Beweeg Z:%aZ" +#define UI_TEXT_MOVE_Z_DELTA_NL "Beweeg:%aZ" +#define UI_TEXT_JERK_NL "Ruk:%aj" +#define UI_TEXT_ZJERK_NL "Z-Ruk:%aJ" +#define UI_TEXT_ACCELERATION_NL "Acceleratie" +#define UI_TEXT_STORE_TO_EEPROM_NL "Opslaan n. EEPROM" +#define UI_TEXT_LOAD_EEPROM_NL "Ladd f. EEPROM" +#define UI_TEXT_DBG_ECHO_NL "Echo :%do" +#define UI_TEXT_DBG_INFO_NL "Info :%di" +#define UI_TEXT_DBG_ERROR_NL "Fouten :%de" +#define UI_TEXT_DBG_DRYRUN_NL "Droogloop:%dd" +#define UI_TEXT_OPS_OFF_NL "%O0 OPS Uit" +#define UI_TEXT_OPS_CLASSIC_NL "%O1 OPS Klassiek" +#define UI_TEXT_OPS_FAST_NL "%O2 OPS Snel" +#define UI_TEXT_OPS_RETRACT_NL "Terugtrekken:%Or" +#define UI_TEXT_OPS_BACKSLASH_NL "Backsl. :%Ob" +#define UI_TEXT_OPS_MINDIST_NL "Min. afstand:%Od" +#define UI_TEXT_OPS_MOVE_AFTER_NL "Beweeg na:%Oa" +#define UI_TEXT_ANTI_OOZE_NL "Anti lekken" +#define UI_TEXT_PRINT_FILE_NL "Print bestand" +#define UI_TEXT_PAUSE_PRINT_NL "Pauzeer Print" +#define UI_TEXT_CONTINUE_PRINT_NL "Zet print voort" +#define UI_TEXT_UNMOUNT_CARD_NL "Ontkoppel Kaart" +#define UI_TEXT_MOUNT_CARD_NL "Koppel Kaart" +#define UI_TEXT_DELETE_FILE_NL "Verw. bestand" +#define UI_TEXT_FEEDRATE_NL "Beweeg snelheid" +#define UI_TEXT_FEED_MAX_X_NL "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_NL "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_NL "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_NL "Max:%fz" +#define UI_TEXT_FEED_HOME_X_NL "Home X:%fX" +#define UI_TEXT_FEED_HOME_Y_NL "Home Y:%fY" +#define UI_TEXT_FEED_HOME_Z_NL "Home Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_NL "Home:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_NL "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_NL "Min eindst.:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_NL "Max eindst.:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_NL "" +#define UI_TEXT_ACTION_YPOSITION4A_NL "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_NL "Min eindst.:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_NL "Max eindst.:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_NL "" +#define UI_TEXT_ACTION_ZPOSITION4A_NL "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_NL "Min eindst.:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_NL "Max eindst.:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_NL "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_NL "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_NL "Min eindst.:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_NL "Max eindst.:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_NL "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_NL "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_NL "Min eindst.:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_NL "Max eindst.:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_NL "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_NL "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_NL "Min eindst.:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_NL "Max eindst.:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_NL "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_NL "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_NL "1 klik = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_NL "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_NL "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_NL "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_NL "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_NL "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_NL "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_NL "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_NL "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_NL "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_NL "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_NL "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_NL "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_NL "Fan snelheid" +#define UI_TEXT_FAN_OFF_NL "Zet Fan uit" +#define UI_TEXT_ACTION_FANSPEED_NL "Fan snelheid:%Fs%%%" +#define UI_TEXT_FAN_25_NL "Zet Fan 25%%%" +#define UI_TEXT_FAN_50_NL "Zet Fan 50%%%" +#define UI_TEXT_FAN_75_NL "Zet Fan 75%%%" +#define UI_TEXT_FAN_FULL_NL "Zet Fan Vol aan" +#define UI_TEXT_STEPPER_INACTIVE_NL "Motor Inactief" +#define UI_TEXT_STEPPER_INACTIVE2A_NL "Uit na: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_NL "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_NL "Max. Inactief" +#define UI_TEXT_POWER_INACTIVE2A_NL "Zet uit na: %ip" +#define UI_TEXT_POWER_INACTIVE2B_NL "[min] 0=Off" +#define UI_TEXT_GENERAL_NL "Algemeen" +#define UI_TEXT_BAUDRATE_NL "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_NL "Stappen/MM:%Se" +#define UI_TEXT_EXTR_START_FEED_NL "Start FR.:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_NL "Max FR.:%XF" +#define UI_TEXT_EXTR_ACCEL_NL "Accel:%XA" +#define UI_TEXT_EXTR_WATCH_NL "Stab.Tijd:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_NL "Advance lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_NL "Advance quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_NL "Control:%Xh" +#define UI_TEXT_EXTR_PGAIN_NL "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_NL "Dode tijd:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_NL "Controle PWM:%XM" +#define UI_TEXT_EXTR_IGAIN_NL "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_NL "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_NL "Drive Min:%Xm" +#define UI_TEXT_EXTR_DMAX_NL "Drive Max:%XM" +#define UI_TEXT_EXTR_PMAX_NL "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_NL "X-Offset:%Xx" +#define UI_TEXT_EXTR_YOFF_NL "Y-Offset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_NL "BangBang" +#define UI_TEXT_STRING_HM_PID_NL "PID" +#define UI_TEXT_STRING_ACTION_NL "Action:%la" +#define UI_TEXT_HEATING_EXTRUDER_NL "Opwarmen Extru." +#define UI_TEXT_HEATING_BED_NL "Opwarmen Bed" +#define UI_TEXT_KILLED_NL "Uitgeschakeld" +#define UI_TEXT_STEPPER_DISABLED_NL "Motor uitgezet" +#define UI_TEXT_EEPROM_STOREDA_NL "Configuratie" +#define UI_TEXT_EEPROM_STOREDB_NL "saved. in EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_NL "Configuratie" +#define UI_TEXT_EEPROM_LOADEDB_NL "loaded f. EEPROM" +#define UI_TEXT_UPLOADING_NL "Uploaden..." +#define UI_TEXT_PAGE_BUFFER_NL "Buffer:%oB" +#define UI_TEXT_PAGE_EXTRUDER_NL " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_NL "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_NL "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_NL "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_NL " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_NL "Snelh. Mul.:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_NL "Flow Mul.:%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_NL "Show meting" +#define UI_TEXT_RESET_MEASUREMENT_NL "Reset meting" +#define UI_TEXT_SET_MEASURED_ORIGIN_NL "Set Z=0" +#define UI_TEXT_ZCALIB_NL "Z Calib." +#define UI_TEXT_SET_P1_NL "Set P1" +#define UI_TEXT_SET_P2_NL "Set P2" +#define UI_TEXT_SET_P3_NL "Set P3" +#define UI_TEXT_CALCULATE_LEVELING_NL "Bereken Leveling" +#define UI_TEXT_LEVEL_NL "Level delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_NL "Wacht Temp. %XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_NL "Wacht Retr.:%XU mm" +#define UI_TEXT_SD_REMOVED_NL "SD-kaart verwijderd" +#define UI_TEXT_SD_INSERTED_NL "SD-kaart geplaatst" +#define UI_TEXT_PRINTER_READY_NL "Printer klaar." +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_NL " dagen " +#define UI_TEXT_PRINTTIME_HOURS_NL ":" +#define UI_TEXT_PRINTTIME_MINUTES_NL "" +#define UI_TEXT_PRINT_TIME_NL "Printing tijd" +#define UI_TEXT_PRINT_FILAMENT_NL "Filament gedrukt" +#define UI_TEXT_PRINTED_NL "gedrukt" +#define UI_TEXT_POWER_NL "ATX power aan/uit" +#define UI_TEXT_STRING_HM_DEADTIME_NL "Dode tijd" +#define UI_TEXT_STRING_HM_SLOWBANG_NL "SlowBang" +#define UI_TEXT_STOP_PRINT_NL "Stop Print" +#define UI_TEXT_Z_BABYSTEPPING_NL "Z Babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_NL "Ruil filament" +#define UI_TEXT_WIZ_CH_FILAMENT1_NL "Ruil filament:" +#define UI_TEXT_WIZ_CH_FILAMENT2_NL "Draaien voor" +#define UI_TEXT_WIZ_CH_FILAMENT3_NL "filament op/omlaag" +#define UI_TEXT_CLICK_DONE_NL "Verder met klik" +#define UI_TEXT_AUTOLEVEL_ONOFF_NL "Autolevel: %ll" +#define UI_TEXT_SERVOPOS_NL "Servo-pos.: %oS" +#define UI_TEXT_IGNORE_M106_NL "Negeer M106 %Fi" +#define UI_TEXT_WIZ_REHEAT1_NL "Klik om extruder" +#define UI_TEXT_WIZ_REHEAT2_NL "verwarmen." +#define UI_TEXT_WIZ_WAITTEMP1_NL "Wachten op" +#define UI_TEXT_WIZ_WAITTEMP2_NL "doeltemperatuur..." +#define UI_TEXT_EXTRUDER_JAM_NL "Extruder jam" +#define UI_TEXT_STANDBY_NL "Standby" +#define UI_TEXT_BED_COATING_NL "Bed bedekking" +#define UI_TEXT_BED_COATING_SET1_NL "Bed bedekking set to" +#define UI_TEXT_BED_COATING_SET2_NL "" +#define UI_TEXT_NOCOATING_NL "Geen bedekking" +#define UI_TEXT_BUILDTAK_NL "BuildTak" +#define UI_TEXT_KAPTON_NL "Kapton" +#define UI_TEXT_BLUETAPE_NL "Blauw afplakband" +#define UI_TEXT_PETTAPE_NL "Groene PET Tape" +#define UI_TEXT_GLUESTICK_NL "Lijmstift" +#define UI_TEXT_CUSTOM_NL "Custom" +#define UI_TEXT_COATING_CUSTOM_NL "Custom:%BCmm" +#define UI_TEXT_LANGUAGE_NL "Taal" + +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_NL "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_NL "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_NL "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_NL "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_NL " Y:%x1" +#endif +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_NL "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_NL "Kopieen: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_NL "Flow:\xfd %of%%% Z:%x2" +#endif +#define UI_TEXT_MAINPAGE6_4_NL "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_NL "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_NL "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_NL cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_NL "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_NL "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_NL "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_NL "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_NL "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_NL "%Uf m" +#define UI_TEXT_METER_PRINTED_NL "%Uf m " UI_TEXT_PRINTED_NL +#define UI_TEXT_STATUS_NL "%os" +#define UI_TEXT_EMPTY_NL "" +#define UI_TEXT_TEMP_SET_NL cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_NL cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_NL " %BCmm" +#define UI_TEXT_EXTR3_TEMP_NL "Temp. 4 :%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_NL "Temp. 5 :%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_NL "Temp. 6 :%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_NL "Extruder 4 Uit" +#define UI_TEXT_EXTR4_OFF_NL "Extruder 5 Uit" +#define UI_TEXT_EXTR5_OFF_NL "Extruder 6 Uit" +#define UI_TEXT_EXTR3_SELECT_NL "%X3 Select Extr. 4" +#define UI_TEXT_EXTR4_SELECT_NL "%X4 Select Extr. 5" +#define UI_TEXT_EXTR5_SELECT_NL "%X5 Select Extr. 6" +#define UI_TEXT_DITTO_0_NL "%D0 Geen Kopieen" +#define UI_TEXT_DITTO_1_NL "%D1 1 Kopie" +#define UI_TEXT_DITTO_2_NL "%D2 2 Kopieen" +#define UI_TEXT_DITTO_3_NL "%D3 3 Kopieen" +#define UI_TEXT_ZPROBE_HEIGHT_NL "z-probe hoogte:%zh" + + -#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 cSEL -#define UI_TEXT_NOSEL cUNSEL -#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 " cUP -#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_LIGHTS_ONOFF "Lights :%lo" -#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" cDEG "C" -#define UI_TEXT_EXTR0_TEMP "Temp. 1 : %E0" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 2 : %E1" cDEG "C" -#define UI_TEXT_EXTR2_TEMP "Temp. 3 : %E2" cDEG "C" -#define UI_TEXT_EXTR0_OFF "Turn Extr. 1 Off" -#define UI_TEXT_EXTR1_OFF "Turn Extr. 2 Off" -#define UI_TEXT_EXTR2_OFF "Turn Extr. 3 Off" -#define UI_TEXT_EXTR0_SELECT "%X0 Select Extr. 1" -#define UI_TEXT_EXTR1_SELECT "%X1 Select Extr. 2" -#define UI_TEXT_EXTR2_SELECT "%X2 Select Extr. 3" -#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_PRINT_Z_DELTA "Print:%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_MOVE_Z_DELTA "Move:%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_MAX_Z_DELTA "Max:%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_FEED_HOME_Z_DELTA "Home:%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_ACTION_FANSPEED "Fan speed:%Fs%%%" -#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","[min] 0=Off" -#define UI_TEXT_POWER_INACTIVE "Max. Inactive" -#define UI_TEXT_POWER_INACTIVE2 "Dis. After: %ip","[min] 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_DEADTIME "Deadtime:%Xp" -#define UI_TEXT_EXTR_DMAX_DT "Control PWM:%XM" -#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" cDEG "C" cARROW "%oC" -#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0" cDEG "C" cARROW "%o0" -#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1" cDEG "C" cARROW "%o1" -#define UI_TEXT_PAGE_EXTRUDER3 "E3:%e2/%E2" cDEG "C" cARROW "%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb" cDEG "C" cARROW "%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 Z=0" -#define UI_TEXT_ZCALIB "Z 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" cDEG "C" -#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." +#define UI_TEXT_OFFSETS_NL "Set print offsets" +#define UI_TEXT_X_OFFSET_NL "Set X offset:%T0mm" +#define UI_TEXT_Y_OFFSET_NL "Set Y offset:%T1mm" +#define UI_TEXT_Z_OFFSET_NL "Set Z offset:%T2mm" + + +// *************** Brazilian portuguese translation **************** + +#define UI_TEXT_ON_PT "On" +#define UI_TEXT_OFF_PT "Off" +#define UI_TEXT_NA_PT "N/A" // Output for not available +#define UI_TEXT_YES_PT "Sim" +#define UI_TEXT_NO_PT "Não" +#define UI_TEXT_SEL_PT cSEL +#define UI_TEXT_NOSEL_PT cUNSEL +#define UI_TEXT_PRINT_POS_PT "Imprimindo..." +#define UI_TEXT_PRINTING_PT "Imprimindo" +#define UI_TEXT_IDLE_PT "Ocioso" +#define UI_TEXT_NOSDCARD_PT "Nenhum cartao SD" +#define UI_TEXT_ERROR_PT "**** ERRO ****" +#define UI_TEXT_BACK_PT "Voltar " cUP +#define UI_TEXT_QUICK_SETTINGS_PT "Configuracoes Rapidas" +#define UI_TEXT_ERRORMSG_PT "%oe" +#define UI_TEXT_CONFIGURATION_PT "Configuracao" +#define UI_TEXT_POSITION_PT "Posicao" +#define UI_TEXT_EXTRUDER_PT "Extrusor" +#define UI_TEXT_SD_CARD_PT "Cartao SD" +#define UI_TEXT_DEBUGGING_PT "Depuracao" +#define UI_TEXT_HOME_DELTA_PT "Home delta" +#define UI_TEXT_HOME_ALL_PT "Home todos" +#define UI_TEXT_HOME_X_PT "Home X" +#define UI_TEXT_HOME_Y_PT "Home Y" +#define UI_TEXT_HOME_Z_PT "Home Z" +#define UI_TEXT_PREHEAT_PLA_PT "Pre-aquecer PLA" +#define UI_TEXT_PREHEAT_ABS_PT "Pre-aquecer ABS" +#define UI_TEXT_LIGHTS_ONOFF_PT "Luzes:%lo" +#define UI_TEXT_COOLDOWN_PT "Resfriar" +#define UI_TEXT_SET_TO_ORIGIN_PT "Definir como origem" +#define UI_TEXT_DISABLE_STEPPER_PT "Desabilitar motor" +#define UI_TEXT_X_POSITION_PT "Posicao X" +#define UI_TEXT_X_POS_FAST_PT "Pos. Rapida X" +#define UI_TEXT_Y_POSITION_PT "Posicao Y" +#define UI_TEXT_Y_POS_FAST_PT "Pos. Rapida Y" +#define UI_TEXT_Z_POSITION_PT "Posicao Z" +#define UI_TEXT_Z_POS_FAST_PT "Pos. Rapida Z" +#define UI_TEXT_E_POSITION_PT "Posicao Extrusor" +#define UI_TEXT_BED_TEMP_PT "Tem.Cama:%eb/%Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_PT "Temp. 1 :%e0/%E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_PT "Temp. 2 :%e1/%E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_PT "Temp. 3 :%e2/%E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_PT "Extr. 1 Desligado" +#define UI_TEXT_EXTR1_OFF_PT "Extr. 2 Desligado" +#define UI_TEXT_EXTR2_OFF_PT "Extr. 3 Desligado" +#define UI_TEXT_EXTR0_SELECT_PT "%X0 Sel. Extr. 1" +#define UI_TEXT_EXTR1_SELECT_PT "%X1 Sel. Extr. 2" +#define UI_TEXT_EXTR2_SELECT_PT "%X2 Sel. Extr. 3" +#define UI_TEXT_EXTR_ORIGIN_PT "Definir Origem" +#define UI_TEXT_PRINT_X_PT "Imprimir X:%ax" +#define UI_TEXT_PRINT_Y_PT "Imprimir Y:%ay" +#define UI_TEXT_PRINT_Z_PT "Imprimir Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_PT "Imprimir:%az" +#define UI_TEXT_MOVE_X_PT "Mover X:%aX" +#define UI_TEXT_MOVE_Y_PT "Mover Y:%aY" +#define UI_TEXT_MOVE_Z_PT "Mover Z:%aZ" +#define UI_TEXT_MOVE_Z_DELTA_PT "Mover:%aZ" +#define UI_TEXT_JERK_PT "Jerk:%aj" +#define UI_TEXT_ZJERK_PT "Z-Jerk:%aJ" +#define UI_TEXT_ACCELERATION_PT "Aceleracao" +#define UI_TEXT_STORE_TO_EEPROM_PT "Armazenar na EEPROM" +#define UI_TEXT_LOAD_EEPROM_PT "Carregar da EEPROM" +#define UI_TEXT_DBG_ECHO_PT "Echo :%do" +#define UI_TEXT_DBG_INFO_PT "Info :%di" +#define UI_TEXT_DBG_ERROR_PT "Erros :%de" +#define UI_TEXT_DBG_DRYRUN_PT "Dry run:%dd" +#define UI_TEXT_OPS_OFF_PT "%O0 OPS Off" +#define UI_TEXT_OPS_CLASSIC_PT "%O1 OPS Classic" +#define UI_TEXT_OPS_FAST_PT "%O2 OPS Fast" +#define UI_TEXT_OPS_RETRACT_PT "Retract :%Or" +#define UI_TEXT_OPS_BACKSLASH_PT "Backsl. :%Ob" +#define UI_TEXT_OPS_MINDIST_PT "Min.dist:%Od" +#define UI_TEXT_OPS_MOVE_AFTER_PT "Move after:%Oa" +#define UI_TEXT_ANTI_OOZE_PT "Anti Ooze" +#define UI_TEXT_PRINT_FILE_PT "Imprimir arquivo" +#define UI_TEXT_PAUSE_PRINT_PT "Pausar Impressao" +#define UI_TEXT_CONTINUE_PRINT_PT "Continuar Impressao" +#define UI_TEXT_UNMOUNT_CARD_PT "Desmontar Cartao" +#define UI_TEXT_MOUNT_CARD_PT "Montar Cartao" +#define UI_TEXT_DELETE_FILE_PT "Deletar arquivo" +#define UI_TEXT_FEEDRATE_PT "Feedrate" +#define UI_TEXT_FEED_MAX_X_PT "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_PT "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_PT "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_PT "Max:%fz" +#define UI_TEXT_FEED_HOME_X_PT "Home X:%fX" +#define UI_TEXT_FEED_HOME_Y_PT "Home Y:%fY" +#define UI_TEXT_FEED_HOME_Z_PT "Home Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_PT "Home:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_PT "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_PT "Min endstop:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_PT "Max endstop:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_PT "" +#define UI_TEXT_ACTION_YPOSITION4A_PT "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_PT "Min endstop:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_PT "Max endstop:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_PT "" +#define UI_TEXT_ACTION_ZPOSITION4A_PT "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_PT "Min endstop:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_PT "Max endstop:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_PT "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_PT "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_PT "Min endstop:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_PT "Max endstop:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_PT "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_PT "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_PT "Min endstop:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_PT "Max endstop:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_PT "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_PT "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_PT "Min endstop:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_PT "Max endstop:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_PT "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_PT "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_PT "1 click = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_PT "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_PT "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_PT "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_PT "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_PT "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_PT "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_PT "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_PT "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_PT "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_PT "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_PT "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_PT "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_PT "Velocidade ventoinha" +#define UI_TEXT_ACTION_FANSPEED_PT "Vel. vent.:%Fs%%%" +#define UI_TEXT_FAN_OFF_PT "Desligar ventoinha" +#define UI_TEXT_FAN_25_PT "Def. ventoinha 25%%%" +#define UI_TEXT_FAN_50_PT "Def. ventoinha 50%%%" +#define UI_TEXT_FAN_75_PT "Def. ventoinha 75%%%" +#define UI_TEXT_FAN_FULL_PT "Def. ventoinha 100%%%" +#define UI_TEXT_STEPPER_INACTIVE_PT "Motor Inativo" +#define UI_TEXT_STEPPER_INACTIVE2A_PT "Des. Depois: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_PT "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_PT "Max. Inativo" +#define UI_TEXT_POWER_INACTIVE2A_PT "Des. Depois: %ip" +#define UI_TEXT_POWER_INACTIVE2B_PT "[min] 0=Off" +#define UI_TEXT_GENERAL_PT "Geral" +#define UI_TEXT_BAUDRATE_PT "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_PT "Passos/mm:%Se" +#define UI_TEXT_EXTR_START_FEED_PT "Iniciar FR:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_PT "Max FR:%XF" +#define UI_TEXT_EXTR_ACCEL_PT "Accel:%XA" +#define UI_TEXT_EXTR_WATCH_PT "Stab.Time:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_PT "Advance lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_PT "Advance quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_PT "Controle:%Xh" +#define UI_TEXT_EXTR_PGAIN_PT "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_PT "Tempo morto:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_PT "Controle PWM:%XM" +#define UI_TEXT_EXTR_IGAIN_PT "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_PT "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_PT "Drive Min:%Xm" +#define UI_TEXT_EXTR_DMAX_PT "Drive Max:%XM" +#define UI_TEXT_EXTR_PMAX_PT "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_PT "Offset X:%Xx" +#define UI_TEXT_EXTR_YOFF_PT "Offset Y:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_PT "BangBang" +#define UI_TEXT_STRING_HM_PID_PT "PID" +#define UI_TEXT_STRING_ACTION_PT "Acao:%la" +#define UI_TEXT_HEATING_EXTRUDER_PT "Aquecendo Extrusor" +#define UI_TEXT_HEATING_BED_PT "Aquecendo Cama" +#define UI_TEXT_KILLED_PT "Killed" +#define UI_TEXT_STEPPER_DISABLED_PT "Motor Desabilitado" +#define UI_TEXT_EEPROM_STOREDA_PT "Configuracao" +#define UI_TEXT_EEPROM_STOREDB_PT "armazenada na EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_PT "Configuracao" +#define UI_TEXT_EEPROM_LOADEDB_PT "carregada da EEPROM" +#define UI_TEXT_UPLOADING_PT "Enviando..." +#define UI_TEXT_PAGE_BUFFER_PT "Buffer:%oB" +#define UI_TEXT_PAGE_EXTRUDER_PT " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_PT "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_PT "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_PT "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_PT " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_PT "Mult. Veloc.:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_PT "Mult. Fluxo:%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_PT "Mostrar medicao" +#define UI_TEXT_RESET_MEASUREMENT_PT "Reset medicao" +#define UI_TEXT_SET_MEASURED_ORIGIN_PT "Set Z=0" +#define UI_TEXT_ZCALIB_PT "Z calib." +#define UI_TEXT_SET_P1_PT "Set P1" +#define UI_TEXT_SET_P2_PT "Set P2" +#define UI_TEXT_SET_P3_PT "Set P3" +#define UI_TEXT_CALCULATE_LEVELING_PT "Calcule nivelamento" +#define UI_TEXT_LEVEL_PT "Nivel delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_PT "Aguardar Temp.%XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_PT "Aguardar Unidades:%XUmm" +#define UI_TEXT_SD_REMOVED_PT "Cartao SD removido" +#define UI_TEXT_SD_INSERTED_PT "Cartao SD inserido" +#define UI_TEXT_PRINTER_READY_PT "Impressora pronta." +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_PT " dias " +#define UI_TEXT_PRINTTIME_HOURS_PT ":" +#define UI_TEXT_PRINTTIME_MINUTES_PT "" +#define UI_TEXT_PRINT_TIME_PT "tempo de impressao" +#define UI_TEXT_PRINT_FILAMENT_PT "Filament impresso" +#define UI_TEXT_PRINTED_PT "impresso" +#define UI_TEXT_POWER_PT "ATX poder on/off" +#define UI_TEXT_STRING_HM_DEADTIME_PT "Tempo morto" +#define UI_TEXT_STRING_HM_SLOWBANG_PT "SlowBang" +#define UI_TEXT_STOP_PRINT_PT "Parar impressao" +#define UI_TEXT_Z_BABYSTEPPING_PT "Z babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_PT "Alterar filamento" +#define UI_TEXT_WIZ_CH_FILAMENT1_PT "Alterar filamento" +#define UI_TEXT_WIZ_CH_FILAMENT2_PT "Gire para mover" +#define UI_TEXT_WIZ_CH_FILAMENT3_PT "filamento cima/baixo" +#define UI_TEXT_CLICK_DONE_PT "Clique quando feito" +#define UI_TEXT_AUTOLEVEL_ONOFF_PT "Nivel auto: %ll" +#define UI_TEXT_SERVOPOS_PT "Pos. servo: %oS" +#define UI_TEXT_IGNORE_M106_PT "Ignorar M106 %Fi" +#define UI_TEXT_WIZ_REHEAT1_PT "Clique para" +#define UI_TEXT_WIZ_REHEAT2_PT "aquecer extrusora." +#define UI_TEXT_WIZ_WAITTEMP1_PT "Aguardando a" +#define UI_TEXT_WIZ_WAITTEMP2_PT "temperatura alvo ..." +#define UI_TEXT_EXTRUDER_JAM_PT "Extrusora congest." +#define UI_TEXT_STANDBY_PT "Standby" +#define UI_TEXT_BED_COATING_PT "Revest. de leito" +#define UI_TEXT_BED_COATING_SET1_PT "Revest. de leito:" +#define UI_TEXT_BED_COATING_SET2_PT "" +#define UI_TEXT_NOCOATING_PT "Sem revestimento" +#define UI_TEXT_BUILDTAK_PT "BuildTak" +#define UI_TEXT_KAPTON_PT "Kapton" +#define UI_TEXT_BLUETAPE_PT "Fita crepe azul" +#define UI_TEXT_PETTAPE_PT "Fita verde PET" +#define UI_TEXT_GLUESTICK_PT "Cola bastao" +#define UI_TEXT_CUSTOM_PT "Personalizadas" +#define UI_TEXT_COATING_CUSTOM_PT "Person.:%BCmm" +#define UI_TEXT_LANGUAGE_PT "Idioma" + +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_PT "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_PT "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_PT "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_PT "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_PT " Y:%x1" +#endif +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_PT "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_PT "Copias: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_PT "Fluxo:\xfd %of%%% Z:%x2" +#endif +#define UI_TEXT_MAINPAGE6_4_PT "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_PT "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_PT "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_PT cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_PT "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_PT "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_PT "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_PT "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_PT "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_PT "%Uf m" +#define UI_TEXT_METER_PRINTED_PT "%Uf m " UI_TEXT_PRINTED_EN +#define UI_TEXT_STATUS_PT "%os" +#define UI_TEXT_EMPTY_PT "" +#define UI_TEXT_TEMP_SET_PT cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_PT cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_PT " %BCmm" +#define UI_TEXT_EXTR3_TEMP_PT "Temp. 4 :%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_PT "Temp. 5 :%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_PT "Temp. 6 :%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_PT "Extr. 4 Desligado" +#define UI_TEXT_EXTR4_OFF_PT "Extr. 5 Desligado" +#define UI_TEXT_EXTR5_OFF_PT "Extr. 6 Desligado" +#define UI_TEXT_EXTR3_SELECT_PT "%X3 Sel. Extr. 4" +#define UI_TEXT_EXTR4_SELECT_PT "%X4 Sel. Extr. 5" +#define UI_TEXT_EXTR5_SELECT_PT "%X5 Sel. Extr. 6" +#define UI_TEXT_DITTO_0_PT "%D0 Nenhuma Copia" +#define UI_TEXT_DITTO_1_PT "%D1 1 Copia" +#define UI_TEXT_DITTO_2_PT "%D2 2 Copias" +#define UI_TEXT_DITTO_3_PT "%D3 3 Copias" +#define UI_TEXT_ZPROBE_HEIGHT_PT "Altura Z-Probe:%zh" + + + +#define UI_TEXT_OFFSETS_PT "Set print offsets" +#define UI_TEXT_X_OFFSET_PT "Set X offset:%T0mm" +#define UI_TEXT_Y_OFFSET_PT "Set Y offset:%T1mm" +#define UI_TEXT_Z_OFFSET_PT "Set Z offset:%T2mm" + + +// *************** Italian translation **************** + +#define UI_TEXT_ON_IT "On" +#define UI_TEXT_OFF_IT "Off" +#define UI_TEXT_NA_IT "N/A" // Output for not available +#define UI_TEXT_YES_IT "Si" +#define UI_TEXT_NO_IT "No" +#define UI_TEXT_PRINT_POS_IT "Stampa..." +#define UI_TEXT_PRINTING_IT "Stampa" +#define UI_TEXT_IDLE_IT "Pausa" +#define UI_TEXT_NOSDCARD_IT "No Scheda SD" +#define UI_TEXT_ERROR_IT "**** ERRORE ****" +#define UI_TEXT_BACK_IT "Indietro " cUP +#define UI_TEXT_QUICK_SETTINGS_IT "Impostazioni veloci" +#define UI_TEXT_ERRORMSG_IT "%oe" +#define UI_TEXT_CONFIGURATION_IT "Configurazione" +#define UI_TEXT_POSITION_IT "Posizione" +#define UI_TEXT_EXTRUDER_IT "Estrusore" +#define UI_TEXT_SD_CARD_IT "Scheda SD" +#define UI_TEXT_DEBUGGING_IT "Sviluppo" +#define UI_TEXT_HOME_DELTA_IT "Origine Delta" +#define UI_TEXT_HOME_ALL_IT "Origine Tutti" +#define UI_TEXT_HOME_X_IT "Origine X" +#define UI_TEXT_HOME_Y_IT "Origine Y" +#define UI_TEXT_HOME_Z_IT "Origine Z" +#define UI_TEXT_PREHEAT_PLA_IT "Presicaldamento PLA" +#define UI_TEXT_PREHEAT_ABS_IT "Presicaldamento ABS" +#define UI_TEXT_LIGHTS_ONOFF_IT "Luci:%lo" +#define UI_TEXT_COOLDOWN_IT "Raffreddamento" +#define UI_TEXT_SET_TO_ORIGIN_IT "Imposta come Origine" +#define UI_TEXT_DISABLE_STEPPER_IT "Disabilita Stepper" +#define UI_TEXT_X_POSITION_IT "Posizione X" +#define UI_TEXT_X_POS_FAST_IT "Pos. X Veloce" +#define UI_TEXT_Y_POSITION_IT "Posizione Y" +#define UI_TEXT_Y_POS_FAST_IT "Pos. Y Veloce" +#define UI_TEXT_Z_POSITION_IT "Posizione Z" +#define UI_TEXT_Z_POS_FAST_IT "Pos. Z Veloce" +#define UI_TEXT_E_POSITION_IT "Posizione Estrusore" +#define UI_TEXT_BED_TEMP_IT "Temp.Piatto:%Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_IT "Temp. 1 :%e0/%E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_IT "Temp. 2 :%e1/%E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_IT "Temp. 3 :%e2/%E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_IT "Estrusore 1 Spento" +#define UI_TEXT_EXTR1_OFF_IT "Estrusore 2 Spento" +#define UI_TEXT_EXTR2_OFF_IT "Estrusore 3 Spento" +#define UI_TEXT_EXTR0_SELECT_IT "%X0 Seleziona Estr. 1" +#define UI_TEXT_EXTR1_SELECT_IT "%X1 Seleziona Estr. 2" +#define UI_TEXT_EXTR2_SELECT_IT "%X2 Seleziona Estr. 3" +#define UI_TEXT_EXTR_ORIGIN_IT "Imposta Origine" +#define UI_TEXT_PRINT_X_IT "Stampa X:%ax" +#define UI_TEXT_PRINT_Y_IT "Stampa Y:%ay" +#define UI_TEXT_PRINT_Z_IT "Stampa Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_IT "Stampa:%az" +#define UI_TEXT_MOVE_X_IT "Movimento X:%aX" +#define UI_TEXT_MOVE_Y_IT "Movimento Y:%aY" +#define UI_TEXT_MOVE_Z_IT "Movimento Z:%aZ" +#define UI_TEXT_MOVE_Z_DELTA_IT "Movimento:%aZ" +#define UI_TEXT_JERK_IT "Scatto:%aj" +#define UI_TEXT_ZJERK_IT "Scatto-Z:%aJ" +#define UI_TEXT_ACCELERATION_IT "Accelerazione" +#define UI_TEXT_STORE_TO_EEPROM_IT "Salva in EEPROM" +#define UI_TEXT_LOAD_EEPROM_IT "Carica da EEPROM" +#define UI_TEXT_DBG_ECHO_IT "Eco :%do" +#define UI_TEXT_DBG_INFO_IT "Info :%di" +#define UI_TEXT_DBG_ERROR_IT "Errori :%de" +#define UI_TEXT_DBG_DRYRUN_IT "Simulazione:%dd" +#define UI_TEXT_OPS_OFF_IT "%O0 OPS Spento" +#define UI_TEXT_OPS_CLASSIC_IT "%O1 OPS Classico" +#define UI_TEXT_OPS_FAST_IT "%O2 OPS Veloce" +#define UI_TEXT_OPS_RETRACT_IT "Ritiro :%Or" +#define UI_TEXT_OPS_BACKSLASH_IT "Gioco barra:%Ob" +#define UI_TEXT_OPS_MINDIST_IT "Distanza Min.:%Od" +#define UI_TEXT_OPS_MOVE_AFTER_IT "Movimento dopo:%Oa" +#define UI_TEXT_ANTI_OOZE_IT "Anti goccia" +#define UI_TEXT_PRINT_FILE_IT "Stampa file" +#define UI_TEXT_PAUSE_PRINT_IT "Pausa Stampa" +#define UI_TEXT_CONTINUE_PRINT_IT "Continua Stampa" +#define UI_TEXT_UNMOUNT_CARD_IT "Scarica Scheda" +#define UI_TEXT_MOUNT_CARD_IT "Carica Scheda" +#define UI_TEXT_DELETE_FILE_IT "Cancella file" +#define UI_TEXT_FEEDRATE_IT "Velocita'" +#define UI_TEXT_FEED_MAX_X_IT "Massimo X:%fx" +#define UI_TEXT_FEED_MAX_Y_IT "Massimo Y:%fy" +#define UI_TEXT_FEED_MAX_Z_IT "Massimo Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_IT "Massimo:%fz" +#define UI_TEXT_FEED_HOME_X_IT "Origine X:%fX" +#define UI_TEXT_FEED_HOME_Y_IT "Origine Y:%fY" +#define UI_TEXT_FEED_HOME_Z_IT "Origine Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_IT "Origine:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_IT "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_IT "Min finec.:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_IT "Max finec.:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_IT "" +#define UI_TEXT_ACTION_YPOSITION4A_IT "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_IT "Min finec.:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_IT "Max finec.:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_IT "" +#define UI_TEXT_ACTION_ZPOSITION4A_IT "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_IT "Min finec.:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_IT "Max finec.:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_IT "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_IT "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_IT "Min finec.:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_IT "Max finec.:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_IT "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_IT "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_IT "Min finec.:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_IT "Max finec.:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_IT "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_IT "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_IT "Min finec.:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_IT "Max finec.:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_IT "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_IT "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_IT "1 scatto = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_IT "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_IT "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_IT "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_IT "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_IT "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_IT "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_IT "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_IT "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_IT "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_IT "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_IT "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_IT "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_IT "Velocita Ventola" +#define UI_TEXT_ACTION_FANSPEED_IT "Vel. Ventola:%Fs%%%" +#define UI_TEXT_FAN_OFF_IT "Spegnimento Ventola" +#define UI_TEXT_FAN_25_IT "Ventola al 25%%%" +#define UI_TEXT_FAN_50_IT "Ventola al%%%" +#define UI_TEXT_FAN_75_IT "Ventola al%%%" +#define UI_TEXT_FAN_FULL_IT "Ventola al massimo" +#define UI_TEXT_STEPPER_INACTIVE_IT "Stepper Inattivi" +#define UI_TEXT_STEPPER_INACTIVE2A_IT "Dis. dopo: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_IT "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_IT "Max. Inattivita'" +#define UI_TEXT_POWER_INACTIVE2A_IT "Dis. After: %ip" +#define UI_TEXT_POWER_INACTIVE2B_IT "[min] 0=Off" +#define UI_TEXT_GENERAL_IT "Generale" +#define UI_TEXT_BAUDRATE_IT "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_IT "Passi/mm:%Se" +#define UI_TEXT_EXTR_START_FEED_IT "Velocita' Avvio:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_IT "Velocita' Max:%XF" +#define UI_TEXT_EXTR_ACCEL_IT "Accel:%XA" +#define UI_TEXT_EXTR_WATCH_IT "Tempo Stab.:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_IT "Avanzamento lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_IT "Avanzamento espon:%Xa" +#define UI_TEXT_EXTR_MANAGER_IT "Controllo:%Xh" +#define UI_TEXT_EXTR_PGAIN_IT "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_IT "Tempo morto:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_IT "Controllo PWM:%XM" +#define UI_TEXT_EXTR_IGAIN_IT "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_IT "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_IT "Drive Min:%Xm" +#define UI_TEXT_EXTR_DMAX_IT "Drive Max:%XM" +#define UI_TEXT_EXTR_PMAX_IT "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_IT "X-Offset:%Xx" +#define UI_TEXT_EXTR_YOFF_IT "Y-Offset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_IT "BangBang" +#define UI_TEXT_STRING_HM_PID_IT "PID" +#define UI_TEXT_STRING_ACTION_IT "Azione:%la" +#define UI_TEXT_HEATING_EXTRUDER_IT "Riscald. Estrusore" +#define UI_TEXT_HEATING_BED_IT "Riscald. Piatto" +#define UI_TEXT_KILLED_IT "Abortito" +#define UI_TEXT_STEPPER_DISABLED_IT "Stepper Disabilitato" +#define UI_TEXT_EEPROM_STOREDA_IT "Configurazione" +#define UI_TEXT_EEPROM_STOREDB_IT "Salvata in EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_IT "Configurazione" +#define UI_TEXT_EEPROM_LOADEDB_IT "Caricata da EEPROM" +#define UI_TEXT_UPLOADING_IT "Caricamento..." +#define UI_TEXT_PAGE_BUFFER_IT "Tampone:%oB" +#define UI_TEXT_PAGE_EXTRUDER_IT " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_IT "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_IT "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_IT "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_IT " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_IT "Molt. Velocita':%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_IT "Molt. Flusso:%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_IT "Mostra di misura" +#define UI_TEXT_RESET_MEASUREMENT_IT "Ripristino di misura" +#define UI_TEXT_SET_MEASURED_ORIGIN_IT "Set Z=0" +#define UI_TEXT_ZCALIB_IT "Z Calib." +#define UI_TEXT_SET_P1_IT "Impostato P1" +#define UI_TEXT_SET_P2_IT "Impostato P2" +#define UI_TEXT_SET_P3_IT "Impostato P3" +#define UI_TEXT_CALCULATE_LEVELING_IT "Calcol. livellamento" +#define UI_TEXT_LEVEL_IT "Livello delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_IT "Attesa Temp.%XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_IT "Attesa Unita':%XUmm" +#define UI_TEXT_SD_REMOVED_IT "SD Card rimosso" +#define UI_TEXT_SD_INSERTED_IT "SD Card inserita" +#define UI_TEXT_PRINTER_READY_IT "Stampante pronta." +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_IT " giorni " +#define UI_TEXT_PRINTTIME_HOURS_IT ":" +#define UI_TEXT_PRINTTIME_MINUTES_IT "" +#define UI_TEXT_PRINT_TIME_IT "Tempo di stampa" +#define UI_TEXT_PRINT_FILAMENT_IT "Filament stampata" +#define UI_TEXT_PRINTED_IT "stampato" +#define UI_TEXT_POWER_IT "ATX on/off" +#define UI_TEXT_STRING_HM_DEADTIME_IT "Tempo morto" +#define UI_TEXT_STRING_HM_SLOWBANG_IT "SlowBang" +#define UI_TEXT_STOP_PRINT_IT "Arresto Stampa" +#define UI_TEXT_Z_BABYSTEPPING_IT "Z Babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_IT "Cambia filamento" +#define UI_TEXT_WIZ_CH_FILAMENT1_IT "Cambia filamento" +#define UI_TEXT_WIZ_CH_FILAMENT2_IT "Ruotare per spostare" +#define UI_TEXT_WIZ_CH_FILAMENT3_IT "filamento su/giu" +#define UI_TEXT_CLICK_DONE_IT "Clicca quando fatto" +#define UI_TEXT_AUTOLEVEL_ONOFF_IT "Autoliv.: %ll" +#define UI_TEXT_SERVOPOS_IT "Pos. servo: %oS" +#define UI_TEXT_IGNORE_M106_IT "Ignora M106 cmd %Fi" +#define UI_TEXT_WIZ_REHEAT1_IT "Clicca per" +#define UI_TEXT_WIZ_REHEAT2_IT "riscaldare estrusori" +#define UI_TEXT_WIZ_WAITTEMP1_IT "Attendere che temp." +#define UI_TEXT_WIZ_WAITTEMP2_IT "di destinazione ..." +#define UI_TEXT_EXTRUDER_JAM_IT "Stoccaggio estrusore" +#define UI_TEXT_STANDBY_IT "Stand-by" +#define UI_TEXT_BED_COATING_IT "Rivestimento letto" +#define UI_TEXT_BED_COATING_SET1_IT "Rivestimento letto:" +#define UI_TEXT_BED_COATING_SET2_IT "" +#define UI_TEXT_NOCOATING_IT "Non rivestito" +#define UI_TEXT_BUILDTAK_IT "BuildTak" +#define UI_TEXT_KAPTON_IT "Kapton" +#define UI_TEXT_BLUETAPE_IT "Blu nastro adesivo" +#define UI_TEXT_PETTAPE_IT "Verde PET nastro" +#define UI_TEXT_GLUESTICK_IT "Colla stick" +#define UI_TEXT_CUSTOM_IT "Usanza" +#define UI_TEXT_COATING_CUSTOM_IT "Usanza:%BCmm" +#define UI_TEXT_LANGUAGE_IT "Lingua" + +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_IT "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_IT "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_IT "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_IT "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_IT " Y:%x1" +#endif +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_IT "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_IT "Copie: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_IT "Flusso:\xfd %of%%% Z:%x2" +#endif +#define UI_TEXT_MAINPAGE6_4_IT "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_IT "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_IT "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_IT cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_IT "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_IT "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_IT "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_IT "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_IT "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_IT "%Uf m" +#define UI_TEXT_METER_PRINTED_IT "%Uf m " UI_TEXT_PRINTED_IT +#define UI_TEXT_STATUS_IT "%os" +#define UI_TEXT_EMPTY_IT "" +#define UI_TEXT_TEMP_SET_IT cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_IT cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_IT " %BCmm" +#define UI_TEXT_EXTR3_TEMP_IT "Temp. 4 :%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_IT "Temp. 5 :%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_IT "Temp. 6 :%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_IT "Estrusore 4 Spento" +#define UI_TEXT_EXTR4_OFF_IT "Estrusore 5 Spento" +#define UI_TEXT_EXTR5_OFF_IT "Estrusore 6 Spento" +#define UI_TEXT_EXTR3_SELECT_IT "%X3 Seleziona Estr. 4" +#define UI_TEXT_EXTR4_SELECT_IT "%X4 Seleziona Estr. 5" +#define UI_TEXT_EXTR5_SELECT_IT "%X5 Seleziona Estr. 6" +#define UI_TEXT_DITTO_0_IT "%D0 Nessuna Copia" +#define UI_TEXT_DITTO_1_IT "%D1 1 Copia" +#define UI_TEXT_DITTO_2_IT "%D2 2 Copie" +#define UI_TEXT_DITTO_3_IT "%D3 3 Copie" +#define UI_TEXT_ZPROBE_HEIGHT_IT "Altezza Z-Probe:%zh" + + + +#define UI_TEXT_OFFSETS_IT "Set print offsets" +#define UI_TEXT_X_OFFSET_IT "Set X offset:%T0mm" +#define UI_TEXT_Y_OFFSET_IT "Set Y offset:%T1mm" +#define UI_TEXT_Z_OFFSET_IT "Set Z offset:%T2mm" + + +// Spanish translation + +#define UI_TEXT_ON_ES "On" +#define UI_TEXT_OFF_ES "Off" +#define UI_TEXT_NA_ES "N/A" // Output for not available +#define UI_TEXT_YES_ES "Si" +#define UI_TEXT_NO_ES "No" +#define UI_TEXT_PRINT_POS_ES "Imprimiendo..." +#define UI_TEXT_PRINTING_ES "Imprimiendo" +#define UI_TEXT_IDLE_ES "Idle" +#define UI_TEXT_NOSDCARD_ES "Sin tarjeta SD" +#define UI_TEXT_ERROR_ES "**** ERROR ****" +#define UI_TEXT_BACK_ES "Atras " cUP +#define UI_TEXT_QUICK_SETTINGS_ES "Configuracion Rapida" +#define UI_TEXT_ERRORMSG_ES "%oe" +#define UI_TEXT_CONFIGURATION_ES "Configuracion" +#define UI_TEXT_POSITION_ES "Posicion" +#define UI_TEXT_EXTRUDER_ES "Extrusor" +#define UI_TEXT_SD_CARD_ES "Tarjeta SD" +#define UI_TEXT_DEBUGGING_ES "Debugging" +#define UI_TEXT_HOME_DELTA_ES "Delta Home" +#define UI_TEXT_HOME_ALL_ES "Todo Home" +#define UI_TEXT_HOME_X_ES "X Home" +#define UI_TEXT_HOME_Y_ES "Y Home" +#define UI_TEXT_HOME_Z_ES "Z Home" +#define UI_TEXT_PREHEAT_PLA_ES "Precalentar PLA" +#define UI_TEXT_PREHEAT_ABS_ES "Precalentar ABS" +#define UI_TEXT_LIGHTS_ONOFF_ES "Luces:%lo" +#define UI_TEXT_COOLDOWN_ES "Enfriar" +#define UI_TEXT_SET_TO_ORIGIN_ES "Fija a origen" +#define UI_TEXT_DISABLE_STEPPER_ES "Desactiva motor" +#define UI_TEXT_X_POSITION_ES "Posicion X" +#define UI_TEXT_X_POS_FAST_ES "Pos. Rapida X" +#define UI_TEXT_Y_POSITION_ES "Posicion Y" +#define UI_TEXT_Y_POS_FAST_ES "Pos. Rapida Y" +#define UI_TEXT_Z_POSITION_ES "Posicion Z" +#define UI_TEXT_Z_POS_FAST_ES "Pos. Rapida Z" +#define UI_TEXT_E_POSITION_ES "Extr. Posicion" +#define UI_TEXT_BED_TEMP_ES "Temp.Cama:%eb/%Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_ES "Temp. 1 :%e0/%E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_ES "Temp. 2 :%e1/%E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_ES "Temp. 3 :%e2/%E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_ES "Extrusor 1 Off" +#define UI_TEXT_EXTR1_OFF_ES "Extrusor 2 Off" +#define UI_TEXT_EXTR2_OFF_ES "Extrusor 3 Off" +#define UI_TEXT_EXTR0_SELECT_ES "%X0 Select Extr. 1" +#define UI_TEXT_EXTR1_SELECT_ES "%X1 Select Extr. 2" +#define UI_TEXT_EXTR2_SELECT_ES "%X2 Select Extr. 3" +#define UI_TEXT_EXTR_ORIGIN_ES "Fija Originen" +#define UI_TEXT_PRINT_X_ES "Print X:%ax" +#define UI_TEXT_PRINT_Y_ES "Print Y:%ay" +#define UI_TEXT_PRINT_Z_ES "Print Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_ES "Print:%az" +#define UI_TEXT_MOVE_X_ES "Mueve X:%aX" +#define UI_TEXT_MOVE_Y_ES "Mueve Y:%aY" +#define UI_TEXT_MOVE_Z_ES "Mueve Z:%aZ" +#define UI_TEXT_MOVE_Z_DELTA_ES "Mueve:%aZ" +#define UI_TEXT_JERK_ES "Jerk:%aj" +#define UI_TEXT_ZJERK_ES "Z-Jerk:%aJ" +#define UI_TEXT_ACCELERATION_ES "Aceleracion" +#define UI_TEXT_STORE_TO_EEPROM_ES "Almacena en EEPROM" +#define UI_TEXT_LOAD_EEPROM_ES "Carga de EEPROM" +#define UI_TEXT_DBG_ECHO_ES "Echo :%do" +#define UI_TEXT_DBG_INFO_ES "Info :%di" +#define UI_TEXT_DBG_ERROR_ES "Errors :%de" +#define UI_TEXT_DBG_DRYRUN_ES "Ejecucion vacio:%dd" +#define UI_TEXT_OPS_OFF_ES "%O0 OPS Off" +#define UI_TEXT_OPS_CLASSIC_ES "%O1 OPS Classica" +#define UI_TEXT_OPS_FAST_ES "%O2 OPS Rapida" +#define UI_TEXT_OPS_RETRACT_ES "Retraccion :%Or" +#define UI_TEXT_OPS_BACKSLASH_ES "Backsl. :%Ob" +#define UI_TEXT_OPS_MINDIST_ES "Min.dist:%Od" +#define UI_TEXT_OPS_MOVE_AFTER_ES "Move after:%Oa" +#define UI_TEXT_ANTI_OOZE_ES "Anti Ooze" +#define UI_TEXT_PRINT_FILE_ES "Imprimiendo fichero" +#define UI_TEXT_PAUSE_PRINT_ES "Pausando impresion" +#define UI_TEXT_CONTINUE_PRINT_ES "Continuando impresion" +#define UI_TEXT_UNMOUNT_CARD_ES "Desmontando Tarjeta" +#define UI_TEXT_MOUNT_CARD_ES "Montando Card" +#define UI_TEXT_DELETE_FILE_ES "Borrando fichero" +#define UI_TEXT_FEEDRATE_ES "Feedrate" +#define UI_TEXT_FEED_MAX_X_ES "X Max:%fx" +#define UI_TEXT_FEED_MAX_Y_ES "Y Max:%fy" +#define UI_TEXT_FEED_MAX_Z_ES "Z Max:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_ES "Max:%fz" +#define UI_TEXT_FEED_HOME_X_ES "X Home:%fX" +#define UI_TEXT_FEED_HOME_Y_ES "Y Home:%fY" +#define UI_TEXT_FEED_HOME_Z_ES "Z Home:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_ES "Home:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_ES "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_ES "Fin Carrera Min:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_ES "Max:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_ES "" +#define UI_TEXT_ACTION_YPOSITION4A_ES "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_ES "Fin Carrera Min:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_ES "Max:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_ES "" +#define UI_TEXT_ACTION_ZPOSITION4A_ES "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_ES "Fin Carrera Min:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_ES "Max:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_ES "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_ES "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_ES "Fin Carrera Min:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_ES "Max:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_ES "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_ES "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_ES "Fin Carrera Min:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_ES "Max:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_ES "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_ES "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_ES "Fin Carrera Min:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_ES "Max:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_ES "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_ES "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_ES "1 click = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_ES "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_ES "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_ES "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_ES "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_ES "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_ES "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_ES "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_ES "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_ES "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_ES "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_ES "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_ES "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_ES "Velocida ventilador" +#define UI_TEXT_ACTION_FANSPEED_ES "Vel. vent.:%Fs%%%" +#define UI_TEXT_FAN_OFF_ES "Apaga ventilador" +#define UI_TEXT_FAN_25_ES "Ventilador al 25%%%" +#define UI_TEXT_FAN_50_ES "Ventilador al 50%%%" +#define UI_TEXT_FAN_75_ES "Ventilador al 75%%%" +#define UI_TEXT_FAN_FULL_ES "Ventilador al 100%%%" +#define UI_TEXT_STEPPER_INACTIVE_ES "Motor Inactivo" +#define UI_TEXT_STEPPER_INACTIVE2A_ES "Dis. Despues: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_ES "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_ES "Max. Inactivo" +#define UI_TEXT_POWER_INACTIVE2A_ES "Dis. Despues: %ip" +#define UI_TEXT_POWER_INACTIVE2B_ES "[min] 0=Off" +#define UI_TEXT_GENERAL_ES "General" +#define UI_TEXT_BAUDRATE_ES "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_ES "Pasos/MM:%Se" +#define UI_TEXT_EXTR_START_FEED_ES "Start FR:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_ES "Max FR:%XF" +#define UI_TEXT_EXTR_ACCEL_ES "Acel:%XA" +#define UI_TEXT_EXTR_WATCH_ES "Tiempo Estab.:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_ES "Advance lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_ES "Advance quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_ES "Control:%Xh" +#define UI_TEXT_EXTR_PGAIN_ES "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_ES "Tiempo muerto:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_ES "PWM control:%XM" +#define UI_TEXT_EXTR_IGAIN_ES "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_ES "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_ES "Drive Min:%Xm" +#define UI_TEXT_EXTR_DMAX_ES "Drive Max:%XM" +#define UI_TEXT_EXTR_PMAX_ES "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_ES "X-Offset:%Xx" +#define UI_TEXT_EXTR_YOFF_ES "Y-Offset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_ES "BangBang" +#define UI_TEXT_STRING_HM_PID_ES "PID" +#define UI_TEXT_STRING_ACTION_ES "Accion:%la" +#define UI_TEXT_HEATING_EXTRUDER_ES "Calentando Extrusor" +#define UI_TEXT_HEATING_BED_ES "Calentando Cama" +#define UI_TEXT_KILLED_ES "Aborta" +#define UI_TEXT_STEPPER_DISABLED_ES "Deshabilita motor" +#define UI_TEXT_EEPROM_STOREDA_ES "Config." +#define UI_TEXT_EEPROM_STOREDB_ES "almacenada en EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_ES "Config." +#define UI_TEXT_EEPROM_LOADEDB_ES "cargada de EEPROM" +#define UI_TEXT_UPLOADING_ES "Actualizando..." +#define UI_TEXT_PAGE_BUFFER_ES "Buffer:%oB" +#define UI_TEXT_PAGE_EXTRUDER_ES " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_ES "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_ES "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_ES "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_ES " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_ES "Mult. Velocidad.:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_ES "Mult. Flujo:%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_ES "Mostrar medicion" +#define UI_TEXT_RESET_MEASUREMENT_ES "Resetear medicion" +#define UI_TEXT_SET_MEASURED_ORIGIN_ES "Set Z=0" +#define UI_TEXT_ZCALIB_ES "Z calib." +#define UI_TEXT_SET_P1_ES "Set P1" +#define UI_TEXT_SET_P2_ES "Set P2" +#define UI_TEXT_SET_P3_ES "Set P3" +#define UI_TEXT_CALCULATE_LEVELING_ES "Calcula nivelacion" +#define UI_TEXT_LEVEL_ES "Nivel delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_ES "Esperando Temp.%XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_ES "Esperando Unidad:%XUmm" +#define UI_TEXT_SD_REMOVED_ES "Tarjeta SD retira" +#define UI_TEXT_SD_INSERTED_ES "Tarjeta SD insertada" +#define UI_TEXT_PRINTER_READY_ES "Impresora lista." +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_ES " dias " +#define UI_TEXT_PRINTTIME_HOURS_ES ":" +#define UI_TEXT_PRINTTIME_MINUTES_ES "" +#define UI_TEXT_PRINT_TIME_ES "tiempo de impresion" +#define UI_TEXT_PRINT_FILAMENT_ES "Filamento impresa" +#define UI_TEXT_PRINTED_ES "impreso" +#define UI_TEXT_POWER_ES "Energie ATX on/off" +#define UI_TEXT_STRING_HM_DEADTIME_ES "Tiempo muerto" +#define UI_TEXT_STRING_HM_SLOWBANG_ES "SlowBang" +#define UI_TEXT_STOP_PRINT_ES "Detener impresion" +#define UI_TEXT_Z_BABYSTEPPING_ES "Z Babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_ES "Cambio filamento" +#define UI_TEXT_WIZ_CH_FILAMENT1_ES "Cambio filamento" +#define UI_TEXT_WIZ_CH_FILAMENT2_ES "Gire para mover" +#define UI_TEXT_WIZ_CH_FILAMENT3_ES "fil. arriba/abajo" +#define UI_TEXT_CLICK_DONE_ES "Clic cuando se hace" +#define UI_TEXT_AUTOLEVEL_ONOFF_ES "Autolevel: %ll" +#define UI_TEXT_SERVOPOS_ES "Pos. servo: %oS" +#define UI_TEXT_IGNORE_M106_ES "Ignorar M106 cmd %Fi" +#define UI_TEXT_WIZ_REHEAT1_ES "Haga clic para" +#define UI_TEXT_WIZ_REHEAT2_ES "recalentar extr." +#define UI_TEXT_WIZ_WAITTEMP1_ES "Espere a temp." +#define UI_TEXT_WIZ_WAITTEMP2_ES "objetivo ..." +#define UI_TEXT_EXTRUDER_JAM_ES "Atasco extrusora" +#define UI_TEXT_STANDBY_ES "Standby" +#define UI_TEXT_BED_COATING_ES "Recubrimiento cama" +#define UI_TEXT_BED_COATING_SET1_ES "Rec. cama ajustado a" +#define UI_TEXT_BED_COATING_SET2_ES "" +#define UI_TEXT_NOCOATING_ES "Sin recubrimiento" +#define UI_TEXT_BUILDTAK_ES "BuildTak" +#define UI_TEXT_KAPTON_ES "Kapton" +#define UI_TEXT_BLUETAPE_ES "Cinta adhesiva azul" +#define UI_TEXT_PETTAPE_ES "Verde PET cinta" +#define UI_TEXT_GLUESTICK_ES "Barra de pegamento" +#define UI_TEXT_CUSTOM_ES "Custom" +#define UI_TEXT_COATING_CUSTOM_ES "Custom:%BCmm" +#define UI_TEXT_LANGUAGE_ES "Idioma" + +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_ES "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_ES "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_ES "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_ES "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_ES " Y:%x1" +#endif +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_ES "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_ES "Copias: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_ES "Flujo:\xfd %of%%% Z:%x2" +#endif +#define UI_TEXT_MAINPAGE6_4_ES "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_ES "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_ES "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_ES cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_ES "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_ES "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_ES "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_ES "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_ES "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_ES "%Uf m" +#define UI_TEXT_METER_PRINTED_ES "%Uf m " UI_TEXT_PRINTED_ES +#define UI_TEXT_STATUS_ES "%os" +#define UI_TEXT_EMPTY_ES "" +#define UI_TEXT_TEMP_SET_ES cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_ES cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_ES " %BCmm" +#define UI_TEXT_EXTR3_TEMP_ES "Temp. 4 :%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_ES "Temp. 5 :%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_ES "Temp. 6 :%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_ES "Extrusor 4 Off" +#define UI_TEXT_EXTR4_OFF_ES "Extrusor 5 Off" +#define UI_TEXT_EXTR5_OFF_ES "Extrusor 6 Off" +#define UI_TEXT_EXTR3_SELECT_ES "%X3 Select Extr. 4" +#define UI_TEXT_EXTR4_SELECT_ES "%X4 Select Extr. 5" +#define UI_TEXT_EXTR5_SELECT_ES "%X5 Select Extr. 6" +#define UI_TEXT_DITTO_0_ES "%D0 No Hay Copias" +#define UI_TEXT_DITTO_1_ES "%D1 1 Copia" +#define UI_TEXT_DITTO_2_ES "%D2 2 Copias" +#define UI_TEXT_DITTO_3_ES "%D3 3 Copias" +#define UI_TEXT_ZPROBE_HEIGHT_ES "Altura Z-Probe:%zh" + + +#define UI_TEXT_OFFSETS_ES "Set print offsets" +#define UI_TEXT_X_OFFSET_ES "Set X offset:%T0mm" +#define UI_TEXT_Y_OFFSET_ES "Set Y offset:%T1mm" +#define UI_TEXT_Z_OFFSET_ES "Set Z offset:%T2mm" + + +// *************** Swedish translation **************** +// By Daniel Tedenljung 2013-08-21 + +#define UI_TEXT_ON_SE "P" STR_uuml "" +#define UI_TEXT_OFF_SE "Av" +#define UI_TEXT_NA_SE "N/A" // Output for not available +#define UI_TEXT_YES_SE "Ja" +#define UI_TEXT_NO_SE "Nej" +#define UI_TEXT_PRINT_POS_SE "Skriver ut..." +#define UI_TEXT_PRINTING_SE "Skriver" +#define UI_TEXT_IDLE_SE "Sysslol" STR_ouml "s" +#define UI_TEXT_NOSDCARD_SE "Inget SD-kort" +#define UI_TEXT_ERROR_SE "**** FEL ****" +#define UI_TEXT_BACK_SE "Tillbaka " cUP +#define UI_TEXT_QUICK_SETTINGS_SE "Inst" STR_auml "llnigar" +#define UI_TEXT_ERRORMSG_SE "%oe" +#define UI_TEXT_CONFIGURATION_SE "Konfiguration" +#define UI_TEXT_POSITION_SE "Position" +#define UI_TEXT_EXTRUDER_SE "Extruder" +#define UI_TEXT_SD_CARD_SE "SD-kort" +#define UI_TEXT_DEBUGGING_SE "Debugging" +#define UI_TEXT_HOME_DELTA_SE "Hem delta" +#define UI_TEXT_HOME_ALL_SE "K" STR_ouml "r hem alla" +#define UI_TEXT_HOME_X_SE "K" STR_ouml "r hem X" +#define UI_TEXT_HOME_Y_SE "K" STR_ouml "r hem Y" +#define UI_TEXT_HOME_Z_SE "K" STR_ouml "r hem Z" +#define UI_TEXT_PREHEAT_PLA_SE "F" STR_ouml "rv" STR_auml "rm f" STR_ouml "r PLA" +#define UI_TEXT_PREHEAT_ABS_SE "F" STR_ouml "rv" STR_auml "rm f" STR_ouml "r ABS" +#define UI_TEXT_LIGHTS_ONOFF_SE "Lights:%lo" +#define UI_TEXT_COOLDOWN_SE "Kyl ner" +#define UI_TEXT_SET_TO_ORIGIN_SE "S" STR_auml "tt som origo" +#define UI_TEXT_DISABLE_STEPPER_SE "St" STR_auml "ng av stegmotor" +#define UI_TEXT_X_POSITION_SE "X-position" +#define UI_TEXT_X_POS_FAST_SE "X-pos. snabb" +#define UI_TEXT_Y_POSITION_SE "Y-position" +#define UI_TEXT_Y_POS_FAST_SE "Y-pos. snabb" +#define UI_TEXT_Z_POSITION_SE "Z-osition" +#define UI_TEXT_Z_POS_FAST_SE "Z-pos. snabb" +#define UI_TEXT_E_POSITION_SE "Extr.-position" +#define UI_TEXT_BED_TEMP_SE "B" STR_auml "dd-temp:%eb/%Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_SE "Temp. 1 :%e0/%E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_SE "Temp. 2 :%e1/%E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_SE "Temp. 3 :%e2/%E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_SE "Extruder 1 av" +#define UI_TEXT_EXTR1_OFF_SE "Extruder 2 av" +#define UI_TEXT_EXTR2_OFF_SE "Extruder 3 av" +#define UI_TEXT_EXTR0_SELECT_SE "%X0 V" STR_auml "lj Extr. 1" +#define UI_TEXT_EXTR1_SELECT_SE "%X1 V" STR_auml "lj Extr. 2" +#define UI_TEXT_EXTR2_SELECT_SE "%X2 V" STR_auml "lj Extr. 3" +#define UI_TEXT_EXTR_ORIGIN_SE "S" STR_auml "tt origo" +#define UI_TEXT_PRINT_X_SE "Skriv X:%ax" +#define UI_TEXT_PRINT_Y_SE "Skriv Y:%ay" +#define UI_TEXT_PRINT_Z_SE "Skriv Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_SE "Skriv:%az" +#define UI_TEXT_MOVE_X_SE "Transp. X:%aX" +#define UI_TEXT_MOVE_Y_SE "Transp. Y:%aY" +#define UI_TEXT_MOVE_Z_SE "Transp. Z:%aZ" +#define UI_TEXT_MOVE_Z_DELTA_SE "Transp.:%aZ" +#define UI_TEXT_JERK_SE "Ryck: %aj" +#define UI_TEXT_ZJERK_SE "Z-ryck: %aJ" +#define UI_TEXT_ACCELERATION_SE "Acceleration" +#define UI_TEXT_STORE_TO_EEPROM_SE "Spara till EEPROM" +#define UI_TEXT_LOAD_EEPROM_SE "Ladda f. EEPROM" +#define UI_TEXT_DBG_ECHO_SE "Eko: %do" +#define UI_TEXT_DBG_INFO_SE "Info: %di" +#define UI_TEXT_DBG_ERROR_SE "Errors: %de" +#define UI_TEXT_DBG_DRYRUN_SE "Torrk" STR_ouml "r:%dd" +#define UI_TEXT_OPS_OFF_SE "%O1 OPS av" +#define UI_TEXT_OPS_CLASSIC_SE "%O2 OPS klassisk" +#define UI_TEXT_OPS_FAST_SE "%O3 OPS snabb" +#define UI_TEXT_OPS_RETRACT_SE "Backa: %Or" +#define UI_TEXT_OPS_BACKSLASH_SE "Backsl. :%Ob" +#define UI_TEXT_OPS_MINDIST_SE "Min.dist: %Od" +#define UI_TEXT_OPS_MOVE_AFTER_SE "Flytta efter:%Oa" +#define UI_TEXT_ANTI_OOZE_SE "Antikladd" +#define UI_TEXT_PRINT_FILE_SE "Skriv ut fil" +#define UI_TEXT_PAUSE_PRINT_SE "Pausa utskrift" +#define UI_TEXT_CONTINUE_PRINT_SE "Forts" STR_auml "tt utskrift" +#define UI_TEXT_UNMOUNT_CARD_SE "Mata ut kort" +#define UI_TEXT_MOUNT_CARD_SE "Anslut kort" +#define UI_TEXT_DELETE_FILE_SE "Radera fil" +#define UI_TEXT_FEEDRATE_SE "Matning" +#define UI_TEXT_FEED_MAX_X_SE "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_SE "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_SE "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_SE "Max:%fz" +#define UI_TEXT_FEED_HOME_X_SE "Ref X:%fX" +#define UI_TEXT_FEED_HOME_Y_SE "Ref Y:%fY" +#define UI_TEXT_FEED_HOME_Z_SE "Ref Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_SE "Ref:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_SE "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_SE "Min " STR_auml "ndl" STR_auml "ge:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_SE "Max " STR_auml "ndl" STR_auml "ge:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_SE "" +#define UI_TEXT_ACTION_YPOSITION4A_SE "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_SE "Min " STR_auml "ndl" STR_auml "ge:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_SE "Max " STR_auml "ndl" STR_auml "ge:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_SE "" +#define UI_TEXT_ACTION_ZPOSITION4A_SE "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_SE "Min " STR_auml "ndl" STR_auml "ge:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_SE "Max " STR_auml "ndl" STR_auml "ge:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_SE "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_SE "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_SE "Min " STR_auml "ndl" STR_auml "ge:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_SE "Max " STR_auml "ndl" STR_auml "ge:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_SE "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_SE "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_SE "Min " STR_auml "ndl" STR_auml "ge:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_SE "Max " STR_auml "ndl" STR_auml "ge:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_SE "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_SE "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_SE "Min " STR_auml "ndl" STR_auml "ge:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_SE "Max " STR_auml "ndl" STR_auml "ge:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_SE "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_SE "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_SE "1 click = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_SE "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_SE "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_SE "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_SE "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_SE "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_SE "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_SE "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_SE "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_SE "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_SE "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_SE "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_SE "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_SE "Fl" STR_auml "kt hast." +#define UI_TEXT_ACTION_FANSPEED_SE "Fl" STR_auml "kt hast.:%Fs%%%" +#define UI_TEXT_FAN_OFF_SE "St" STR_auml "ng av fl" STR_auml "kt" +#define UI_TEXT_FAN_25_SE "Fl" STR_auml "kt 25%%%" +#define UI_TEXT_FAN_50_SE "Fl" STR_auml "kt 50%%%" +#define UI_TEXT_FAN_75_SE "Fl" STR_auml "kt 75%%%" +#define UI_TEXT_FAN_FULL_SE "Full fl" STR_auml "kt" +#define UI_TEXT_STEPPER_INACTIVE_SE "Stegmotorer inakt." +#define UI_TEXT_STEPPER_INACTIVE2A_SE "Inakt. efter: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_SE "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_SE "Max. inaktiv" +#define UI_TEXT_POWER_INACTIVE2A_SE "Inakt. efter: %ip" +#define UI_TEXT_POWER_INACTIVE2B_SE "[min] 0=Off" +#define UI_TEXT_GENERAL_SE "Generella" +#define UI_TEXT_BAUDRATE_SE "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_SE "Steg/MM:%Se" +#define UI_TEXT_EXTR_START_FEED_SE "Start FR:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_SE "Max FR:%XF" +#define UI_TEXT_EXTR_ACCEL_SE "Accel:%XA" +#define UI_TEXT_EXTR_WATCH_SE "Stab. tid:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_SE "Advance lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_SE "Advance quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_SE "Control:%Xh" +#define UI_TEXT_EXTR_PGAIN_SE "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_SE "D" STR_ouml "dtid:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_SE "Kontroll PWM:%XM" +#define UI_TEXT_EXTR_IGAIN_SE "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_SE "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_SE "Drive min:%Xm" +#define UI_TEXT_EXTR_DMAX_SE "Drive max:%XM" +#define UI_TEXT_EXTR_PMAX_SE "PID max:%XD" +#define UI_TEXT_EXTR_XOFF_SE "X-offset:%Xx" +#define UI_TEXT_EXTR_YOFF_SE "Y-offset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_SE "BangBang" +#define UI_TEXT_STRING_HM_PID_SE "PID" +#define UI_TEXT_STRING_ACTION_SE "Aktion:%la" +#define UI_TEXT_HEATING_EXTRUDER_SE "V" STR_auml "rmer Extruder" +#define UI_TEXT_HEATING_BED_SE "V" STR_auml "rmer B" STR_auml "dd" +#define UI_TEXT_KILLED_SE "D" STR_ouml "dad" +#define UI_TEXT_STEPPER_DISABLED_SE "Stegmotorer av" +#define UI_TEXT_EEPROM_STOREDA_SE "Konfiguration" +#define UI_TEXT_EEPROM_STOREDB_SE "sparad i EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_SE "Konfiguration" +#define UI_TEXT_EEPROM_LOADEDB_SE "laddat fr. EEPROM" +#define UI_TEXT_UPLOADING_SE "Uppladdning..." +#define UI_TEXT_PAGE_BUFFER_SE "Buffer:%oB" +#define UI_TEXT_PAGE_EXTRUDER_SE " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_SE "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_SE "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_SE "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_SE " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_SE "Hast. Mul.:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_SE "Fl" STR_ouml "de Mul.:%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_SE "Visa m" STR_auml "tning" +#define UI_TEXT_RESET_MEASUREMENT_SE "Aterst" STR_auml "ll m" STR_auml "tning" +#define UI_TEXT_SET_MEASURED_ORIGIN_SE "St" STR_auml "ll Z=0" +#define UI_TEXT_ZCALIB_SE "Z kalib." +#define UI_TEXT_SET_P1_SE "St" STR_auml "ll P1" +#define UI_TEXT_SET_P2_SE "St" STR_auml "ll P2" +#define UI_TEXT_SET_P3_SE "Set P3" +#define UI_TEXT_CALCULATE_LEVELING_SE "ber" STR_auml "kna nivellering" +#define UI_TEXT_LEVEL_SE "Niva delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_SE "Inv" STR_auml "nta temp.%XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_SE "Inv" STR_auml "nta pos:%XUmm" +#define UI_TEXT_SD_REMOVED_SE "SD-kort tas bort" +#define UI_TEXT_SD_INSERTED_SE "SD-kort isatt" +#define UI_TEXT_PRINTER_READY_SE "Utskrift klar." +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_SE " dagar " +#define UI_TEXT_PRINTTIME_HOURS_SE ":" +#define UI_TEXT_PRINTTIME_MINUTES_SE "" +#define UI_TEXT_PRINT_TIME_SE "Tryckningstid" +#define UI_TEXT_PRINT_FILAMENT_SE "Filament tryckt" +#define UI_TEXT_PRINTED_SE "tryckt" +#define UI_TEXT_POWER_SE "ATX str" STR_ouml "m p" STR_uuml "/av" +#define UI_TEXT_STRING_HM_DEADTIME_SE "D" STR_ouml "dtid" +#define UI_TEXT_STRING_HM_SLOWBANG_SE "SlowBang" +#define UI_TEXT_STOP_PRINT_SE "Stopp trycket" +#define UI_TEXT_Z_BABYSTEPPING_SE "Z babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_SE "" STR_Auml "ndra filamentet" +#define UI_TEXT_WIZ_CH_FILAMENT1_SE "" STR_Auml "ndra filamentet" +#define UI_TEXT_WIZ_CH_FILAMENT2_SE "Rotera att flytta" +#define UI_TEXT_WIZ_CH_FILAMENT3_SE "filamentet upp/ner" +#define UI_TEXT_CLICK_DONE_SE "Klicka n" STR_auml "r du " STR_auml "r klar" +#define UI_TEXT_AUTOLEVEL_ONOFF_SE "Autolevel: %ll" +#define UI_TEXT_SERVOPOS_SE "Servol" STR_auml "ge: %oS" +#define UI_TEXT_IGNORE_M106_SE "Ignorera M106 %Fi" +#define UI_TEXT_WIZ_REHEAT1_SE "Klicka f" STR_ouml "r att" +#define UI_TEXT_WIZ_REHEAT2_SE "v" STR_auml "rma extrudrar." +#define UI_TEXT_WIZ_WAITTEMP1_SE "V" STR_auml "nta pa" +#define UI_TEXT_WIZ_WAITTEMP2_SE "maltemperaturer ..." +#define UI_TEXT_EXTRUDER_JAM_SE "Extruder tr" STR_auml "ngsel" +#define UI_TEXT_STANDBY_SE "Standby" +#define UI_TEXT_BED_COATING_SE "B" STR_auml "ddbel" STR_auml "ggning" +#define UI_TEXT_BED_COATING_SET1_SE "B" STR_auml "ddbel" STR_auml "ggning:" +#define UI_TEXT_BED_COATING_SET2_SE "" +#define UI_TEXT_NOCOATING_SE "Ingen bel" STR_auml "ggning" +#define UI_TEXT_BUILDTAK_SE "BuildTak" +#define UI_TEXT_KAPTON_SE "Kapton" +#define UI_TEXT_BLUETAPE_SE "Bla maskeringstejp" +#define UI_TEXT_PETTAPE_SE "Gr" STR_ouml "n PET band" +#define UI_TEXT_GLUESTICK_SE "Limstift" +#define UI_TEXT_CUSTOM_SE "Anpassad" +#define UI_TEXT_COATING_CUSTOM_SE "Anpassad:%BCmm" +#define UI_TEXT_LANGUAGE_SE "Sprak" + +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_SE "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_SE "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_SE "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_SE "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_SE " Y:%x1" +#endif +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_SE "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_SE "Kopior: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_SE "Fl" STR_ouml "de:\xfd %of%%% Z:%x2" +#endif +#define UI_TEXT_MAINPAGE6_4_SE "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_SE "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_SE "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_SE cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_SE "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_SE "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_SE "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_SE "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_SE "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_SE "%Uf m" +#define UI_TEXT_METER_PRINTED_SE "%Uf m " UI_TEXT_PRINTED_SE +#define UI_TEXT_STATUS_SE "%os" +#define UI_TEXT_EMPTY_SE "" +#define UI_TEXT_TEMP_SET_SE cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_SE cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_SE " %BCmm" +#define UI_TEXT_EXTR3_TEMP_SE "Temp. 4 :%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_SE "Temp. 5 :%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_SE "Temp. 6 :%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_SE "Extruder 4 av" +#define UI_TEXT_EXTR4_OFF_SE "Extruder 5 av" +#define UI_TEXT_EXTR5_OFF_SE "Extruder 6 av" +#define UI_TEXT_EXTR3_SELECT_SE "%X3 V" STR_auml "lj Extr. 4" +#define UI_TEXT_EXTR4_SELECT_SE "%X4 V" STR_auml "lj Extr. 5" +#define UI_TEXT_EXTR5_SELECT_SE "%X5 V" STR_auml "lj Extr. 6" +#define UI_TEXT_DITTO_0_SE "%D0 Inga Kopior" +#define UI_TEXT_DITTO_1_SE "%D1 1 Kopia" +#define UI_TEXT_DITTO_2_SE "%D2 2 Kopior" +#define UI_TEXT_DITTO_3_SE "%D3 3 Kopior" +#define UI_TEXT_ZPROBE_HEIGHT_SE "Z-probh" STR_ouml "jden:%zh" + + + +#define UI_TEXT_OFFSETS_SE "Set print offsets" +#define UI_TEXT_X_OFFSET_SE "Set X offset:%T0mm" +#define UI_TEXT_Y_OFFSET_SE "Set Y offset:%T1mm" +#define UI_TEXT_Z_OFFSET_SE "Set Z offset:%T2mm" + + +// *************** French translation **************** +// *************** By Doudou **************** + +#define UI_TEXT_ON_FR "On" +#define UI_TEXT_OFF_FR "Off" +#define UI_TEXT_NA_FR "N/A" // Output for not available +#define UI_TEXT_YES_FR "Oui" +#define UI_TEXT_NO_FR "Non" +#define UI_TEXT_PRINT_POS_FR "Impression..." +#define UI_TEXT_PRINTING_FR "Impression" +#define UI_TEXT_IDLE_FR "Au Repos" +#define UI_TEXT_NOSDCARD_FR "Pas de Carte SD" +#define UI_TEXT_ERROR_FR "**** ERREUR ****" +#define UI_TEXT_BACK_FR "Retour \001" +#define UI_TEXT_QUICK_SETTINGS_FR "Reglages Rapides" +#define UI_TEXT_ERRORMSG_FR "%oe" +#define UI_TEXT_CONFIGURATION_FR "Configuration" +#define UI_TEXT_POSITION_FR "Position" +#define UI_TEXT_EXTRUDER_FR "Extrudeuse" +#define UI_TEXT_SD_CARD_FR "Carte SD" +#define UI_TEXT_DEBUGGING_FR "Deboguer" +#define UI_TEXT_HOME_DELTA_FR "Accueil Delta" +#define UI_TEXT_HOME_ALL_FR "Accueil Tout" +#define UI_TEXT_HOME_X_FR "Accueil X" +#define UI_TEXT_HOME_Y_FR "Accueil Y" +#define UI_TEXT_HOME_Z_FR "Accueil Z" +#define UI_TEXT_PREHEAT_PLA_FR "Prechauf. PLA" +#define UI_TEXT_PREHEAT_ABS_FR "Prechauf. ABS" +#define UI_TEXT_LIGHTS_ONOFF_FR "Eclairage :%lo" +#define UI_TEXT_COOLDOWN_FR "Refroidir" +#define UI_TEXT_SET_TO_ORIGIN_FR "Reglez sur Origine" +#define UI_TEXT_DISABLE_STEPPER_FR "Desactiv. Moteurs" +#define UI_TEXT_X_POSITION_FR "Position X" +#define UI_TEXT_X_POS_FAST_FR "Pos. Rapide X" +#define UI_TEXT_Y_POSITION_FR "Position Y" +#define UI_TEXT_Y_POS_FAST_FR "Pos. Rapide Y" +#define UI_TEXT_Z_POSITION_FR "Position Z" +#define UI_TEXT_Z_POS_FAST_FR "Pos. Rapide Z" +#define UI_TEXT_E_POSITION_FR "Position Extr." +#define UI_TEXT_BED_TEMP_FR "Lit Temp:%eb/%Eb\002C" +#define UI_TEXT_EXTR0_TEMP_FR "Temp. 1 :%e0/%E0\002C" +#define UI_TEXT_EXTR1_TEMP_FR "Temp. 2 :%e1/%E1\002C" +#define UI_TEXT_EXTR2_TEMP_FR "Temp. 2 :%e2/%E2\002C" +#define UI_TEXT_EXTR0_OFF_FR "Extrudeuse 1 Off" +#define UI_TEXT_EXTR1_OFF_FR "Extrudeuse 2 Off" +#define UI_TEXT_EXTR2_OFF_FR "Extrudeuse 3 Off" +#define UI_TEXT_EXTR0_SELECT_FR "%X0 Select. Extr. 1" +#define UI_TEXT_EXTR1_SELECT_FR "%X1 Select. Extr. 2" +#define UI_TEXT_EXTR2_SELECT_FR "%X1 Select. Extr. 3" +#define UI_TEXT_EXTR_ORIGIN_FR "Set Origin" +#define UI_TEXT_PRINT_X_FR "Imprim. X:%ax" +#define UI_TEXT_PRINT_Y_FR "Imprim. Y:%ay" +#define UI_TEXT_PRINT_Z_FR "Imprim. Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_FR "Imprim.:%az" +#define UI_TEXT_MOVE_X_FR "Deplac. X:%aX" +#define UI_TEXT_MOVE_Y_FR "Deplac. Y:%aY" +#define UI_TEXT_MOVE_Z_FR "Deplac. Z:%aZ" +#define UI_TEXT_MOVE_Z_DELTA_FR "Deplac.:%aZ" +#define UI_TEXT_JERK_FR "Jerk:%aj" +#define UI_TEXT_ZJERK_FR "Z-Jerk:%aJ" +#define UI_TEXT_ACCELERATION_FR "Acceleration" +#define UI_TEXT_STORE_TO_EEPROM_FR "Stock. Dans EEPROM" +#define UI_TEXT_LOAD_EEPROM_FR "Charg. f. EEPROM" +#define UI_TEXT_DBG_ECHO_FR "Echo :%do" +#define UI_TEXT_DBG_INFO_FR "Info :%di" +#define UI_TEXT_DBG_ERROR_FR "Erreurs :%de" +#define UI_TEXT_DBG_DRYRUN_FR "Fonct. a Vide:%dd" +#define UI_TEXT_OPS_OFF_FR "%O0 OPS Off" +#define UI_TEXT_OPS_CLASSIC_FR "%O1 OPS Classiq." +#define UI_TEXT_OPS_FAST_FR "%O2 OPS Rapide" +#define UI_TEXT_OPS_RETRACT_FR "Retract. :%Or" +#define UI_TEXT_OPS_BACKSLASH_FR "Backsl. :%Ob" +#define UI_TEXT_OPS_MINDIST_FR "Min.dist:%Od" +#define UI_TEXT_OPS_MOVE_AFTER_FR "Déplac. Apres:%Oa" +#define UI_TEXT_ANTI_OOZE_FR "Anti Ooze" +#define UI_TEXT_PRINT_FILE_FR "Imprim. fichier" +#define UI_TEXT_PAUSE_PRINT_FR "Pause Impress." +#define UI_TEXT_CONTINUE_PRINT_FR "Continuer Impress." +#define UI_TEXT_UNMOUNT_CARD_FR "Retirer Carte" +#define UI_TEXT_MOUNT_CARD_FR "Inserer Carte" +#define UI_TEXT_DELETE_FILE_FR "Supp. fichier" +#define UI_TEXT_FEEDRATE_FR "Avance" +#define UI_TEXT_FEED_MAX_X_FR "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_FR "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_FR "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_FR "Max:%fz" +#define UI_TEXT_FEED_HOME_X_FR "Accueil X:%fX" +#define UI_TEXT_FEED_HOME_Y_FR "Accueil Y:%fY" +#define UI_TEXT_FEED_HOME_Z_FR "Accueil Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_FR "Accueil:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_FR "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_FR "Min Butee:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_FR "Max Butee:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_FR "" +#define UI_TEXT_ACTION_YPOSITION4A_FR "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_FR "Min Butee:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_FR "Max Butee:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_FR "" +#define UI_TEXT_ACTION_ZPOSITION4A_FR "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_FR "Min Butee:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_FR "Max Butee:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_FR "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_FR "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_FR "Min Butee:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_FR "Max Butee:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_FR "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_FR "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_FR "Min Butee:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_FR "Max Butee:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_FR "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_FR "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_FR "Min Butee:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_FR "Max Butee:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_FR "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_FR "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_FR "1 clic = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_FR "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_FR "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_FR "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_FR "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_FR "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_FR "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_FR "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_FR "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_FR "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_FR "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_FR "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_FR "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_FR "Vit. Ventil." +#define UI_TEXT_ACTION_FANSPEED_FR "Vit. Ventil.:%Fs%%%" +#define UI_TEXT_FAN_OFF_FR "Arret Ventil." +#define UI_TEXT_FAN_25_FR "Ventil. 25%%%" +#define UI_TEXT_FAN_50_FR "Ventil. 50%%%" +#define UI_TEXT_FAN_75_FR "Ventil. 75%%%" +#define UI_TEXT_FAN_FULL_FR "Ventil. Max" +#define UI_TEXT_STEPPER_INACTIVE_FR "Arret Moteurs" +#define UI_TEXT_STEPPER_INACTIVE2A_FR "Dis. Apres: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_FR "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_FR "Arret Alim." +#define UI_TEXT_POWER_INACTIVE2A_FR "Dis. Apres: %ip" +#define UI_TEXT_POWER_INACTIVE2B_FR "[min] 0=Off" +#define UI_TEXT_GENERAL_FR "General" +#define UI_TEXT_BAUDRATE_FR "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_FR "Pas/MM:%Se" +#define UI_TEXT_EXTR_START_FEED_FR "Start FR:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_FR "Max FR:%XF" +#define UI_TEXT_EXTR_ACCEL_FR "Accel:%XA" +#define UI_TEXT_EXTR_WATCH_FR "Stab.Temps:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_FR "Avance lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_FR "Avance quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_FR "Controle:%Xh" +#define UI_TEXT_EXTR_PGAIN_FR "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_FR "Temps Mort:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_FR "PWM Control:%XM" +#define UI_TEXT_EXTR_IGAIN_FR "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_FR "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_FR "Drive Min:%Xm" +#define UI_TEXT_EXTR_DMAX_FR "Drive Max:%XM" +#define UI_TEXT_EXTR_PMAX_FR "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_FR "X-Offset:%Xx" +#define UI_TEXT_EXTR_YOFF_FR "Y-Offset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_FR "BangBang" +#define UI_TEXT_STRING_HM_PID_FR "PID" +#define UI_TEXT_STRING_ACTION_FR "Action:%la" +#define UI_TEXT_HEATING_EXTRUDER_FR "Chauff. Extrud." +#define UI_TEXT_HEATING_BED_FR "Chauff. Lit" +#define UI_TEXT_KILLED_FR "Stoppe" +#define UI_TEXT_STEPPER_DISABLED_FR "Moteurs Arretes" +#define UI_TEXT_EEPROM_STOREDA_FR "Configuration" +#define UI_TEXT_EEPROM_STOREDB_FR "Stock. Dans EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_FR "Configuration" +#define UI_TEXT_EEPROM_LOADEDB_FR "Charg. f. EEPROM" +#define UI_TEXT_UPLOADING_FR "Telechargement.." +#define UI_TEXT_PAGE_BUFFER_FR "Tampon:%oB" +#define UI_TEXT_PAGE_EXTRUDER_FR " E:%ec/%Ec\002C\176%oC" +#define UI_TEXT_PAGE_EXTRUDER1_FR "E1:%e0/%E0\002C\176%o0" +#define UI_TEXT_PAGE_EXTRUDER2_FR "E2:%e1/%E1\002C\176%o1" +#define UI_TEXT_PAGE_EXTRUDER3_FR "E3:%e2/%E2\002C\176%o2" +#define UI_TEXT_PAGE_BED_FR " B:%eb/%Eb\002C\176%ob" +#define UI_TEXT_SPEED_MULTIPLY_FR "Vit. Mul.:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_FR "Flow Mul.:%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_FR "Montrer Mesure" +#define UI_TEXT_RESET_MEASUREMENT_FR "Reset Mesure" +#define UI_TEXT_SET_MEASURED_ORIGIN_FR "Regler Z=0" +#define UI_TEXT_ZCALIB_FR "Z Calib." +#define UI_TEXT_SET_P1_FR "Regler P1" +#define UI_TEXT_SET_P2_FR "Regler P2" +#define UI_TEXT_SET_P3_FR "Regler P3" +#define UI_TEXT_CALCULATE_LEVELING_FR "Calculer Nivellement" +#define UI_TEXT_LEVEL_FR "Niveau delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_FR "Att. Temp.%XT\002C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_FR "Att. Units:%XUmm" +#define UI_TEXT_SD_REMOVED_FR "Carte SD retiree" +#define UI_TEXT_SD_INSERTED_FR "Carte SD inseree" +#define UI_TEXT_PRINTER_READY_FR "imprimante prete" +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_FR " jours " +#define UI_TEXT_PRINTTIME_HOURS_FR ":" +#define UI_TEXT_PRINTTIME_MINUTES_FR "" +#define UI_TEXT_PRINT_TIME_FR "Temps Impression" +#define UI_TEXT_PRINT_FILAMENT_FR "Filament Imprime" +#define UI_TEXT_PRINTED_FR "Imprime" +#define UI_TEXT_POWER_FR "ATX power on/off" +#define UI_TEXT_STRING_HM_DEADTIME_FR "Temps Mort" +#define UI_TEXT_STRING_HM_SLOWBANG_FR "Tout ou Rien" +#define UI_TEXT_STOP_PRINT_FR "Arret Impress." +#define UI_TEXT_Z_BABYSTEPPING_FR "Z Babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_FR "Changement Filament" +#define UI_TEXT_WIZ_CH_FILAMENT1_FR "Changement Filament" +#define UI_TEXT_WIZ_CH_FILAMENT2_FR "Tournez Deplacer" +#define UI_TEXT_WIZ_CH_FILAMENT3_FR "Filament haut/bas" +#define UI_TEXT_CLICK_DONE_FR "Continuer avec Clic" +#define UI_TEXT_AUTOLEVEL_ONOFF_FR "Autolevel: %ll" +#define UI_TEXT_SERVOPOS_FR "Pos. Servo: %oS" +#define UI_TEXT_IGNORE_M106_FR "Ignorer M106 %Fi" +#define UI_TEXT_WIZ_REHEAT1_FR "Cliquez pour" +#define UI_TEXT_WIZ_REHEAT2_FR "Rechauffer Extrud." +#define UI_TEXT_WIZ_WAITTEMP1_FR "Attendez Temp." +#define UI_TEXT_WIZ_WAITTEMP2_FR "cibles ..." +#define UI_TEXT_EXTRUDER_JAM_FR "Stockage d'Extrusion" +#define UI_TEXT_STANDBY_FR "Standby" +#define UI_TEXT_BED_COATING_FR "Revetement de Lit" +#define UI_TEXT_BED_COATING_SET1_FR "Revetement de Lit:" +#define UI_TEXT_BED_COATING_SET2_FR "" +#define UI_TEXT_NOCOATING_FR "Aucun Revetement" +#define UI_TEXT_BUILDTAK_FR "BuildTak" +#define UI_TEXT_KAPTON_FR "Kapton" +#define UI_TEXT_BLUETAPE_FR "Blue Tape" +#define UI_TEXT_PETTAPE_FR "Ruban vert PET" +#define UI_TEXT_GLUESTICK_FR "Baton de Colle" +#define UI_TEXT_CUSTOM_FR "Coutume" +#define UI_TEXT_COATING_CUSTOM_FR "Coutume:%BCmm" +#define UI_TEXT_LANGUAGE_FR "Langue" + +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_FR "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_FR "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_FR "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_FR "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_FR " Y:%x1" +#endif +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_FR "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_FR "Copies: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_FR "Flow:\xfd %of%%% Z:%x2" +#endif +#define UI_TEXT_MAINPAGE6_4_FR "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_FR "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_FR "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_FR cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_FR "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_FR "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_FR "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_FR "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_FR "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_FR "%Uf m" +#define UI_TEXT_METER_PRINTED_FR "%Uf m " UI_TEXT_PRINTED_FR +#define UI_TEXT_STATUS_FR "%os" +#define UI_TEXT_EMPTY_FR "" +#define UI_TEXT_TEMP_SET_FR cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_FR cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_FR " %BCmm" +#define UI_TEXT_EXTR3_TEMP_FR "Temp. 4 :%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_FR "Temp. 5 :%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_FR "Temp. 6 :%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_FR "Extrudeuse 4 Off" +#define UI_TEXT_EXTR4_OFF_FR "Extrudeuse 5 Off" +#define UI_TEXT_EXTR5_OFF_FR "Extrudeuse 6 Off" +#define UI_TEXT_EXTR3_SELECT_FR "%X3 Select. Extr. 4" +#define UI_TEXT_EXTR4_SELECT_FR "%X4 Select. Extr. 5" +#define UI_TEXT_EXTR5_SELECT_FR "%X5 Select. Extr. 6" +#define UI_TEXT_DITTO_0_FR "%D0 Aucune Copie" +#define UI_TEXT_DITTO_1_FR "%D1 1 Copie" +#define UI_TEXT_DITTO_2_FR "%D2 2 Copies" +#define UI_TEXT_DITTO_3_FR "%D3 3 Copies" +#define UI_TEXT_ZPROBE_HEIGHT_FR "Hauteur Z-Sonde:%zh" + + + +#define UI_TEXT_OFFSETS_FR "Set print offsets" +#define UI_TEXT_X_OFFSET_FR "Set X offset:%T0mm" +#define UI_TEXT_Y_OFFSET_FR "Set Y offset:%T1mm" +#define UI_TEXT_Z_OFFSET_FR "Set Z offset:%T2mm" + + +// *************** Czech translation **************** +// *************** By Majkl **************** +// version: 2014/08/27 + + +#define UI_TEXT_ON_CZ "Zap" +#define UI_TEXT_OFF_CZ "Vyp" +#define UI_TEXT_NA_CZ "neni" // Output for not available +#define UI_TEXT_YES_CZ "Ano" +#define UI_TEXT_NO_CZ "Ne" +#define UI_TEXT_PRINT_POS_CZ "Tisknu..." +#define UI_TEXT_PRINTING_CZ "Tisknu" +#define UI_TEXT_IDLE_CZ "V klidu" +#define UI_TEXT_NOSDCARD_CZ "Neni SD karta" +#define UI_TEXT_ERROR_CZ "**** CHYBA ****" +#define UI_TEXT_BACK_CZ "Zpet \001" +#define UI_TEXT_QUICK_SETTINGS_CZ "Zakladni nastaveni" +#define UI_TEXT_ERRORMSG_CZ "%oe" +#define UI_TEXT_CONFIGURATION_CZ "Nastaveni" +#define UI_TEXT_POSITION_CZ "Pozice" +#define UI_TEXT_EXTRUDER_CZ "Extruder" +#define UI_TEXT_SD_CARD_CZ "SD karta" +#define UI_TEXT_DEBUGGING_CZ "Debug" +#define UI_TEXT_HOME_DELTA_CZ "Home delta" +#define UI_TEXT_HOME_ALL_CZ "Home vsech" +#define UI_TEXT_HOME_X_CZ "Home X" +#define UI_TEXT_HOME_Y_CZ "Home Y" +#define UI_TEXT_HOME_Z_CZ "Home Z" +#define UI_TEXT_PREHEAT_PLA_CZ "Ohrat pro PLA" +#define UI_TEXT_PREHEAT_ABS_CZ "Ohrat pro ABS" +#define UI_TEXT_LIGHTS_ONOFF_CZ "Svetla:%lo" +#define UI_TEXT_COOLDOWN_CZ "Zchladit" +#define UI_TEXT_SET_TO_ORIGIN_CZ "Nastavit pocatek" +#define UI_TEXT_DISABLE_STEPPER_CZ "Vypnout motory" +#define UI_TEXT_X_POSITION_CZ "X pozice" +#define UI_TEXT_X_POS_FAST_CZ "X rychle" +#define UI_TEXT_Y_POSITION_CZ "Y pozice" +#define UI_TEXT_Y_POS_FAST_CZ "Y rychle" +#define UI_TEXT_Z_POSITION_CZ "Z pozice" +#define UI_TEXT_Z_POS_FAST_CZ "Z rychle" +#define UI_TEXT_E_POSITION_CZ "Pozice extruderu" +#define UI_TEXT_BED_TEMP_CZ "Teplota desky: %Eb\002C" +#define UI_TEXT_EXTR0_TEMP_CZ "Teplota 1:%e0/%E0\002C" +#define UI_TEXT_EXTR1_TEMP_CZ "Teplota 2:%e1/%E1\002C" +#define UI_TEXT_EXTR2_TEMP_CZ "Teplota 3:%e2/%E2\002C" +#define UI_TEXT_EXTR0_OFF_CZ "Extruder 1 vyp." +#define UI_TEXT_EXTR1_OFF_CZ "Extruder 2 vyp." +#define UI_TEXT_EXTR2_OFF_CZ "Extruder 3 vyp." +#define UI_TEXT_EXTR0_SELECT_CZ "%X0 Zvolit Extr. 1" +#define UI_TEXT_EXTR1_SELECT_CZ "%X1 Zvolit Extr. 2" +#define UI_TEXT_EXTR2_SELECT_CZ "%X1 Zvolit Extr. 3" +#define UI_TEXT_EXTR_ORIGIN_CZ "Nastavit pocatek" +#define UI_TEXT_PRINT_X_CZ "Tisk X:%ax" +#define UI_TEXT_PRINT_Y_CZ "Tisk Y:%ay" +#define UI_TEXT_PRINT_Z_CZ "Tisk Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_CZ "Tisk:%az" +#define UI_TEXT_MOVE_X_CZ "Posun X:%aX" +#define UI_TEXT_MOVE_Y_CZ "Posun Y:%aY" +#define UI_TEXT_MOVE_Z_CZ "Posun Z:%aZ" +#define UI_TEXT_MOVE_Z_DELTA_CZ "Posun:%aZ" +#define UI_TEXT_JERK_CZ "Jerk:%aj" +#define UI_TEXT_ZJERK_CZ "Z-Jerk:%aJ" +#define UI_TEXT_ACCELERATION_CZ "Akcelerace" +#define UI_TEXT_STORE_TO_EEPROM_CZ "Ulozit do EEPROM" +#define UI_TEXT_LOAD_EEPROM_CZ "Nahrat z EEPROM" +#define UI_TEXT_DBG_ECHO_CZ "Echo :%do" +#define UI_TEXT_DBG_INFO_CZ "Info :%di" +#define UI_TEXT_DBG_ERROR_CZ "Chyby :%de" +#define UI_TEXT_DBG_DRYRUN_CZ "Beh nanecisto:%dd" +#define UI_TEXT_OPS_OFF_CZ "%O0 OPS Vypnuto" +#define UI_TEXT_OPS_CLASSIC_CZ "%O1 OPS Klasicke" +#define UI_TEXT_OPS_FAST_CZ "%O2 OPS Rychle" +#define UI_TEXT_OPS_RETRACT_CZ "Retrakce :%Or" +#define UI_TEXT_OPS_BACKSLASH_CZ "Vule. :%Ob" +#define UI_TEXT_OPS_MINDIST_CZ "Min.vzd,:%Od" +#define UI_TEXT_OPS_MOVE_AFTER_CZ "Posunuti po:%Oa" +#define UI_TEXT_ANTI_OOZE_CZ "Proti kapani" +#define UI_TEXT_PRINT_FILE_CZ "Tisknout soubor" +#define UI_TEXT_PAUSE_PRINT_CZ "Pozastavit tisk" +#define UI_TEXT_CONTINUE_PRINT_CZ "Pokracovani tisku" +#define UI_TEXT_UNMOUNT_CARD_CZ "Odpojit kartu" +#define UI_TEXT_MOUNT_CARD_CZ "Pripojit kartu" +#define UI_TEXT_DELETE_FILE_CZ "Smazat soubor" +#define UI_TEXT_FEEDRATE_CZ "Rychlost" +#define UI_TEXT_FEED_MAX_X_CZ "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_CZ "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_CZ "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_CZ "Max:%fz" +#define UI_TEXT_FEED_HOME_X_CZ "Home X:%fX" +#define UI_TEXT_FEED_HOME_Y_CZ "Home Y:%fY" +#define UI_TEXT_FEED_HOME_Z_CZ "Home Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_CZ "Home:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_CZ "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_CZ "Min koncak:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_CZ "Max koncak:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_CZ "" +#define UI_TEXT_ACTION_YPOSITION4A_CZ "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_CZ "Min koncak:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_CZ "Max koncak:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_CZ "" +#define UI_TEXT_ACTION_ZPOSITION4A_CZ "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_CZ "Min koncak:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_CZ "Max koncak:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_CZ "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_CZ "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_CZ "Min koncak:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_CZ "Max koncak:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_CZ "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_CZ "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_CZ "Min koncak:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_CZ "Max koncak:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_CZ "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_CZ "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_CZ "Min koncak:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_CZ "Max koncak:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_CZ "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_CZ "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_CZ "1 kliknuti = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_CZ "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_CZ "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_CZ "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_CZ "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_CZ "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_CZ "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_CZ "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_CZ "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_CZ "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_CZ "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_CZ "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_CZ "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_CZ "Rychlost vetraku" +#define UI_TEXT_ACTION_FANSPEED_CZ "Aktualni rychlost:%Fs%%%" +#define UI_TEXT_FAN_OFF_CZ "Vypnout" +#define UI_TEXT_FAN_25_CZ "Vetrak na 25%%%" +#define UI_TEXT_FAN_50_CZ "Vetrak na 50%%%" +#define UI_TEXT_FAN_75_CZ "Vetrak na 75%%%" +#define UI_TEXT_FAN_FULL_CZ "Vetrak na plno" +#define UI_TEXT_STEPPER_INACTIVE_CZ "Neaktivni motory" +#define UI_TEXT_STEPPER_INACTIVE2A_CZ "Vypnout po :%i m" +#define UI_TEXT_STEPPER_INACTIVE2B_CZ "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_CZ "Max. neaktivni" +#define UI_TEXT_POWER_INACTIVE2A_CZ "Vypnout po: %i m" +#define UI_TEXT_POWER_INACTIVE2B_CZ "[min] 0=Off" +#define UI_TEXT_GENERAL_CZ "Zakladni" +#define UI_TEXT_BAUDRATE_CZ "Rychlost:%oc" +#define UI_TEXT_EXTR_STEPS_CZ "kroku/MM:%Se" +#define UI_TEXT_EXTR_START_FEED_CZ "Start FR:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_CZ "Max FR:%XF" +#define UI_TEXT_EXTR_ACCEL_CZ "Zrychl.:%XA" +#define UI_TEXT_EXTR_WATCH_CZ "Stab.cas:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_CZ "Rozsir. lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_CZ "Rozsir. quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_CZ "Control:%Xh" +#define UI_TEXT_EXTR_PGAIN_CZ "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_CZ "Mrtva doba:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_CZ "Ovladani PWM:%XM" +#define UI_TEXT_EXTR_IGAIN_CZ "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_CZ "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_CZ "Drive Min:%Xm" +#define UI_TEXT_EXTR_DMAX_CZ "Drive Max:%XM" +#define UI_TEXT_EXTR_PMAX_CZ "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_CZ "X-Offset:%Xx" +#define UI_TEXT_EXTR_YOFF_CZ "Y-Offset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_CZ "BangBang" +#define UI_TEXT_STRING_HM_PID_CZ "PID" +#define UI_TEXT_STRING_ACTION_CZ "Akce:%la" +#define UI_TEXT_HEATING_EXTRUDER_CZ "Ohrivani extruderu" +#define UI_TEXT_HEATING_BED_CZ "Ohrivani desky" +#define UI_TEXT_KILLED_CZ "Zastaveno" +#define UI_TEXT_STEPPER_DISABLED_CZ "Motor vypnut" +#define UI_TEXT_EEPROM_STOREDA_CZ "Konfigurace" +#define UI_TEXT_EEPROM_STOREDB_CZ "Ulozena v EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_CZ "Konfigurace" +#define UI_TEXT_EEPROM_LOADEDB_CZ "Nactena z EEPROM" +#define UI_TEXT_UPLOADING_CZ "Nahravam..." +#define UI_TEXT_PAGE_BUFFER_CZ "Buffer:%oB" +#define UI_TEXT_PAGE_EXTRUDER_CZ " E:%ec/%Ec\002C\176%oC" +#define UI_TEXT_PAGE_EXTRUDER1_CZ "E1:%e0/%E0\002C\176%o0" +#define UI_TEXT_PAGE_EXTRUDER2_CZ "E2:%e1/%E1\002C\176%o1" +#define UI_TEXT_PAGE_EXTRUDER3_CZ "E3:%e2/%E2\002C\176%o2" +#define UI_TEXT_PAGE_BED_CZ " B:%eb/%Eb\002C\176%ob" +#define UI_TEXT_SPEED_MULTIPLY_CZ "Rychlost:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_CZ "Flow nasobit:%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_CZ "Ukazat merení" +#define UI_TEXT_RESET_MEASUREMENT_CZ "Obnovit mereni" +#define UI_TEXT_SET_MEASURED_ORIGIN_CZ "Set Z=0" +#define UI_TEXT_ZCALIB_CZ "Z kalib." +#define UI_TEXT_SET_P1_CZ "Set P1" +#define UI_TEXT_SET_P2_CZ "Set P2" +#define UI_TEXT_SET_P3_CZ "Set P3" +#define UI_TEXT_CALCULATE_LEVELING_CZ "Vypocitat leveling" +#define UI_TEXT_LEVEL_CZ "Level delta" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_CZ "Tepl. cekani%XT\002C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_CZ "Jedn. cekani:%XUmm" +#define UI_TEXT_SD_REMOVED_CZ "SD karta vyjmuta." +#define UI_TEXT_SD_INSERTED_CZ "Vlozena SD karta" +#define UI_TEXT_PRINTER_READY_CZ "Tiskarna OK" +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_CZ " dnu " +#define UI_TEXT_PRINTTIME_HOURS_CZ ":" +#define UI_TEXT_PRINTTIME_MINUTES_CZ "" +#define UI_TEXT_PRINT_TIME_CZ "Cas tisku" +#define UI_TEXT_PRINT_FILAMENT_CZ "Filament tisteny" +#define UI_TEXT_PRINTED_CZ "Protisknuto" +#define UI_TEXT_POWER_CZ "Zapnout ATX zdroj" +#define UI_TEXT_STRING_HM_DEADTIME_CZ "Dead Time" +#define UI_TEXT_STRING_HM_SLOWBANG_CZ "SlowBang" +#define UI_TEXT_STOP_PRINT_CZ "Zastavit tisk" +#define UI_TEXT_Z_BABYSTEPPING_CZ "Z babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_CZ "Zmena filament" +#define UI_TEXT_WIZ_CH_FILAMENT1_CZ "Zmena filament" +#define UI_TEXT_WIZ_CH_FILAMENT2_CZ "Otocit se pohybovat" +#define UI_TEXT_WIZ_CH_FILAMENT3_CZ "vlaken nahoru/dolu" +#define UI_TEXT_CLICK_DONE_CZ "Pokr. s cvaknutim" +#define UI_TEXT_AUTOLEVEL_ONOFF_CZ "Autolevel: %ll" +#define UI_TEXT_SERVOPOS_CZ "Servo pozice: %oS" +#define UI_TEXT_IGNORE_M106_CZ "Ignorovat M106 %Fi" +#define UI_TEXT_WIZ_REHEAT1_CZ "Klikněte ohrat" +#define UI_TEXT_WIZ_REHEAT2_CZ "extruders." +#define UI_TEXT_WIZ_WAITTEMP1_CZ "Pockejte na cilove" +#define UI_TEXT_WIZ_WAITTEMP2_CZ "teploty ..." +#define UI_TEXT_EXTRUDER_JAM_CZ "Extruder jam" +#define UI_TEXT_STANDBY_CZ "Standby" +#define UI_TEXT_BED_COATING_CZ "Postel nater" +#define UI_TEXT_BED_COATING_SET1_CZ "Postel nater:" +#define UI_TEXT_BED_COATING_SET2_CZ "" +#define UI_TEXT_NOCOATING_CZ "No nater" +#define UI_TEXT_BUILDTAK_CZ "BuildTak" +#define UI_TEXT_KAPTON_CZ "Kapton" +#define UI_TEXT_BLUETAPE_CZ "Modra mask. paska" +#define UI_TEXT_PETTAPE_CZ "Zelena PET paska" +#define UI_TEXT_GLUESTICK_CZ "Lepici tycinka" +#define UI_TEXT_CUSTOM_CZ "Vlastni" +#define UI_TEXT_COATING_CUSTOM_CZ "Vlastni:%BCmm" +#define UI_TEXT_LANGUAGE_CZ "Jazyk" + +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_CZ "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_CZ "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_CZ "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_CZ "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_CZ " Y:%x1" +#endif +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_CZ "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_CZ "Kopii: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_CZ "Flow:\xfd %of%%% Z:%x2" +#endif +#define UI_TEXT_MAINPAGE6_4_CZ "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_CZ "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_CZ "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_CZ cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_CZ "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_CZ "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_CZ "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_CZ "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_CZ "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_CZ "%Uf m" +#define UI_TEXT_METER_PRINTED_CZ "%Uf m " UI_TEXT_PRINTED_CZ +#define UI_TEXT_STATUS_CZ "%os" +#define UI_TEXT_EMPTY_CZ "" +#define UI_TEXT_TEMP_SET_CZ cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_CZ cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_CZ " %BCmm" +#define UI_TEXT_EXTR3_TEMP_CZ "Teplota 4:%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_CZ "Teplota 5:%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_CZ "Teplota 6:%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_CZ "Extruder 4 vyp." +#define UI_TEXT_EXTR4_OFF_CZ "Extruder 5 vyp." +#define UI_TEXT_EXTR5_OFF_CZ "Extruder 6 vyp." +#define UI_TEXT_EXTR3_SELECT_CZ "%X3 Zvolit Extr. 4" +#define UI_TEXT_EXTR4_SELECT_CZ "%X4 Zvolit Extr. 5" +#define UI_TEXT_EXTR5_SELECT_CZ "%X5 Zvolit Extr. 6" +#define UI_TEXT_DITTO_0_CZ "%D0 Zadne Kopie" +#define UI_TEXT_DITTO_1_CZ "%D1 1 Kopie" +#define UI_TEXT_DITTO_2_CZ "%D2 2 Kopii" +#define UI_TEXT_DITTO_3_CZ "%D3 3 Kopii" +#define UI_TEXT_ZPROBE_HEIGHT_CZ "Vyska z-test:%zh" + +#define UI_TEXT_OFFSETS_CZ "Set print offsets" +#define UI_TEXT_X_OFFSET_CZ "Set X offset:%T0mm" +#define UI_TEXT_Y_OFFSET_CZ "Set Y offset:%T1mm" +#define UI_TEXT_Z_OFFSET_CZ "Set Z offset:%T2mm" + + +// *************** Polish translation **************** +// *************** By MIS **************** +// version: 2015/01/18 + +#define UI_TEXT_ON_PL "Zal" +#define UI_TEXT_OFF_PL "Wyl" +#define UI_TEXT_NA_PL "Brak" // Output for not available +#define UI_TEXT_YES_PL "Tak" +#define UI_TEXT_NO_PL "Nie" +#define UI_TEXT_PRINT_POS_PL "Drukowanie..." +#define UI_TEXT_PRINTING_PL "Drukowanie" +#define UI_TEXT_IDLE_PL "Wolna" +#define UI_TEXT_NOSDCARD_PL "Brak karty SD" +#define UI_TEXT_ERROR_PL "**** BLAD ****" +#define UI_TEXT_BACK_PL "Powrot " cUP +#define UI_TEXT_QUICK_SETTINGS_PL "Szybkie ustawienia" +#define UI_TEXT_ERRORMSG_PL "%oe" +#define UI_TEXT_CONFIGURATION_PL "Konfiguracja" +#define UI_TEXT_POSITION_PL "Pozycja" +#define UI_TEXT_EXTRUDER_PL "Ekstruder" +#define UI_TEXT_SD_CARD_PL "Karta SD" +#define UI_TEXT_DEBUGGING_PL "Testowanie" +#define UI_TEXT_HOME_DELTA_PL "Home delta" +#define UI_TEXT_HOME_ALL_PL "Zeruj wszystkie osie" +#define UI_TEXT_HOME_X_PL "Zeruj X" +#define UI_TEXT_HOME_Y_PL "Zeruj Y" +#define UI_TEXT_HOME_Z_PL "Zeruj Z" +#define UI_TEXT_PREHEAT_PLA_PL "Rozgrzej PLA" +#define UI_TEXT_PREHEAT_ABS_PL "Rozgrzej ABS" +#define UI_TEXT_LIGHTS_ONOFF_PL "Oswietlenie :%lo" +#define UI_TEXT_COOLDOWN_PL "Chlodzenie" +#define UI_TEXT_SET_TO_ORIGIN_PL "Ustaw jako zero" +#define UI_TEXT_DISABLE_STEPPER_PL "Wylacz silniki" +#define UI_TEXT_X_POSITION_PL "Pozycja X" +#define UI_TEXT_X_POS_FAST_PL "Pozycja X Szybko" +#define UI_TEXT_Y_POSITION_PL "Pozycja Y" +#define UI_TEXT_Y_POS_FAST_PL "Pozycja Y Szybko" +#define UI_TEXT_Z_POSITION_PL "Pozycja Z" +#define UI_TEXT_Z_POS_FAST_PL "Pozycja Z Szybko" +#define UI_TEXT_E_POSITION_PL "Pozycja Extrudera" +#define UI_TEXT_BED_TEMP_PL "Temp.Stolu:%eb/%Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_PL "Temp.Ex1:%e0/%E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_PL "Temp.Ex2:%e1/%E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_PL "Temp.Ex3:%e2/%E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_PL "Wyl. Extruder 1" +#define UI_TEXT_EXTR1_OFF_PL "Wyl. Extruder 2" +#define UI_TEXT_EXTR2_OFF_PL "Wyl. Extruder 3" +#define UI_TEXT_EXTR0_SELECT_PL "%X0 Wybierz Extr. 1" +#define UI_TEXT_EXTR1_SELECT_PL "%X1 Wybierz Extr. 2" +#define UI_TEXT_EXTR2_SELECT_PL "%X1 Wybierz Extr. 3" +#define UI_TEXT_EXTR_ORIGIN_PL "Ustaw jako zero" +#define UI_TEXT_PRINT_X_PL "Drukow. X :%ax" +#define UI_TEXT_PRINT_Y_PL "Drukow. Y :%ay" +#define UI_TEXT_PRINT_Z_PL "Drukow. Z :%az" +#define UI_TEXT_PRINT_Z_DELTA_PL "Drukowania :%az" +#define UI_TEXT_MOVE_X_PL "Przesuw. X :%aX" +#define UI_TEXT_MOVE_Y_PL "Przesuw. Y :%aY" +#define UI_TEXT_MOVE_Z_PL "Przesuw. Z :%aZ" +#define UI_TEXT_MOVE_Z_DELTA_PL "Przesuwania :%aZ" +#define UI_TEXT_JERK_PL "Jerk:%aj" +#define UI_TEXT_ZJERK_PL "Z-Jerk:%aJ" +#define UI_TEXT_ACCELERATION_PL "Przyspieszenie" +#define UI_TEXT_STORE_TO_EEPROM_PL "Zapisz do EEPROM" +#define UI_TEXT_LOAD_EEPROM_PL "Odczyt z EEPROM" +#define UI_TEXT_DBG_ECHO_PL "Echo : %do" +#define UI_TEXT_DBG_INFO_PL "Informacje : %di" +#define UI_TEXT_DBG_ERROR_PL "Bledy : %de" +#define UI_TEXT_DBG_DRYRUN_PL "Bez wydruku : %dd" +#define UI_TEXT_OPS_OFF_PL "%O0 OPS Off" +#define UI_TEXT_OPS_CLASSIC_PL "%O1 OPS Classic" +#define UI_TEXT_OPS_FAST_PL "%O2 OPS Fast" +#define UI_TEXT_OPS_RETRACT_PL "Retract :%Or" +#define UI_TEXT_OPS_BACKSLASH_PL "Backsl. :%Ob" +#define UI_TEXT_OPS_MINDIST_PL "Min.dist:%Od" +#define UI_TEXT_OPS_MOVE_AFTER_PL "Przesun po:%Oa" +#define UI_TEXT_ANTI_OOZE_PL "Anti Ooze" +#define UI_TEXT_PRINT_FILE_PL "Drukuj z pliku" +#define UI_TEXT_PAUSE_PRINT_PL "Wstrzymaj druk" +#define UI_TEXT_CONTINUE_PRINT_PL "Wznow drukow." +#define UI_TEXT_UNMOUNT_CARD_PL "Odmontuj karte" +#define UI_TEXT_MOUNT_CARD_PL "Zamontuj karte" +#define UI_TEXT_DELETE_FILE_PL "Usun plik" +#define UI_TEXT_FEEDRATE_PL "Szybkosc" +#define UI_TEXT_FEED_MAX_X_PL "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_PL "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_PL "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_PL "Max:%fz" +#define UI_TEXT_FEED_HOME_X_PL "Powrot X:%fX" +#define UI_TEXT_FEED_HOME_Y_PL "Powrot Y:%fY" +#define UI_TEXT_FEED_HOME_Z_PL "Powrot Z:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_PL "Powrot:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_PL "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_PL "Krancowka MIN: %sx" +#define UI_TEXT_ACTION_XPOSITION4C_PL "Krancowka MAX: %sX" +#define UI_TEXT_ACTION_XPOSITION4D_PL "" +#define UI_TEXT_ACTION_YPOSITION4A_PL "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_PL "Krancowka MIN: %sy" +#define UI_TEXT_ACTION_YPOSITION4C_PL "Krancowka Max: %sY" +#define UI_TEXT_ACTION_YPOSITION4D_PL "" +#define UI_TEXT_ACTION_ZPOSITION4A_PL "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_PL "Krancowka MIN: %sz" +#define UI_TEXT_ACTION_ZPOSITION4C_PL "Krancowka Max: %sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_PL "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_PL "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_PL "Krancowka MIN: %sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_PL "Krancowka MAX: %sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_PL "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_PL "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_PL "Krancowka MIN: %sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_PL "Krancowka MAX: %sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_PL "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_PL "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_PL "Krancowka MIN: %sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_PL "Krancowka MAX: %sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_PL "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_PL "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_PL "Jednostka 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_PL "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_PL "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_PL "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_PL "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_PL "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_PL "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_PL "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_PL "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_PL "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_PL "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_PL "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_PL "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_PL "Obroty wiatraka" +#define UI_TEXT_ACTION_FANSPEED_PL "Obroty wiatraka:%Fs%%%" +#define UI_TEXT_FAN_OFF_PL "Wylacz wiatrak" +#define UI_TEXT_FAN_25_PL "Ustaw na 25%%%" +#define UI_TEXT_FAN_50_PL "Ustaw na 50%%%" +#define UI_TEXT_FAN_75_PL "Ustaw na 75%%%" +#define UI_TEXT_FAN_FULL_PL "Ustaw na 100%%%" +#define UI_TEXT_STEPPER_INACTIVE_PL "Wylacz silniki po" +#define UI_TEXT_STEPPER_INACTIVE2A_PL "Wylacz po: %is min." +#define UI_TEXT_STEPPER_INACTIVE2B_PL "0=Nie wylaczaj" +#define UI_TEXT_POWER_INACTIVE_PL "Wylacz zasil. po" +#define UI_TEXT_POWER_INACTIVE2A_PL "Wylacz po: %ip min." +#define UI_TEXT_POWER_INACTIVE2B_PL "0=Nie wylaczaj" +#define UI_TEXT_GENERAL_PL "Ustawienia glowne" +#define UI_TEXT_BAUDRATE_PL "Szybkosc USB:%oc" +#define UI_TEXT_EXTR_STEPS_PL "Kroki/mm : %Se" +#define UI_TEXT_EXTR_START_FEED_PL "Poczatkowa SZ:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_PL "Max Szybkosc :%XF" +#define UI_TEXT_EXTR_ACCEL_PL "Przyspiesz. :%XA" +#define UI_TEXT_EXTR_WATCH_PL "Czas stabil. :%Xws" +#define UI_TEXT_EXTR_ADVANCE_L_PL "Advance lin :%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_PL "Advance quad :%Xa" +#define UI_TEXT_EXTR_MANAGER_PL "Regulator:%Xh" +#define UI_TEXT_EXTR_DEADTIME_PL "Deadtime :%Xp" +#define UI_TEXT_EXTR_DMAX_DT_PL "Max. PWM :%XD" +#define UI_TEXT_EXTR_PGAIN_PL "PID P :%Xp" +#define UI_TEXT_EXTR_IGAIN_PL "PID I :%Xi" +#define UI_TEXT_EXTR_DGAIN_PL "PID D :%Xd" +#define UI_TEXT_EXTR_DMIN_PL "Min I war: %Xm" +#define UI_TEXT_EXTR_DMAX_PL "Max I war: %XM" +#define UI_TEXT_EXTR_PMAX_PL "Max ster.: %XD" +#define UI_TEXT_EXTR_XOFF_PL "Ofset X :%Xx" +#define UI_TEXT_EXTR_YOFF_PL "Ofset Y :%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_PL "Dwustanowy" +#define UI_TEXT_STRING_HM_PID_PL "PID" +#define UI_TEXT_STRING_ACTION_PL "Akcja:%la" +#define UI_TEXT_HEATING_EXTRUDER_PL "Grzanie glowicy" +#define UI_TEXT_HEATING_BED_PL "Grzanie stolu" +#define UI_TEXT_KILLED_PL "Zatrzymany" +#define UI_TEXT_STEPPER_DISABLED_PL "Silniki wylaczone" +#define UI_TEXT_EEPROM_STOREDA_PL "Konfiguracja" +#define UI_TEXT_EEPROM_STOREDB_PL "zapisana do EEPROM" +#define UI_TEXT_EEPROM_LOADEDA_PL "Konfiguracja" +#define UI_TEXT_EEPROM_LOADEDB_PL "odczytana z EEPROM" +#define UI_TEXT_UPLOADING_PL "Ladowanie..." +#define UI_TEXT_PAGE_BUFFER_PL "Bufor:%oB" +#define UI_TEXT_PAGE_EXTRUDER_PL " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_PL "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_PL "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_PL "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_PL " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_PL "Szybkosc druku :%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_PL "Przeplyw filam.:%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_PL "Pokaz pomiar" +#define UI_TEXT_RESET_MEASUREMENT_PL "Zeruj pomiar" +#define UI_TEXT_SET_MEASURED_ORIGIN_PL "Ustaw Z=0" +#define UI_TEXT_ZCALIB_PL "Z kalib." +#define UI_TEXT_SET_P1_PL "Ustaw P1" +#define UI_TEXT_SET_P2_PL "Ustaw P2" +#define UI_TEXT_SET_P3_PL "Ustaw P3" +#define UI_TEXT_CALCULATE_LEVELING_PL "Oblicz poziomowania" +#define UI_TEXT_LEVEL_PL "Poziom delty" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_PL "MinTemp wysuwu:%XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_PL "Wysuw rozgrzew:%XUmm" +#define UI_TEXT_SD_REMOVED_PL "Karta SD wyjeta" +#define UI_TEXT_SD_INSERTED_PL "Karta SD wlozona" +#define UI_TEXT_PRINTER_READY_PL "Drukarka gotowa" // Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES // ___88 days 12:45 -#define UI_TEXT_PRINTTIME_DAYS " days " -#define UI_TEXT_PRINTTIME_HOURS ":" -#define UI_TEXT_PRINTTIME_MINUTES "" -#define UI_TEXT_PRINT_TIME "Printing time" -#define UI_TEXT_PRINT_FILAMENT "Filament printed" -#define UI_TEXT_PRINTED "printed" -#define UI_TEXT_POWER "ATX power on/off" -#define UI_TEXT_STRING_HM_DEADTIME "Dead Time" -#define UI_TEXT_STRING_HM_SLOWBANG "SlowBang" -#define UI_TEXT_STOP_PRINT "Stop Print" -#define UI_TEXT_Z_BABYSTEPPING "Z Babystep.:%oYmm" -#define UI_TEXT_CHANGE_FILAMENT "Change filament" -#define UI_TEXT_WIZ_CH_FILAMENT1 "Change filament" -#define UI_TEXT_WIZ_CH_FILAMENT2 "Rotate to move" -#define UI_TEXT_WIZ_CH_FILAMENT3 "filament up/down" -#define UI_TEXT_CLICK_DONE "Click when done" -#define UI_TEXT_AUTOLEVEL_ONOFF "Autolevel: %ll" -#define UI_TEXT_SERVOPOS "Servo pos.: %oS" -#define UI_TEXT_IGNORE_M106 "Ignore M106 cmd %Fi" -#define UI_TEXT_WIZ_REHEAT1 "Click to reheat" -#define UI_TEXT_WIZ_REHEAT2 "extruders." -#define UI_TEXT_WIZ_WAITTEMP1 "Wait for target" -#define UI_TEXT_WIZ_WAITTEMP2 "temperatures ..." -#define UI_TEXT_EXTRUDER_JAM "Extruder Jam" -#define UI_TEXT_STANDBY "Standby" - -// *************** 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 " cUP -#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_LIGHTS_ONOFF "Lampen: %lo" -#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" cDEG "C" -#define UI_TEXT_EXTR0_TEMP "Temp. 1 : %E0" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 2 : %E1" cDEG "C" -#define UI_TEXT_EXTR2_TEMP "Temp. 3 : %E2" cDEG "C" -#define UI_TEXT_EXTR0_OFF "Extruder 1 Aus" -#define UI_TEXT_EXTR1_OFF "Extruder 2 Aus" -#define UI_TEXT_EXTR2_OFF "Extruder 3 Aus" -#define UI_TEXT_EXTR0_SELECT "W" STR_auml "hle Extr. 1" -#define UI_TEXT_EXTR1_SELECT "W" STR_auml "hle Extr. 2" -#define UI_TEXT_EXTR2_SELECT "W" STR_auml "hle Extr. 3" -#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_PRINT_Z_DELTA "Drucken:%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_MOVE_Z_DELTA "Bewegen:%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_MAX_Z_DELTA "Max:%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_FEED_HOME_Z_DELTA "Home:%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_ACTION_FANSPEED "L" STR_uuml "fter:%Fs%%%" -#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","[min] 0=Aus" -#define UI_TEXT_POWER_INACTIVE "Max. Inaktiv" -#define UI_TEXT_POWER_INACTIVE2 "Aus nach: %ip","[min] 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_DEADTIME "Totzeit:%Xp" -#define UI_TEXT_EXTR_DMAX_DT "Controll-PWM:%XM" -#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" cDEG "C" cARROW "%oC" -#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0" cDEG "C" cARROW "%o0" -#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1" cDEG "C" cARROW "%o1" -#define UI_TEXT_PAGE_EXTRUDER3 "E3:%e2/%E2" cDEG "C" cARROW "%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb" cDEG "C" cARROW "%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 Z=0" -#define UI_TEXT_ZCALIB "Z 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" cDEG "C" -#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 "\007 %PN bereit." -// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES -// ___88 days 12:45 -#define UI_TEXT_PRINTTIME_DAYS " Tage " -#define UI_TEXT_PRINTTIME_HOURS ":" -#define UI_TEXT_PRINTTIME_MINUTES "" -#define UI_TEXT_PRINT_TIME "Ges. Druckzeit" -#define UI_TEXT_PRINT_FILAMENT "Filament gedruckt" -#define UI_TEXT_PRINTED "gedruckt" -#define UI_TEXT_POWER "ATX Netzteil an/aus" -#define UI_TEXT_STRING_HM_DEADTIME "Totzeit" -#define UI_TEXT_STRING_HM_SLOWBANG "Langs.BB" -#define UI_TEXT_STOP_PRINT "Druck abbrechen" -#define UI_TEXT_Z_BABYSTEPPING "Z Babyschr.:%oYmm" -#define UI_TEXT_CHANGE_FILAMENT "Filamentwechsel" -#define UI_TEXT_WIZ_CH_FILAMENT1 "Filamentwechsel:" -#define UI_TEXT_WIZ_CH_FILAMENT2 "Zum man. f" STR_ouml "rdern" -#define UI_TEXT_WIZ_CH_FILAMENT3 "Men" STR_uuml "knopf drehen" -#define UI_TEXT_CLICK_DONE "Weiter mit Klick" -#define UI_TEXT_AUTOLEVEL_ONOFF "Autolevel: %ll" -#define UI_TEXT_SERVOPOS "Servo Pos.: %oS" -#define UI_TEXT_STANDBY "Bereitschaft" - +#define UI_TEXT_PRINTTIME_DAYS_PL " dni, " +#define UI_TEXT_PRINTTIME_HOURS_PL ":" +#define UI_TEXT_PRINTTIME_MINUTES_PL " h." +#define UI_TEXT_PRINT_TIME_PL "Czas pracy" +#define UI_TEXT_PRINT_FILAMENT_PL "Zuzyto filamentu" +#define UI_TEXT_PRINTED_PL "drukowane" +#define UI_TEXT_POWER_PL "Wl/Wyl zasilanie" +#define UI_TEXT_STRING_HM_DEADTIME_PL "Dead Time" +#define UI_TEXT_STRING_HM_SLOWBANG_PL "SlowBang" +#define UI_TEXT_STOP_PRINT_PL "Przerwij wydruk" +#define UI_TEXT_Z_BABYSTEPPING_PL "Doreguluj Z:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_PL "Zmiana filamentu" +#define UI_TEXT_WIZ_CH_FILAMENT1_PL "Zmien filament" +#define UI_TEXT_WIZ_CH_FILAMENT2_PL "Krec aby przesuwac" +#define UI_TEXT_WIZ_CH_FILAMENT3_PL "filament w gore/dol" +#define UI_TEXT_CLICK_DONE_PL "Kliknij jak gotowe" +#define UI_TEXT_AUTOLEVEL_ONOFF_PL "Autopoziomow.: %ll" +#define UI_TEXT_SERVOPOS_PL "Pozycja Serwa: %oS" +#define UI_TEXT_IGNORE_M106_PL "Ignoruj kom. M106 %Fi" +#define UI_TEXT_WIZ_REHEAT1_PL "Kliknij aby znów" +#define UI_TEXT_WIZ_REHEAT2_PL "rozgrzac ekstrudery" +#define UI_TEXT_WIZ_WAITTEMP1_PL "Poczekaj na zadane" +#define UI_TEXT_WIZ_WAITTEMP2_PL "temperatury ..." +#define UI_TEXT_EXTRUDER_JAM_PL "Ekstruder zablokowany" +#define UI_TEXT_STANDBY_PL "Standby" +#define UI_TEXT_BED_COATING_PL "Pokrycie stolu" +#define UI_TEXT_BED_COATING_SET1_PL "Wybierz material" +#define UI_TEXT_BED_COATING_SET2_PL "stolu:" +#define UI_TEXT_NOCOATING_PL "Czysty stol" +#define UI_TEXT_BUILDTAK_PL "BuildTak" +#define UI_TEXT_KAPTON_PL "Kapton" +#define UI_TEXT_BLUETAPE_PL "Nieb. tasma mask." +#define UI_TEXT_PETTAPE_PL "Zielona tasma PET" +#define UI_TEXT_GLUESTICK_PL "Klej w sztyfcie" +#define UI_TEXT_CUSTOM_PL "Inna" +#define UI_TEXT_COATING_CUSTOM_PL "Inna grubosc:%BCmm" +#define UI_TEXT_LANGUAGE_PL "Jezyk" +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 + #define UI_TEXT_MAINPAGE6_1_PL "\xa %ec/%Ec\xb0 X:%x0" +#else + #define UI_TEXT_MAINPAGE6_1_PL "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_2_PL "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED + #define UI_TEXT_MAINPAGE6_2_PL "\xe %eb/%Eb\xb0 Y:%x1" +#else + #define UI_TEXT_MAINPAGE6_2_PL " Y:%x1" #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 cSEL -#define UI_TEXT_NOSEL cUNSEL -#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 " cUP -#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" cDEG "C" -#define UI_TEXT_EXTR0_TEMP "Temp. 1: %E0" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 2: %E1" cDEG "C" -#define UI_TEXT_EXTR2_TEMP "Temp. 3: %E2" cDEG "C" -#define UI_TEXT_EXTR0_OFF "Extruder 1 Uit" -#define UI_TEXT_EXTR1_OFF "Extruder 2 Uit" -#define UI_TEXT_EXTR2_OFF "Extruder 3 Uit" -#define UI_TEXT_EXTR0_SELECT "%X0 Select Extr. 1" -#define UI_TEXT_EXTR1_SELECT "%X1 Select Extr. 2" -#define UI_TEXT_EXTR2_SELECT "%X2 Select Extr. 3" -#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_PRINT_Z_DELTA "Print:%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_MOVE_Z_DELTA "Beweeg:%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_MAX_Z_DELTA "Max:%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_FEED_HOME_Z_DELTA "Home:%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","[min] 0=Off" -#define UI_TEXT_POWER_INACTIVE "Max. Inactief" -#define UI_TEXT_POWER_INACTIVE2 "Zet uit na: %ip","[min] 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" cDEG "C" cARROW "%oC" -#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0" cDEG "C" cARROW "%o0" -#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1" cDEG "C" cARROW "%o1" -#define UI_TEXT_PAGE_EXTRUDER3 "E3:%e2/%E2" cDEG "C" cARROW "%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb" cDEG "C" cARROW "%ob" -#define UI_TEXT_SPEED_MULTIPLY "Snelh. Mul.:%om%%%" -#define UI_TEXT_FLOW_MULTIPLY "Flow Mul.:%of%%%" - +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 + #define UI_TEXT_MAINPAGE6_3_PL "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING + #define UI_TEXT_MAINPAGE6_3_PL "Kopie: %ed Z:%x2" +#else + #define UI_TEXT_MAINPAGE6_3_PL "Przep:\xfd %of%%% Z:%x2" #endif +#define UI_TEXT_MAINPAGE6_4_PL "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_PL "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_PL "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_PL cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_PL "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_PL "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_PL "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_PL "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_PL "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_PL "%Uf m" +#define UI_TEXT_METER_PRINTED_PL "%Uf m " UI_TEXT_PRINTED_PL +#define UI_TEXT_STATUS_PL "%os" +#define UI_TEXT_EMPTY_PL "" +#define UI_TEXT_TEMP_SET_PL cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_PL cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_PL " %BCmm" +#define UI_TEXT_EXTR3_TEMP_PL "Temp.Ex4:%e3/%E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_PL "Temp.Ex5:%e4/%E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_PL "Temp.Ex6:%e5/%E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_PL "Wyl. Extruder 4" +#define UI_TEXT_EXTR4_OFF_PL "Wyl. Extruder 5" +#define UI_TEXT_EXTR5_OFF_PL "Wyl. Extruder 6" +#define UI_TEXT_EXTR3_SELECT_PL "%X3 Wybierz Extr. 4" +#define UI_TEXT_EXTR4_SELECT_PL "%X4 Wybierz Extr. 5" +#define UI_TEXT_EXTR5_SELECT_PL "%X5 Wybierz Extr. 6" +#define UI_TEXT_DITTO_0_PL "%D0 Nie kopiuj" +#define UI_TEXT_DITTO_1_PL "%D1 1 Kopia" +#define UI_TEXT_DITTO_2_PL "%D2 2 Kopie" +#define UI_TEXT_DITTO_3_PL "%D3 3 Kopie" +#define UI_TEXT_ZPROBE_HEIGHT_PL "Wys. Sondy Z:%zh" -// *************** Brazilian portuguese translation **************** - -#if UI_LANGUAGE==3 - -#define UI_TEXT_ON "On" -#define UI_TEXT_OFF "Off" -#define UI_TEXT_NA "N/A" // Output for not available -#define UI_TEXT_YES "Sim" -#define UI_TEXT_NO "Não" -#define UI_TEXT_SEL cSEL -#define UI_TEXT_NOSEL cUNSEL -#define UI_TEXT_PRINT_POS "Imprimindo..." -#define UI_TEXT_PRINTING "Imprimindo" -#define UI_TEXT_IDLE "Ocioso" -#define UI_TEXT_NOSDCARD "Nenhum cartao SD" -#define UI_TEXT_ERROR "**** ERRO ****" -#define UI_TEXT_BACK "Voltar " cUP -#define UI_TEXT_QUICK_SETTINGS "Configuracoes Rapidas" -#define UI_TEXT_CONFIGURATION "Configuracao" -#define UI_TEXT_POSITION "Posicao" -#define UI_TEXT_EXTRUDER "Extrusor" -#define UI_TEXT_SD_CARD "Cartao SD" -#define UI_TEXT_DEBUGGING "Depuracao" -#define UI_TEXT_HOME_ALL "Home Todos" -#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 "Pre-aquecer PLA" -#define UI_TEXT_PREHEAT_ABS "Pre-aquecer ABS" -#define UI_TEXT_COOLDOWN "Resfriar" -#define UI_TEXT_SET_TO_ORIGIN "Definir como Origem" -#define UI_TEXT_DISABLE_STEPPER "Desabilitar motor" -#define UI_TEXT_X_POSITION "Posicao X" -#define UI_TEXT_X_POS_FAST "Pos. Rapida X" -#define UI_TEXT_Y_POSITION "Posicao Y" -#define UI_TEXT_Y_POS_FAST "Pos. Rapida Y" -#define UI_TEXT_Z_POSITION "Posicao Z" -#define UI_TEXT_Z_POS_FAST "Pos. Rapida Z" -#define UI_TEXT_E_POSITION "Posicao Extrusor" -#define UI_TEXT_BED_TEMP "Temp. Cama: %Eb" cDEG "C" -#define UI_TEXT_EXTR0_TEMP "Temp. 1: %E0" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 2: %E1" cDEG "C" -#define UI_TEXT_EXTR2_TEMP "Temp. 3: %E2" cDEG "C" -#define UI_TEXT_EXTR0_OFF "Extrusor 1 Desligado" -#define UI_TEXT_EXTR1_OFF "Extrusor 2 Desligado" -#define UI_TEXT_EXTR2_OFF "Extrusor 3 Desligado" -#define UI_TEXT_EXTR0_SELECT "%X0 Selecionar Extr. 1" -#define UI_TEXT_EXTR1_SELECT "%X1 Selecionar Extr. 2" -#define UI_TEXT_EXTR2_SELECT "%X2 Selecionar Extr. 3" -#define UI_TEXT_EXTR_ORIGIN "Definir Origem" -#define UI_TEXT_PRINT_X "Imprimir X:%ax" -#define UI_TEXT_PRINT_Y "Imprimir Y:%ay" -#define UI_TEXT_PRINT_Z "Imprimir Z:%az" -#define UI_TEXT_PRINT_Z_DELTA "Imprimir:%az" -#define UI_TEXT_MOVE_X "Mover X:%aX" -#define UI_TEXT_MOVE_Y "Mover Y:%aY" -#define UI_TEXT_MOVE_Z "Mover Z:%aZ" -#define UI_TEXT_MOVE_Z_DELTA "Mover:%aZ" -#define UI_TEXT_JERK "Jerk:%aj" -#define UI_TEXT_ZJERK "Z-Jerk:%aJ" -#define UI_TEXT_ACCELERATION "Aceleracao" -#define UI_TEXT_STORE_TO_EEPROM "Armazenar na EEPROM" -#define UI_TEXT_LOAD_EEPROM "Carregar da EEPROM" -#define UI_TEXT_DBG_ECHO "Echo :%do" -#define UI_TEXT_DBG_INFO "Info :%di" -#define UI_TEXT_DBG_ERROR "Erros :%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 "Imprimir arquivo" -#define UI_TEXT_PAUSE_PRINT "Pausar Impressao" -#define UI_TEXT_CONTINUE_PRINT "Continuar Impressao" -#define UI_TEXT_UNMOUNT_CARD "Desmontar Cartao" -#define UI_TEXT_MOUNT_CARD "Montar Cartao" -#define UI_TEXT_DELETE_FILE "Deletar arquivo" -#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_MAX_Z_DELTA "Max:%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_FEED_HOME_Z_DELTA "Home:%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 "Velocidade ventoinha" -#define UI_TEXT_FAN_OFF "Desligar ventoinha" -#define UI_TEXT_FAN_25 "Def. ventoinha 25%%%" -#define UI_TEXT_FAN_50 "Def. ventoinha 50%%%" -#define UI_TEXT_FAN_75 "Def. ventoinha 75%%%" -#define UI_TEXT_FAN_FULL "Def. ventoinha 100%%%" -#define UI_TEXT_STEPPER_INACTIVE "Motor Inativo" -#define UI_TEXT_STEPPER_INACTIVE2 "Des. Depois: %is","[min] 0=Off" -#define UI_TEXT_POWER_INACTIVE "Max. Inativo" -#define UI_TEXT_POWER_INACTIVE2 "Des. Depois: %ip","[min] 0=Off" -#define UI_TEXT_GENERAL "Geral" -#define UI_TEXT_BAUDRATE "Baudrate:%oc" -#define UI_TEXT_EXTR_STEPS "Passos/mm:%Se" -#define UI_TEXT_EXTR_START_FEED "Iniciar 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 "Controle:%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 "Offset X:%Xx" -#define UI_TEXT_EXTR_YOFF "Offset Y:%Xy" -#define UI_TEXT_STRING_HM_BANGBANG "BangBang" -#define UI_TEXT_STRING_HM_PID "PID" -#define UI_TEXT_STRING_ACTION "Acao:%la" -#define UI_TEXT_HEATING_EXTRUDER "Aquecendo Extrusor" -#define UI_TEXT_HEATING_BED "Aquecendo Cama" -#define UI_TEXT_KILLED "Killed" -#define UI_TEXT_STEPPER_DISABLED "Motor Desabilitado" -#define UI_TEXT_EEPROM_STORED "Configuracao","armazenada na EEPROM" -#define UI_TEXT_EEPROM_LOADED "Configuracao","carregada da EEPROM" -#define UI_TEXT_UPLOADING "Enviando..." -#define UI_TEXT_PAGE_BUFFER "Buffer:%oB" -#define UI_TEXT_PAGE_EXTRUDER " E:%ec/%Ec" cDEG "C" cARROW "%oC" -#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0" cDEG "C" cARROW "%o0" -#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1" cDEG "C" cARROW "%o1" -#define UI_TEXT_PAGE_EXTRUDER3 "E3:%e2/%E2" cDEG "C" cARROW "%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb" cDEG "C" cARROW "%ob" -#define UI_TEXT_SPEED_MULTIPLY "Mult. Veloc.:%om%%%" -#define UI_TEXT_FLOW_MULTIPLY "Mult. Fluxo:%of%%%" -#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "Aguardar Temp.%XT" cDEG "C" -#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Aguardar Unidades:%XUmm" -#define UI_TEXT_PRINTER_READY "Impressora pronta." - +#define UI_TEXT_OFFSETS_PL "Polozenie wydruku" +#define UI_TEXT_X_OFFSET_PL "Przesun w X : %T0mm" +#define UI_TEXT_Y_OFFSET_PL "Przesun w Y : %T1mm" +#define UI_TEXT_Z_OFFSET_PL "Przesun w Z :%T2mm" + +// Türk + +#define UI_TEXT_ON_TR "Acik" +#define UI_TEXT_OFF_TR "Kapali" +#define UI_TEXT_NA_TR "N/A" // Output for not available +#define UI_TEXT_YES_TR "Evet" +#define UI_TEXT_NO_TR "Hayir" +#define UI_TEXT_PRINT_POS_TR "Yaziyor..." +#define UI_TEXT_PRINTING_TR "Yaziyor" +#define UI_TEXT_IDLE_TR "Bosta" +#define UI_TEXT_NOSDCARD_TR "SD Kart Yok" +#define UI_TEXT_ERROR_TR "**** HATA ****" +#define UI_TEXT_BACK_TR "Geri " cUP +#define UI_TEXT_QUICK_SETTINGS_TR "Hizli Ayar" +#define UI_TEXT_ERRORMSG_TR "%oe" +#define UI_TEXT_CONFIGURATION_TR "Yapilandirma" +#define UI_TEXT_POSITION_TR "Konum-Hareket" +#define UI_TEXT_EXTRUDER_TR "Extruder" +#define UI_TEXT_SD_CARD_TR "SD Kart" +#define UI_TEXT_DEBUGGING_TR "Debugging" +#define UI_TEXT_HOME_DELTA_TR "Deltayi Sifr. Gond." +#define UI_TEXT_HOME_ALL_TR "Hepsini S.Gonder" +#define UI_TEXT_HOME_X_TR "X S.Gonder" +#define UI_TEXT_HOME_Y_TR "Y S.Gonder" +#define UI_TEXT_HOME_Z_TR "Z S.Gonder" +#define UI_TEXT_PREHEAT_PLA_TR "PLA On Isitma" +#define UI_TEXT_PREHEAT_ABS_TR "ABS On Isitma" +#define UI_TEXT_LIGHTS_ONOFF_TR "Isiklar :%lo" +#define UI_TEXT_COOLDOWN_TR "Soguma" +#define UI_TEXT_SET_TO_ORIGIN_TR "Orijine ayarla" +#define UI_TEXT_DISABLE_STEPPER_TR "Motoru Kapat" +#define UI_TEXT_X_POSITION_TR "X Hareketi" +#define UI_TEXT_X_POS_FAST_TR "X Hizli Hareketi" +#define UI_TEXT_Y_POSITION_TR "Y Hareketi" +#define UI_TEXT_Y_POS_FAST_TR "Y Hizli Hareketi" +#define UI_TEXT_Z_POSITION_TR "Z Hareketi" +#define UI_TEXT_Z_POS_FAST_TR "Z Hizli Hareketi" +#define UI_TEXT_E_POSITION_TR "Hareketi" +#define UI_TEXT_BED_TEMP_TR "Tabla Sic: %Eb" cDEG "C" +#define UI_TEXT_EXTR0_TEMP_TR "Sic. 1 : %E0" cDEG "C" +#define UI_TEXT_EXTR1_TEMP_TR "Sic. 2 : %E1" cDEG "C" +#define UI_TEXT_EXTR2_TEMP_TR "Sic. 3 : %E2" cDEG "C" +#define UI_TEXT_EXTR0_OFF_TR "Extr. 1'i Kapa" +#define UI_TEXT_EXTR1_OFF_TR "Extr. 2'i Kapa" +#define UI_TEXT_EXTR2_OFF_TR "Extr. 3'i Kapa" +#define UI_TEXT_EXTR0_SELECT_TR "%X0 Extr. 1'i Sec" +#define UI_TEXT_EXTR1_SELECT_TR "%X1 Extr. 2'yi Sec" +#define UI_TEXT_EXTR2_SELECT_TR "%X2 Extr. 3'u Sec" +#define UI_TEXT_EXTR_ORIGIN_TR "Origin i Ayarla" +#define UI_TEXT_PRINT_X_TR "Yazma H. X:%ax" +#define UI_TEXT_PRINT_Y_TR "Yazma H. Y:%ay" +#define UI_TEXT_PRINT_Z_TR "Yazma H. Z:%az" +#define UI_TEXT_PRINT_Z_DELTA_TR "Yazma H.:%az" +#define UI_TEXT_MOVE_X_TR "Hareket X :%aX" +#define UI_TEXT_MOVE_Y_TR "Hareket Y :%aY" +#define UI_TEXT_MOVE_Z_TR "Hareket Z :%aZ" +#define UI_TEXT_MOVE_Z_DELTA_TR "Hareket :%aZ" +#define UI_TEXT_JERK_TR "X-Y Jerk :%aj" +#define UI_TEXT_ZJERK_TR "Z-Jerk :%aJ" +#define UI_TEXT_ACCELERATION_TR "Ivme" +#define UI_TEXT_STORE_TO_EEPROM_TR "EEPROM'a kaydet" +#define UI_TEXT_LOAD_EEPROM_TR "EEPROM'dan cagir" +#define UI_TEXT_DBG_ECHO_TR "Echo :%do" +#define UI_TEXT_DBG_INFO_TR "Bilgi :%di" +#define UI_TEXT_DBG_ERROR_TR "Hatalar :%de" +#define UI_TEXT_DBG_DRYRUN_TR "Bosta Calis:%dd" +#define UI_TEXT_OPS_OFF_TR "%O0 OPS Kapali" +#define UI_TEXT_OPS_CLASSIC_TR "%O1 OPS Klasik" +#define UI_TEXT_OPS_FAST_TR "%O2 OPS Hizli" +#define UI_TEXT_OPS_RETRACT_TR "Geri Cekl.:%Or" +#define UI_TEXT_OPS_BACKSLASH_TR "Eksen Bosl.:%Ob" +#define UI_TEXT_OPS_MINDIST_TR "Min. Mesafe:%Od" +#define UI_TEXT_OPS_MOVE_AFTER_TR "Move after:%Oa" +#define UI_TEXT_ANTI_OOZE_TR "Anti Ooze" +#define UI_TEXT_PRINT_FILE_TR "Dosya Yazdir" +#define UI_TEXT_PAUSE_PRINT_TR "Baskiyi Duraklat" +#define UI_TEXT_CONTINUE_PRINT_TR "Baskiya Devam" +#define UI_TEXT_UNMOUNT_CARD_TR "Karti Cikar" +#define UI_TEXT_MOUNT_CARD_TR "Karti Bagla" +#define UI_TEXT_DELETE_FILE_TR "Dosyayi Sil" +#define UI_TEXT_FEEDRATE_TR "Ilerleme" +#define UI_TEXT_FEED_MAX_X_TR "Max X:%fx" +#define UI_TEXT_FEED_MAX_Y_TR "Max Y:%fy" +#define UI_TEXT_FEED_MAX_Z_TR "Max Z:%fz" +#define UI_TEXT_FEED_MAX_Z_DELTA_TR "Max:%fz" +#define UI_TEXT_FEED_HOME_X_TR "X'i Sif.Gon.Hiz.:%fX" +#define UI_TEXT_FEED_HOME_Y_TR "Y'yi Sif.Gon.Hiz.:%fY" +#define UI_TEXT_FEED_HOME_Z_TR "Z'i Sif.Gon.Hiz:%fZ" +#define UI_TEXT_FEED_HOME_Z_DELTA_TR "Delta Sif.Gon.Hiz:%fZ" +#define UI_TEXT_ACTION_XPOSITION4A_TR "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION4B_TR "Min endstop:%sx" +#define UI_TEXT_ACTION_XPOSITION4C_TR "Max endstop:%sX" +#define UI_TEXT_ACTION_XPOSITION4D_TR "" +#define UI_TEXT_ACTION_YPOSITION4A_TR "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION4B_TR "Min endstop:%sy" +#define UI_TEXT_ACTION_YPOSITION4C_TR "Max endstop:%sY" +#define UI_TEXT_ACTION_YPOSITION4D_TR "" +#define UI_TEXT_ACTION_ZPOSITION4A_TR "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION4B_TR "Min endstop:%sz" +#define UI_TEXT_ACTION_ZPOSITION4C_TR "Max endstop:%sZ" +#define UI_TEXT_ACTION_ZPOSITION4D_TR "" +#define UI_TEXT_ACTION_XPOSITION_FAST4A_TR "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST4B_TR "Min endstop:%sx" +#define UI_TEXT_ACTION_XPOSITION_FAST4C_TR "Max endstop:%sX" +#define UI_TEXT_ACTION_XPOSITION_FAST4D_TR "" +#define UI_TEXT_ACTION_YPOSITION_FAST4A_TR "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST4B_TR "Min endstop:%sy" +#define UI_TEXT_ACTION_YPOSITION_FAST4C_TR "Max endstop:%sY" +#define UI_TEXT_ACTION_YPOSITION_FAST4D_TR "" +#define UI_TEXT_ACTION_ZPOSITION_FAST4A_TR "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST4B_TR "Min endstop:%sz" +#define UI_TEXT_ACTION_ZPOSITION_FAST4C_TR "Max endstop:%sZ" +#define UI_TEXT_ACTION_ZPOSITION_FAST4D_TR "" +#define UI_TEXT_ACTION_EPOSITION_FAST2A_TR "E:%x3 mm" +#define UI_TEXT_ACTION_EPOSITION_FAST2B_TR "1 tik = 1 mm" +#define UI_TEXT_ACTION_XPOSITION2A_TR "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION2B_TR "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION2A_TR "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION2B_TR "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION2A_TR "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION2B_TR "Min:%sz Max:%sZ" +#define UI_TEXT_ACTION_XPOSITION_FAST2A_TR "X:%x0 mm" +#define UI_TEXT_ACTION_XPOSITION_FAST2B_TR "Min:%sx Max:%sX" +#define UI_TEXT_ACTION_YPOSITION_FAST2A_TR "Y:%x1 mm" +#define UI_TEXT_ACTION_YPOSITION_FAST2B_TR "Min:%sy Max:%sY" +#define UI_TEXT_ACTION_ZPOSITION_FAST2A_TR "Z:%x2 mm" +#define UI_TEXT_ACTION_ZPOSITION_FAST2B_TR "Min:%sz Max:%sZ" +#define UI_TEXT_FANSPEED_TR "Fan Hizi" +#define UI_TEXT_ACTION_FANSPEED_TR "Fan Hizi:%Fs%%%" +#define UI_TEXT_FAN_OFF_TR "Fan'i Kapat" +#define UI_TEXT_FAN_25_TR "Fan'i Ayarla 25%%%" +#define UI_TEXT_FAN_50_TR "Fan'i Ayarla 50%%%" +#define UI_TEXT_FAN_75_TR "Fan'i Ayarla 75%%%" +#define UI_TEXT_FAN_FULL_TR "Fan Tam Acik" +#define UI_TEXT_STEPPER_INACTIVE_TR "Motorlar Bosta" +#define UI_TEXT_STEPPER_INACTIVE2A_TR "Motor Kapa: %is" +#define UI_TEXT_STEPPER_INACTIVE2B_TR "[min] 0=Off" +#define UI_TEXT_POWER_INACTIVE_TR "Max. Bosta" +#define UI_TEXT_POWER_INACTIVE2A_TR "Kapama sur.: %ip" +#define UI_TEXT_POWER_INACTIVE2B_TR "[min] 0=Kapali" +#define UI_TEXT_GENERAL_TR "Genel" +#define UI_TEXT_BAUDRATE_TR "Baudrate:%oc" +#define UI_TEXT_EXTR_STEPS_TR "Adim/MM:%Se" +#define UI_TEXT_EXTR_START_FEED_TR "Baslangic FR:%Xf" +#define UI_TEXT_EXTR_MAX_FEED_TR "Max FR:%XF" +#define UI_TEXT_EXTR_ACCEL_TR "Ivme:%XA" +#define UI_TEXT_EXTR_WATCH_TR "Stab.Time:%Xw" +#define UI_TEXT_EXTR_ADVANCE_L_TR "Gelismis lin:%Xl" +#define UI_TEXT_EXTR_ADVANCE_K_TR "Gelismis quad:%Xa" +#define UI_TEXT_EXTR_MANAGER_TR "Kontrol:%Xh" +#define UI_TEXT_EXTR_PGAIN_TR "PID P:%Xp" +#define UI_TEXT_EXTR_DEADTIME_TR "Bos Zamn:%Xp" +#define UI_TEXT_EXTR_DMAX_DT_TR "Kontrol PWM:%XM" +#define UI_TEXT_EXTR_IGAIN_TR "PID I:%Xi" +#define UI_TEXT_EXTR_DGAIN_TR "PID D:%Xd" +#define UI_TEXT_EXTR_DMIN_TR "Surucu Min:%Xm" +#define UI_TEXT_EXTR_DMAX_TR "Surucu Max:%XM" +#define UI_TEXT_EXTR_PMAX_TR "PID Max:%XD" +#define UI_TEXT_EXTR_XOFF_TR "X-Ofset:%Xx" +#define UI_TEXT_EXTR_YOFF_TR "Y-Ofset:%Xy" +#define UI_TEXT_STRING_HM_BANGBANG_TR "BangBang" +#define UI_TEXT_STRING_HM_PID_TR "PID" +#define UI_TEXT_STRING_ACTION_TR "Eylem:%la" +#define UI_TEXT_HEATING_EXTRUDER_TR "Extruder Isiniyor" +#define UI_TEXT_HEATING_BED_TR "Bed Isiniyor" +#define UI_TEXT_KILLED_TR "DURDU" +#define UI_TEXT_STEPPER_DISABLED_TR "Motorlar Kapali" +#define UI_TEXT_EEPROM_STOREDA_TR "Konfigurasyon" +#define UI_TEXT_EEPROM_STOREDB_TR "EEPROM'a kaydedildi" +#define UI_TEXT_EEPROM_LOADEDA_TR "Konfigurasyon" +#define UI_TEXT_EEPROM_LOADEDB_TR "EEPROM'dan cagrildi" +#define UI_TEXT_UPLOADING_TR "Yukluyor..." +#define UI_TEXT_PAGE_BUFFER_TR "Onbellek:%oB" +#define UI_TEXT_PAGE_EXTRUDER_TR " E:%ec/%Ec" cDEG "C" cARROW "%oC" +#define UI_TEXT_PAGE_EXTRUDER1_TR "E1:%e0/%E0" cDEG "C" cARROW "%o0" +#define UI_TEXT_PAGE_EXTRUDER2_TR "E2:%e1/%E1" cDEG "C" cARROW "%o1" +#define UI_TEXT_PAGE_EXTRUDER3_TR "E3:%e2/%E2" cDEG "C" cARROW "%o2" +#define UI_TEXT_PAGE_BED_TR " B:%eb/%Eb" cDEG "C" cARROW "%ob" +#define UI_TEXT_SPEED_MULTIPLY_TR "Hiz Carp.:%om%%%" +#define UI_TEXT_FLOW_MULTIPLY_TR "Akis Carp. :%of%%%" +#define UI_TEXT_SHOW_MEASUREMENT_TR "Olcumu Goster" +#define UI_TEXT_RESET_MEASUREMENT_TR "Olcumu Sifirla" +#define UI_TEXT_SET_MEASURED_ORIGIN_TR "Z=0'a ayarla" +#define UI_TEXT_ZCALIB_TR "Z Kalib." +#define UI_TEXT_SET_P1_TR "Set P1" +#define UI_TEXT_SET_P2_TR "Set P2" +#define UI_TEXT_SET_P3_TR "Set P3" +#define UI_TEXT_CALCULATE_LEVELING_TR "Sevieyi Hesapla" +#define UI_TEXT_LEVEL_TR "Deltayi seviyele" +#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP_TR "Bekle Sic. %XT" cDEG "C" +#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS_TR "Bekle: %XU mm" +#define UI_TEXT_SD_REMOVED_TR "SD Card Cikarildi" +#define UI_TEXT_SD_INSERTED_TR "SD Card Takildi" +#define UI_TEXT_PRINTER_READY_TR "Yazici Hazir" +// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES +// ___88 days 12:45 +#define UI_TEXT_PRINTTIME_DAYS_TR " gun " +#define UI_TEXT_PRINTTIME_HOURS_TR ":" +#define UI_TEXT_PRINTTIME_MINUTES_TR "" +#define UI_TEXT_PRINT_TIME_TR "Yazdirma Zamani" +#define UI_TEXT_PRINT_FILAMENT_TR "Filament harcandi" +#define UI_TEXT_PRINTED_TR "yazildi" +#define UI_TEXT_POWER_TR "ATX gucu on/off" +#define UI_TEXT_STRING_HM_DEADTIME_TR "Bosta Zaman" +#define UI_TEXT_STRING_HM_SLOWBANG_TR "SlowBang" +#define UI_TEXT_STOP_PRINT_TR "Yazdirmayi durdur" +#define UI_TEXT_Z_BABYSTEPPING_TR "Z Babystep.:%oYmm" +#define UI_TEXT_CHANGE_FILAMENT_TR "Filament degistir" +#define UI_TEXT_WIZ_CH_FILAMENT1_TR "Filament degistir" +#define UI_TEXT_WIZ_CH_FILAMENT2_TR "Filameti yukari asagi" +#define UI_TEXT_WIZ_CH_FILAMENT3_TR "almak icin cevirin" +#define UI_TEXT_CLICK_DONE_TR "Tamamlandiginda butona basin" +#define UI_TEXT_AUTOLEVEL_ONOFF_TR "Oto seviye: %ll" +#define UI_TEXT_SERVOPOS_TR "Servo pos.: %oS" +#define UI_TEXT_IGNORE_M106_TR "M106Yi atla %Fi" +#define UI_TEXT_WIZ_REHEAT1_TR "Extruderlari tekrar" +#define UI_TEXT_WIZ_REHEAT2_TR "isitmak icin tiklayin" +#define UI_TEXT_WIZ_WAITTEMP1_TR "Istnilen sicakliklar" +#define UI_TEXT_WIZ_WAITTEMP2_TR "icin bekleyin" +#define UI_TEXT_EXTRUDER_JAM_TR "Extruder takildi" +#define UI_TEXT_STANDBY_TR "Bekleme Modu" +#define UI_TEXT_BED_COATING_TR "Tabla ustu kaplama" +#define UI_TEXT_BED_COATING_SET1_TR "Kaplama Kalinligi" +#define UI_TEXT_BED_COATING_SET2_TR "" +#define UI_TEXT_NOCOATING_TR "Kaplama Yok" +#define UI_TEXT_BUILDTAK_TR "BuildTak" +#define UI_TEXT_KAPTON_TR "Kapton" +#define UI_TEXT_BLUETAPE_TR "Mavi Boya Kagidi" +#define UI_TEXT_PETTAPE_TR "Yesil PET Tape" +#define UI_TEXT_GLUESTICK_TR "Yapiskan" +#define UI_TEXT_CUSTOM_TR "Diger" +#define UI_TEXT_COATING_CUSTOM_TR "Diger : %oCmm" +#define UI_TEXT_LANGUAGE_TR "Dil" +#if NUM_EXTRUDER > 2 || MIXING_EXTRUDER != 0 +#define UI_TEXT_MAINPAGE6_1_TR "\xa %ec/%Ec\xb0 X:%x0" +#else +#define UI_TEXT_MAINPAGE6_1_TR "\xa %e0/%E0\xb0 X:%x0" +#endif // NUM_EXTRUDER +#if NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 +#define UI_TEXT_MAINPAGE6_2_TR "\xa %e1/%E1\xb0 Y:%x1" +#elif HAVE_HEATED_BED +#define UI_TEXT_MAINPAGE6_2_TR "\xe %eb/%Eb\xb0 Y:%x1" +#else +#define UI_TEXT_MAINPAGE6_2_TR " Y:%x1" #endif - -// *************** Italian translation **************** -#if UI_LANGUAGE==4 - -#define UI_TEXT_ON "On" -#define UI_TEXT_OFF "Off" -#define UI_TEXT_NA "N/A" // Output for not available -#define UI_TEXT_YES "Si" -#define UI_TEXT_NO "No" -#define UI_TEXT_SEL cSEL -#define UI_TEXT_NOSEL cUNSEL -#define UI_TEXT_PRINT_POS "Stampa..." -#define UI_TEXT_PRINTING "Stampa" -#define UI_TEXT_IDLE "Pausa" -#define UI_TEXT_NOSDCARD "No Scheda SD" -#define UI_TEXT_ERROR "**** ERRORE ****" -#define UI_TEXT_BACK "Indietro " cUP -#define UI_TEXT_QUICK_SETTINGS "Impostazioni veloci" -#define UI_TEXT_CONFIGURATION "Configurazione" -#define UI_TEXT_POSITION "Posizione" -#define UI_TEXT_EXTRUDER "Estrusore" -#define UI_TEXT_SD_CARD "Scheda SD" -#define UI_TEXT_DEBUGGING "Sviluppo" -#define UI_TEXT_HOME_ALL "Origine Tutti" -#define UI_TEXT_HOME_X "Origine X" -#define UI_TEXT_HOME_Y "Origine Y" -#define UI_TEXT_HOME_Z "Origine Z" -#define UI_TEXT_PREHEAT_PLA "Presicaldamento PLA" -#define UI_TEXT_PREHEAT_ABS "Presicaldamento ABS" -#define UI_TEXT_COOLDOWN "Raffreddamento" -#define UI_TEXT_SET_TO_ORIGIN "Imposta come Origine" -#define UI_TEXT_DISABLE_STEPPER "Disabilita stepper" -#define UI_TEXT_X_POSITION "Posizione X" -#define UI_TEXT_X_POS_FAST "Pos. X Veloce" -#define UI_TEXT_Y_POSITION "Posizione Y" -#define UI_TEXT_Y_POS_FAST "Pos. Y Veloce" -#define UI_TEXT_Z_POSITION "Posizione Z" -#define UI_TEXT_Z_POS_FAST "Pos. Z Veloce" -#define UI_TEXT_E_POSITION "Posizione Estrusore" -#define UI_TEXT_BED_TEMP "Temp. Piatto:%Eb" cDEG "C" -#define UI_TEXT_EXTR0_TEMP "Temp. 1: %E0" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 2: %E1" cDEG "C" -#define UI_TEXT_EXTR2_TEMP "Temp. 3: %E2" cDEG "C" -#define UI_TEXT_EXTR0_OFF "Estrusore 1 Spento" -#define UI_TEXT_EXTR1_OFF "Estrusore 2 Spento" -#define UI_TEXT_EXTR2_OFF "Estrusore 3 Spento" -#define UI_TEXT_EXTR0_SELECT "%X0 Seleziona Estr. 1" -#define UI_TEXT_EXTR1_SELECT "%X1 Seleziona Estr. 2" -#define UI_TEXT_EXTR2_SELECT "%X2 Seleziona Estr. 3" -#define UI_TEXT_EXTR_ORIGIN "Imposta Origine" -#define UI_TEXT_PRINT_X "Stampa X:%ax" -#define UI_TEXT_PRINT_Y "Stampa Y:%ay" -#define UI_TEXT_PRINT_Z "Stampa Z:%az" -#define UI_TEXT_PRINT_Z_DELTA "Stampa:%az" -#define UI_TEXT_MOVE_X "Movimento X:%aX" -#define UI_TEXT_MOVE_Y "Movimento Y:%aY" -#define UI_TEXT_MOVE_Z "Movimento Z:%aZ" -#define UI_TEXT_MOVE_Z_DELTA "Movimento:%aZ" -#define UI_TEXT_JERK "Scatto:%aj" -#define UI_TEXT_ZJERK "Scatto-Z:%aJ" -#define UI_TEXT_ACCELERATION "Accelerazione" -#define UI_TEXT_STORE_TO_EEPROM "Salva in EEPROM" -#define UI_TEXT_LOAD_EEPROM "Carica da EEPROM" -#define UI_TEXT_DBG_ECHO "Eco :%do" -#define UI_TEXT_DBG_INFO "Info :%di" -#define UI_TEXT_DBG_ERROR "Errori :%de" -#define UI_TEXT_DBG_DRYRUN "Simulazione:%dd" -#define UI_TEXT_OPS_OFF "%O0 OPS Spento" -#define UI_TEXT_OPS_CLASSIC "%O1 OPS Classico" -#define UI_TEXT_OPS_FAST "%O2 OPS Veloce" -#define UI_TEXT_OPS_RETRACT "Ritiro :%Or" -#define UI_TEXT_OPS_BACKSLASH "Gioco barra:%Ob" -#define UI_TEXT_OPS_MINDIST "Distanza Min.:%Od" -#define UI_TEXT_OPS_MOVE_AFTER "Movimento dopo:%Oa" -#define UI_TEXT_ANTI_OOZE "Anti goccia" -#define UI_TEXT_PRINT_FILE "Stampa file" -#define UI_TEXT_PAUSE_PRINT "Pausa Stampa" -#define UI_TEXT_CONTINUE_PRINT "Continua Stampa" -#define UI_TEXT_UNMOUNT_CARD "Scarica Scheda" -#define UI_TEXT_MOUNT_CARD "Carica Scheda" -#define UI_TEXT_DELETE_FILE "Cancella file" -#define UI_TEXT_FEEDRATE "Velocita'" -#define UI_TEXT_FEED_MAX_X "Massimo X:%fx" -#define UI_TEXT_FEED_MAX_Y "Massimo Y:%fy" -#define UI_TEXT_FEED_MAX_Z "Massimo Z:%fz" -#define UI_TEXT_FEED_MAX_Z_DELTA "Massimo:%fz" -#define UI_TEXT_FEED_HOME_X "Origine X:%fX" -#define UI_TEXT_FEED_HOME_Y "Origine Y:%fY" -#define UI_TEXT_FEED_HOME_Z "Origine Z:%fZ" -#define UI_TEXT_FEED_HOME_Z_DELTA "Origine:%fZ" -#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Min finec.:%sx","Max finec.:%sX","" -#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Min finec.:%sy","Max finec.:%sY","" -#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Min finec.:%sz","Max finec.:%sZ","" -#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Min finec.:%sx","Max finec.:%sX","" -#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Min finec.:%sy","Max finec.:%sY","" -#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Min finec.:%sz","Max finec.:%sZ","" -#define UI_TEXT_ACTION_EPOSITION_FAST2 "E:%x3 mm","1 scatto = 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 "Velocita' Ventola" -#define UI_TEXT_FAN_OFF "Spegnimento Ventola" -#define UI_TEXT_FAN_25 "Ventola al 25%%%" -#define UI_TEXT_FAN_50 "Ventola al%%%" -#define UI_TEXT_FAN_75 "Ventola al%%%" -#define UI_TEXT_FAN_FULL "Ventola al massimo" -#define UI_TEXT_STEPPER_INACTIVE "Stepper Inattivi" -#define UI_TEXT_STEPPER_INACTIVE2 "Dis. dopo: %is","[min] 0=Off" -#define UI_TEXT_POWER_INACTIVE "Max. Inattivita'" -#define UI_TEXT_POWER_INACTIVE2 "Dis. After: %ip","[min] 0=Off" -#define UI_TEXT_GENERAL "Generale" -#define UI_TEXT_BAUDRATE "Baudrate:%oc" -#define UI_TEXT_EXTR_STEPS "Passi/mm:%Se" -#define UI_TEXT_EXTR_START_FEED "Velocita' Avvio:%Xf" -#define UI_TEXT_EXTR_MAX_FEED "Velocita' Max:%XF" -#define UI_TEXT_EXTR_ACCEL "Accel:%XA" -#define UI_TEXT_EXTR_WATCH "Tempo Stab.:%Xw" -#define UI_TEXT_EXTR_ADVANCE_L "Avanzamento lin:%Xl" -#define UI_TEXT_EXTR_ADVANCE_K "Avanzamento espon:%Xa" -#define UI_TEXT_EXTR_MANAGER "Controllo:%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 "Azione:%la" -#define UI_TEXT_HEATING_EXTRUDER "Riscald. Estrusore" -#define UI_TEXT_HEATING_BED "Riscald. Piatto" -#define UI_TEXT_KILLED "Abortito" -#define UI_TEXT_STEPPER_DISABLED "Stepper Disabilitato" -#define UI_TEXT_EEPROM_STORED "Configurazione","Salvata in EEPROM" -#define UI_TEXT_EEPROM_LOADED "Configurazione","Caricata da EEPROM" -#define UI_TEXT_UPLOADING "Caricamento..." -#define UI_TEXT_PAGE_BUFFER "Tampone:%oB" -#define UI_TEXT_PAGE_EXTRUDER " E:%ec/%Ec" cDEG "C" cARROW "%oC" -#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0" cDEG "C" cARROW "%o0" -#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1" cDEG "C" cARROW "%o1" -#define UI_TEXT_PAGE_EXTRUDER3 "E3:%e2/%E2" cDEG "C" cARROW "%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb" cDEG "C" cARROW "%ob" -#define UI_TEXT_SPEED_MULTIPLY "Molt. Velocita':%om%%%" -#define UI_TEXT_FLOW_MULTIPLY "Molt. Flusso:%of%%%" -#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "Attesa Temp.%XT" cDEG "C" -#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Attesa Unita':%XUmm" -#define UI_TEXT_PRINTER_READY "Stampante pronta." - +#if HAVE_HEATED_BED && NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0 +#define UI_TEXT_MAINPAGE6_3_TR "\xe %eb/%Eb\xb0 Z:%x2" +#elif FEATURE_DITTO_PRINTING +#define UI_TEXT_MAINPAGE6_3_TR "Kopie: %ed Z:%x2" +#else +#define UI_TEXT_MAINPAGE6_3_TR "Przep:\xfd %of%%% Z:%x2" #endif - -#if UI_LANGUAGE==5 // Spanish translation - -#define UI_TEXT_ON "On" -#define UI_TEXT_OFF "Off" -#define UI_TEXT_NA "N/A" // Output for not available -#define UI_TEXT_YES "Si" -#define UI_TEXT_NO "No" -#define UI_TEXT_SEL cSEL -#define UI_TEXT_NOSEL cUNSEL -#define UI_TEXT_PRINT_POS "Imprimiendo..." -#define UI_TEXT_PRINTING "Imprimiendo" -#define UI_TEXT_IDLE "Idle" -#define UI_TEXT_NOSDCARD "Sin tarjeta SD" -#define UI_TEXT_ERROR "**** ERROR ****" -#define UI_TEXT_BACK "Atras " cUP -#define UI_TEXT_QUICK_SETTINGS "Configuracion Rapida" -#define UI_TEXT_CONFIGURATION "Configuracion" -#define UI_TEXT_POSITION "Posicion" -#define UI_TEXT_EXTRUDER "Extrusor" -#define UI_TEXT_SD_CARD "Tarjeta SD" -#define UI_TEXT_DEBUGGING "Debugging" -#define UI_TEXT_HOME_ALL "Todo Home" -#define UI_TEXT_HOME_X "X Home" -#define UI_TEXT_HOME_Y "Y Home" -#define UI_TEXT_HOME_Z "Z Home" -#define UI_TEXT_PREHEAT_PLA "Precalentar PLA" -#define UI_TEXT_PREHEAT_ABS "Precalentar ABS" -#define UI_TEXT_COOLDOWN "Enfriar" -#define UI_TEXT_SET_TO_ORIGIN "Fija a origen" -#define UI_TEXT_DISABLE_STEPPER "Desactiva motor" -#define UI_TEXT_X_POSITION "Posicion X" -#define UI_TEXT_X_POS_FAST "Pos. Rapida X" -#define UI_TEXT_Y_POSITION "Posicion Y" -#define UI_TEXT_Y_POS_FAST "Pos. Rapida Y" -#define UI_TEXT_Z_POSITION "Posicion Z" -#define UI_TEXT_Z_POS_FAST "Pos. Rapida Z" -#define UI_TEXT_E_POSITION "Extr. Posicion" -#define UI_TEXT_BED_TEMP "Temp. Cama: %Eb" cDEG "C" -#define UI_TEXT_EXTR0_TEMP "Temp. 1 : %E0" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 2 : %E1" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 3 : %E2" cDEG "C" -#define UI_TEXT_EXTR0_OFF "Extrusor 1 Off" -#define UI_TEXT_EXTR1_OFF "Extrusor 2 Off" -#define UI_TEXT_EXTR2_OFF "Extrusor 3 Off" -#define UI_TEXT_EXTR0_SELECT "%X0 Select Extr. 1" -#define UI_TEXT_EXTR1_SELECT "%X1 Select Extr. 2" -#define UI_TEXT_EXTR2_SELECT "%X2 Select Extr. 3" -#define UI_TEXT_EXTR_ORIGIN "Fija Originen" -#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_PRINT_Z_DELTA "Print:%az" -#define UI_TEXT_MOVE_X "Mueve X:%aX" -#define UI_TEXT_MOVE_Y "Mueve Y:%aY" -#define UI_TEXT_MOVE_Z "Mueve Z:%aZ" -#define UI_TEXT_MOVE_Z_DELTA "Mueve:%aZ" -#define UI_TEXT_JERK "Jerk:%aj" -#define UI_TEXT_ZJERK "Z-Jerk:%aJ" -#define UI_TEXT_ACCELERATION "Aceleracion" -#define UI_TEXT_STORE_TO_EEPROM "Almacena en EEPROM" -#define UI_TEXT_LOAD_EEPROM "Carga de 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 "Ejecucion vacio:%dd" -#define UI_TEXT_OPS_OFF "%O0 OPS Off" -#define UI_TEXT_OPS_CLASSIC "%O1 OPS Classica" -#define UI_TEXT_OPS_FAST "%O2 OPS Rapida" -#define UI_TEXT_OPS_RETRACT "Retraccion :%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 "Imprimiendo fichero" -#define UI_TEXT_PAUSE_PRINT "Pausando impresion" -#define UI_TEXT_CONTINUE_PRINT "Continuando impresion" -#define UI_TEXT_UNMOUNT_CARD "Desmontando Tarjeta" -#define UI_TEXT_MOUNT_CARD "Montando Card" -#define UI_TEXT_DELETE_FILE "Borrando fichero" -#define UI_TEXT_FEEDRATE "Feedrate" -#define UI_TEXT_FEED_MAX_X "X Max:%fx" -#define UI_TEXT_FEED_MAX_Y "Y Max:%fy" -#define UI_TEXT_FEED_MAX_Z "Z Max:%fz" -#define UI_TEXT_FEED_MAX_Z_DELTA "Max:%fz" -#define UI_TEXT_FEED_HOME_X "X Home:%fX" -#define UI_TEXT_FEED_HOME_Y "Y Home:%fY" -#define UI_TEXT_FEED_HOME_Z "Z Home:%fZ" -#define UI_TEXT_FEED_HOME_Z_DELTA "Home:%fZ" -#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Fin Carrera Min:%sx","Max:%sX","" -#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Fin Carrera Min:%sy","Max:%sY","" -#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Fin Carrera Min:%sz","Max:%sZ","" -#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Fin Carrera Min:%sx","Max:%sX","" -#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Fin Carrera Min:%sy","Max:%sY","" -#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Fin Carrera Min:%sz","Max:%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 "Velocida ventilador" -#define UI_TEXT_FAN_OFF "Apaga ventilador" -#define UI_TEXT_FAN_25 "Ventilador al 25%%%" -#define UI_TEXT_FAN_50 "Ventilador al 50%%%" -#define UI_TEXT_FAN_75 "Ventilador al 75%%%" -#define UI_TEXT_FAN_FULL "Ventilador al 100%%%" -#define UI_TEXT_STEPPER_INACTIVE "Motor Inactivo" -#define UI_TEXT_STEPPER_INACTIVE2 "Dis. Despues: %is","[min] 0=Off" -#define UI_TEXT_POWER_INACTIVE "Max. Inactivo" -#define UI_TEXT_POWER_INACTIVE2 "Dis. Despues: %ip","[min] 0=Off" -#define UI_TEXT_GENERAL "General" -#define UI_TEXT_BAUDRATE "Baudrate:%oc" -#define UI_TEXT_EXTR_STEPS "Pasos/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 "Acel:%XA" -#define UI_TEXT_EXTR_WATCH "Tiempo Estab.:%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 "Accion:%la" -#define UI_TEXT_HEATING_EXTRUDER "Calentando Extrusor" -#define UI_TEXT_HEATING_BED "Calentando Cama" -#define UI_TEXT_KILLED "Aborta" -#define UI_TEXT_STEPPER_DISABLED "Deshabilita motor" -#define UI_TEXT_EEPROM_STORED "Config.","almacenada en EEPROM" -#define UI_TEXT_EEPROM_LOADED "Config.","cargada de EEPROM" -#define UI_TEXT_UPLOADING "Actualizando..." -#define UI_TEXT_PAGE_BUFFER "Buffer:%oB" -#define UI_TEXT_PAGE_EXTRUDER " E:%ec/%Ec" cDEG "C" cARROW "%oC" -#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0" cDEG "C" cARROW "%o0" -#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1" cDEG "C" cARROW "%o1" -#define UI_TEXT_PAGE_EXTRUDER3 "E3:%e2/%E2" cDEG "C" cARROW "%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb" cDEG "C" cARROW "%ob" -#define UI_TEXT_SPEED_MULTIPLY "Mult. Velocidad.:%om%%%" -#define UI_TEXT_FLOW_MULTIPLY "Mult. Flujo.:%of%%%" -#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "Esperando Temp.%XT" cDEG "C" -#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Esperando Unidad:%XUmm" -#define UI_TEXT_PRINTER_READY "Impresora Lista." - -#endif - -// *************** Swedish translation **************** -// By Daniel Tedenljung 2013-08-21 -#if UI_LANGUAGE==6 -#define UI_TEXT_ON "P" STR_uuml "" -#define UI_TEXT_OFF "Av" -#define UI_TEXT_NA "N/A" // Output for not available -#define UI_TEXT_YES "Ja" -#define UI_TEXT_NO "Nej" -#define UI_TEXT_SEL cSEL -#define UI_TEXT_NOSEL cUNSEL -#define UI_TEXT_PRINT_POS "Skriver ut..." -#define UI_TEXT_PRINTING "Skriver" -#define UI_TEXT_IDLE "Sysslol" STR_ouml "s" -#define UI_TEXT_NOSDCARD "Inget SD-kort" -#define UI_TEXT_ERROR "**** FEL ****" -#define UI_TEXT_BACK "Tillbaka " cUP -#define UI_TEXT_QUICK_SETTINGS "Inst" STR_auml "llnigar" -#define UI_TEXT_CONFIGURATION "Konfiguration" -#define UI_TEXT_POSITION "Position" -#define UI_TEXT_EXTRUDER "Extruder" -#define UI_TEXT_SD_CARD "SD-kort" -#define UI_TEXT_DEBUGGING "Debugging" -#define UI_TEXT_HOME_ALL "K" STR_ouml "r hem alla" -#define UI_TEXT_HOME_X "K" STR_ouml "r hem X" -#define UI_TEXT_HOME_Y "K" STR_ouml "r hem Y" -#define UI_TEXT_HOME_Z "K" STR_ouml "r hem Z" -#define UI_TEXT_PREHEAT_PLA "F" STR_ouml "rv" STR_auml "rm f" STR_ouml "r PLA" -#define UI_TEXT_PREHEAT_ABS "F" STR_ouml "rv" STR_auml "rm f" STR_ouml "r ABS" -#define UI_TEXT_COOLDOWN "Kyl ner" -#define UI_TEXT_SET_TO_ORIGIN "S" STR_auml "tt som origo" -#define UI_TEXT_DISABLE_STEPPER "St" STR_auml "ng av stegmotor" -#define UI_TEXT_X_POSITION "X-position" -#define UI_TEXT_X_POS_FAST "X-pos. snabb" -#define UI_TEXT_Y_POSITION "Y-position" -#define UI_TEXT_Y_POS_FAST "Y-pos. snabb" -#define UI_TEXT_Z_POSITION "Z-osition" -#define UI_TEXT_Z_POS_FAST "Z-pos. snabb" -#define UI_TEXT_E_POSITION "Extr.-position" -#define UI_TEXT_BED_TEMP "B" STR_auml "dd-temp: %Eb" cDEG "C" -#define UI_TEXT_EXTR0_TEMP "Temp. 1: %E0" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 2: %E1" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 3: %E2" cDEG "C" -#define UI_TEXT_EXTR0_OFF "Extruder 1 av" -#define UI_TEXT_EXTR1_OFF "Extruder 2 av" -#define UI_TEXT_EXTR3_OFF "Extruder 3 av" -#define UI_TEXT_EXTR0_SELECT "%X0 V"STR_auml"lj Extr. 1" -#define UI_TEXT_EXTR1_SELECT "%X1 V"STR_auml"lj Extr. 2" -#define UI_TEXT_EXTR3_SELECT "%X2 V"STR_auml"lj Extr. 3" -#define UI_TEXT_EXTR_ORIGIN "S" STR_auml "tt origo" -#define UI_TEXT_PRINT_X "Skriv X:%ax" -#define UI_TEXT_PRINT_Y "Skriv Y:%ay" -#define UI_TEXT_PRINT_Z "Skriv Z:%az" -#define UI_TEXT_MOVE_X "Transp. X:%aX" -#define UI_TEXT_MOVE_Y "Transp. Y:%aY" -#define UI_TEXT_MOVE_Z "Transp. Z:%aZ" -#define UI_TEXT_JERK "Ryck: %aj" -#define UI_TEXT_ZJERK "Z-ryck: %aJ" -#define UI_TEXT_ACCELERATION "Acceleration" -#define UI_TEXT_STORE_TO_EEPROM "Spara till EEPROM" -#define UI_TEXT_LOAD_EEPROM "Ladda f. EEPROM" -#define UI_TEXT_DBG_ECHO "Eko: %do" -#define UI_TEXT_DBG_INFO "Info: %di" -#define UI_TEXT_DBG_ERROR "Errors: %de" -#define UI_TEXT_DBG_DRYRUN "Torrk" STR_ouml "r:%dd" -#define UI_TEXT_OPS_OFF "%O1 OPS av" -#define UI_TEXT_OPS_CLASSIC "%O2 OPS klassisk" -#define UI_TEXT_OPS_FAST "%O3 OPS snabb" -#define UI_TEXT_OPS_RETRACT "Backa: %Or" -#define UI_TEXT_OPS_BACKSLASH "Backsl. :%Ob" -#define UI_TEXT_OPS_MINDIST "Min.dist: %Od" -#define UI_TEXT_OPS_MOVE_AFTER "Flytta efter:%Oa" -#define UI_TEXT_ANTI_OOZE "Antikladd" -#define UI_TEXT_PRINT_FILE "Skriv ut fil" -#define UI_TEXT_PAUSE_PRINT "Pausa utskrift" -#define UI_TEXT_CONTINUE_PRINT "Forts" STR_auml "tt utskrift" -#define UI_TEXT_UNMOUNT_CARD "Mata ut kort" -#define UI_TEXT_MOUNT_CARD "Anslut kort" -#define UI_TEXT_DELETE_FILE "Radera fil" -#define UI_TEXT_FEEDRATE "Matning" -#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 "Ref X:%fX" -#define UI_TEXT_FEED_HOME_Y "Ref Y:%fY" -#define UI_TEXT_FEED_HOME_Z "Ref Z:%fZ" -#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Min " STR_auml "ndl" STR_auml "ge:%sx","Max " STR_auml "ndl" STR_auml "ge:%sX","" -#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Min " STR_auml "ndl" STR_auml "ge:%sy","Max " STR_auml "ndl" STR_auml "ge:%sY","" -#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Min " STR_auml "ndl" STR_auml "ge:%sz","Max " STR_auml "ndl" STR_auml "ge:%sZ","" -#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Min " STR_auml "ndl" STR_auml "ge:%sx","Max " STR_auml "ndl" STR_auml "ge:%sX","" -#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Min " STR_auml "ndl" STR_auml "ge:%sy","Max " STR_auml "ndl" STR_auml "ge:%sY","" -#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Min " STR_auml "ndl" STR_auml "ge:%sz","Max " STR_auml "ndl" STR_auml "ge:%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 "Fl" STR_auml "kt hast." -#define UI_TEXT_FAN_OFF "St" STR_auml "ng av fl" STR_auml "kt" -#define UI_TEXT_FAN_25 "Fl" STR_auml "kt 25%%%" -#define UI_TEXT_FAN_50 "Fl" STR_auml "kt 50%%%" -#define UI_TEXT_FAN_75 "Fl" STR_auml "kt 75%%%" -#define UI_TEXT_FAN_FULL "Full fl" STR_auml "kt" -#define UI_TEXT_STEPPER_INACTIVE "Stegmotorer inakt." -#define UI_TEXT_STEPPER_INACTIVE2 "Inakt. efter: %is","[min] 0=Off" -#define UI_TEXT_POWER_INACTIVE "Max. inaktiv" -#define UI_TEXT_POWER_INACTIVE2 "Inakt. efter: %ip","[min] 0=Off" -#define UI_TEXT_GENERAL "Generella" -#define UI_TEXT_BAUDRATE "Baudrate:%oc" -#define UI_TEXT_EXTR_STEPS "Steg/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. tid:%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 "Aktion:%la" -#define UI_TEXT_HEATING_EXTRUDER "V" STR_auml "rmer Extruder" -#define UI_TEXT_HEATING_BED "V" STR_auml "rmer B" STR_auml "dd" -#define UI_TEXT_KILLED "D" STR_ouml "dad" -#define UI_TEXT_STEPPER_DISABLED "Stegmotorer av" -#define UI_TEXT_EEPROM_STORED "Konfiguration","sparad i EEPROM" -#define UI_TEXT_EEPROM_LOADED "Konfiguration","laddat fr. EEPROM" -#define UI_TEXT_UPLOADING "Uppladdning..." -#define UI_TEXT_PAGE_BUFFER "Buffer:%oB" -#define UI_TEXT_PAGE_EXTRUDER " E:%ec/%Ec" cDEG "C" cARROW "%oC" -#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0" cDEG "C" cARROW "%o0" -#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1" cDEG "C" cARROW "%o1" -#define UI_TEXT_PAGE_EXTRUDER3 "E3:%e2/%E2" cDEG "C" cARROW "%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb" cDEG "C" cARROW "%ob" -#define UI_TEXT_SPEED_MULTIPLY "Hast. Mul.:%om%%%" -#define UI_TEXT_FLOW_MULTIPLY "Fl" STR_ouml "de Mul.:%of%%%" -#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "Inv" STR_auml "nta temp.%XT" cDEG "C" -#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Inv" STR_auml "nta pos:%XUmm" -#define UI_TEXT_PRINTER_READY "Utskrift klar." -#endif - -// *************** French translation **************** -// *************** By Doudou **************** -#if UI_LANGUAGE==7 - -#define UI_TEXT_ON "On" -#define UI_TEXT_OFF "Off" -#define UI_TEXT_NA "N/A" // Output for not available -#define UI_TEXT_YES "Oui" -#define UI_TEXT_NO "Non" -#define UI_TEXT_SEL "\003" -#define UI_TEXT_NOSEL "\004" -#define UI_TEXT_PRINT_POS "Impression..." -#define UI_TEXT_PRINTING "Impression" -#define UI_TEXT_IDLE "Au Repos" -#define UI_TEXT_NOSDCARD "Pas de Carte SD" -#define UI_TEXT_ERROR "**** ERREUR ****" -#define UI_TEXT_BACK "Retour \001" -#define UI_TEXT_QUICK_SETTINGS "Reglages Rapides" -#define UI_TEXT_CONFIGURATION "Configuration" -#define UI_TEXT_POSITION "Position" -#define UI_TEXT_EXTRUDER "Extrudeuse" -#define UI_TEXT_SD_CARD "Carte SD" -#define UI_TEXT_DEBUGGING "Deboguer" -#define UI_TEXT_HOME_ALL "Accueil Tout" -#define UI_TEXT_HOME_X "Accueil X" -#define UI_TEXT_HOME_Y "Accueil Y" -#define UI_TEXT_HOME_Z "Accueil Z" -#define UI_TEXT_PREHEAT_PLA "Prechauf. PLA" -#define UI_TEXT_PREHEAT_ABS "Prechauf. ABS" -#define UI_TEXT_LIGHTS_ONOFF "Eclairage :%lo" -#define UI_TEXT_COOLDOWN "Refroidir" -#define UI_TEXT_SET_TO_ORIGIN "Set to Origin" -#define UI_TEXT_DISABLE_STEPPER "Desactiv. Moteurs" -#define UI_TEXT_X_POSITION "Position X" -#define UI_TEXT_X_POS_FAST "Pos. Rapide X" -#define UI_TEXT_Y_POSITION "Position Y" -#define UI_TEXT_Y_POS_FAST "Pos. Rapide Y" -#define UI_TEXT_Z_POSITION "Position Z" -#define UI_TEXT_Z_POS_FAST "Pos. Rapide Z" -#define UI_TEXT_E_POSITION "Position Extr." -#define UI_TEXT_BED_TEMP "Lit Temp.: %Eb\002C" -#define UI_TEXT_EXTR0_TEMP "Temp. 1 : %E0\002C" -#define UI_TEXT_EXTR1_TEMP "Temp. 2 : %E1\002C" -#define UI_TEXT_EXTR2_TEMP "Temp. 2 : %E2\002C" -#define UI_TEXT_EXTR0_OFF "Extrudeuse 1 Off" -#define UI_TEXT_EXTR1_OFF "Extrudeuse 2 Off" -#define UI_TEXT_EXTR2_OFF "Extrudeuse 3 Off" -#define UI_TEXT_EXTR0_SELECT "%X0 Select. Extr.0" -#define UI_TEXT_EXTR1_SELECT "%X1 Select. Extr.1" -#define UI_TEXT_EXTR2_SELECT "%X1 Select. Extr.2" -#define UI_TEXT_EXTR_ORIGIN "Set Origin" -#define UI_TEXT_PRINT_X "Imprim. X:%ax" -#define UI_TEXT_PRINT_Y "Imprim. Y:%ay" -#define UI_TEXT_PRINT_Z "Imprim. Z:%az" -#define UI_TEXT_PRINT_Z_DELTA "Imprim.:%az" -#define UI_TEXT_MOVE_X "Deplac. X:%aX" -#define UI_TEXT_MOVE_Y "Deplac. Y:%aY" -#define UI_TEXT_MOVE_Z "Deplac. Z:%aZ" -#define UI_TEXT_MOVE_Z_DELTA "Deplac.:%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 "Stock. Dans EEPROM" -#define UI_TEXT_LOAD_EEPROM "Charg. f. EEPROM" -#define UI_TEXT_DBG_ECHO "Echo :%do" -#define UI_TEXT_DBG_INFO "Info :%di" -#define UI_TEXT_DBG_ERROR "Erreurs :%de" -#define UI_TEXT_DBG_DRYRUN "Fonct. a Vide:%dd" -#define UI_TEXT_OPS_OFF "%O0 OPS Off" -#define UI_TEXT_OPS_CLASSIC "%O1 OPS Classiq." -#define UI_TEXT_OPS_FAST "%O2 OPS Rapide" -#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 "Déplac. Apres:%Oa" -#define UI_TEXT_ANTI_OOZE "Anti Ooze" -#define UI_TEXT_PRINT_FILE "Imprim. fichier" -#define UI_TEXT_PAUSE_PRINT "Pause Impress." -#define UI_TEXT_CONTINUE_PRINT "Continuer Impress." -#define UI_TEXT_UNMOUNT_CARD "Retirer Carte" -#define UI_TEXT_MOUNT_CARD "Inserer Carte" -#define UI_TEXT_DELETE_FILE "Supp. fichier" -#define UI_TEXT_FEEDRATE "Avance" -#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_MAX_Z_DELTA "Max:%fz" -#define UI_TEXT_FEED_HOME_X "Accueil X:%fX" -#define UI_TEXT_FEED_HOME_Y "Accueil Y:%fY" -#define UI_TEXT_FEED_HOME_Z "Accueil Z:%fZ" -#define UI_TEXT_FEED_HOME_Z_DELTA "Accueil:%fZ" -#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Min Butee:%sx","Max Butee:%sX","" -#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Min Butee:%sy","Max Butee:%sY","" -#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Min Butee:%sz","Max Butee:%sZ","" -#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Min Butee:%sx","Max Butee:%sX","" -#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Min Butee:%sy","Max Butee:%sY","" -#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Min Butee:%sz","Max Butee:%sZ","" -#define UI_TEXT_ACTION_EPOSITION_FAST2 "E:%x3 mm","1 clic = 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 "Vit. Ventil." -#define UI_TEXT_ACTION_FANSPEED "Vit. Ventil.:%Fs%%%" -#define UI_TEXT_FAN_OFF "Arret Ventil." -#define UI_TEXT_FAN_25 "Ventil. 25%%%" -#define UI_TEXT_FAN_50 "Ventil. 50%%%" -#define UI_TEXT_FAN_75 "Ventil. 75%%%" -#define UI_TEXT_FAN_FULL "Ventil. Max" -#define UI_TEXT_STEPPER_INACTIVE "Arret Moteurs" -#define UI_TEXT_STEPPER_INACTIVE2 "Dis. Apres: %is","[min] 0=Off" -#define UI_TEXT_POWER_INACTIVE "Arret Alim." -#define UI_TEXT_POWER_INACTIVE2 "Dis. Apres: %ip","[min] 0=Off" -#define UI_TEXT_GENERAL "General" -#define UI_TEXT_BAUDRATE "Baudrate:%oc" -#define UI_TEXT_EXTR_STEPS "Pas/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.Temps:%Xw" -#define UI_TEXT_EXTR_ADVANCE_L "Avance lin:%Xl" -#define UI_TEXT_EXTR_ADVANCE_K "Avance quad:%Xa" -#define UI_TEXT_EXTR_MANAGER "Controle:%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 "Chauff. Extrud." -#define UI_TEXT_HEATING_BED "Chauff. Lit" -#define UI_TEXT_KILLED "Stoppe" -#define UI_TEXT_STEPPER_DISABLED "Moteurs Arretes" -#define UI_TEXT_EEPROM_STORED "Configuration","Stock. Dans EEPROM" -#define UI_TEXT_EEPROM_LOADED "Configuration","Charg. f. EEPROM" -#define UI_TEXT_UPLOADING "Telechargement.." -#define UI_TEXT_PAGE_BUFFER "Tampon:%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_EXTRUDER3 "E3:%e2/%E2\002C\176%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb\002C\176%ob" -#define UI_TEXT_SPEED_MULTIPLY "Vit. Mul.:%om%%%" -#define UI_TEXT_FLOW_MULTIPLY "Flow Mul.:%of%%%" -#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "Att. Temp.%XT\002C" -#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Att. Units:%XUmm" -#define UI_TEXT_PRINTER_READY "imprimante prete" -// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES -// ___88 days 12:45 -#define UI_TEXT_PRINTTIME_DAYS " jours " -#define UI_TEXT_PRINTTIME_HOURS ":" -#define UI_TEXT_PRINTTIME_MINUTES "" -#define UI_TEXT_PRINT_TIME "Temps Impression" -#define UI_TEXT_PRINT_FILAMENT "Filament Imprime" -#define UI_TEXT_PRINTED "Imprime" -#define UI_TEXT_POWER "ATX power on/off" -#define UI_TEXT_STRING_HM_DEADTIME "PWM" -#define UI_TEXT_STRING_HM_SLOWBANG "Tout ou Rien" -#define UI_TEXT_STOP_PRINT "Arret Impress." - -#endif - -// *************** Czech translation **************** -// *************** By Majkl **************** -// version: 2014/08/27 -#if UI_LANGUAGE==8 - -#define UI_TEXT_ON "Zap" -#define UI_TEXT_OFF "Vyp" -#define UI_TEXT_NA "neni" // Output for not available -#define UI_TEXT_YES "Ano" -#define UI_TEXT_NO "Ne" -#define UI_TEXT_SEL "\003" -#define UI_TEXT_NOSEL "\004" -#define UI_TEXT_PRINT_POS "Tisknu..." -#define UI_TEXT_PRINTING "Tisknu" -#define UI_TEXT_IDLE "V klidu" -#define UI_TEXT_NOSDCARD "Neni SD karta" -#define UI_TEXT_ERROR "**** CHYBA ****" -#define UI_TEXT_BACK "Zpet \001" -#define UI_TEXT_QUICK_SETTINGS "Zakladni nastaveni" -#define UI_TEXT_CONFIGURATION "Nastaveni" -#define UI_TEXT_POSITION "Pozice" -#define UI_TEXT_EXTRUDER "Extruder" -#define UI_TEXT_SD_CARD "SD karta" -#define UI_TEXT_DEBUGGING "Debug" -#define UI_TEXT_HOME_ALL "Home vsech" -#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 "Ohrat pro PLA" -#define UI_TEXT_PREHEAT_ABS "Ohrat pro ABS" -#define UI_TEXT_COOLDOWN "Zchladit" -#define UI_TEXT_SET_TO_ORIGIN "Nastavit pocatek" -#define UI_TEXT_DISABLE_STEPPER "Vypnout motory" -#define UI_TEXT_X_POSITION "X pozice" -#define UI_TEXT_X_POS_FAST "X rychle" -#define UI_TEXT_Y_POSITION "Y pozice" -#define UI_TEXT_Y_POS_FAST "Y rychle" -#define UI_TEXT_Z_POSITION "Z pozice" -#define UI_TEXT_Z_POS_FAST "Z rychle" -#define UI_TEXT_E_POSITION "Pozice extruderu" -#define UI_TEXT_BED_TEMP "Teplota desky: %Eb\002C" -#define UI_TEXT_EXTR0_TEMP "Teplota 1: %E0\002C" -#define UI_TEXT_EXTR1_TEMP "Teplota 2: %E1\002C" -#define UI_TEXT_EXTR2_TEMP "Teplota 2: %E2\002C" -#define UI_TEXT_EXTR0_OFF "Extruder 1 vyp." -#define UI_TEXT_EXTR1_OFF "Extruder 2 vyp." -#define UI_TEXT_EXTR2_OFF "Extruder 3 vyp." -#define UI_TEXT_EXTR0_SELECT "%X0 Zvolit Extr. 1" -#define UI_TEXT_EXTR1_SELECT "%X1 Zvolit Extr. 2" -#define UI_TEXT_EXTR2_SELECT "%X1 Zvolit Extr. 3" -#define UI_TEXT_EXTR_ORIGIN "Nastavit pocatek" -#define UI_TEXT_PRINT_X "Tisk X:%ax" -#define UI_TEXT_PRINT_Y "Tisk Y:%ay" -#define UI_TEXT_PRINT_Z "Tisk Z:%az" -#define UI_TEXT_PRINT_Z_DELTA "Tisk:%az" -#define UI_TEXT_MOVE_X "Posun X:%aX" -#define UI_TEXT_MOVE_Y "Posun Y:%aY" -#define UI_TEXT_MOVE_Z "Posun Z:%aZ" -#define UI_TEXT_MOVE_Z_DELTA "Posun:%aZ" -#define UI_TEXT_JERK "Jerk:%aj" -#define UI_TEXT_ZJERK "Z-Jerk:%aJ" -#define UI_TEXT_ACCELERATION "Akcelerace" -#define UI_TEXT_STORE_TO_EEPROM "Ulozit do EEPROM" -#define UI_TEXT_LOAD_EEPROM "Nahrat z EEPROM" -#define UI_TEXT_DBG_ECHO "Echo :%do" -#define UI_TEXT_DBG_INFO "Info :%di" -#define UI_TEXT_DBG_ERROR "Chyby :%de" -#define UI_TEXT_DBG_DRYRUN "Beh nanecisto:%dd" -#define UI_TEXT_OPS_OFF "%O0 OPS Vypnuto" -#define UI_TEXT_OPS_CLASSIC "%O1 OPS Klasicke" -#define UI_TEXT_OPS_FAST "%O2 OPS Rychle" -#define UI_TEXT_OPS_RETRACT "Retrakce :%Or" -#define UI_TEXT_OPS_BACKSLASH "Vule. :%Ob" -#define UI_TEXT_OPS_MINDIST "Min.vzd,:%Od" -#define UI_TEXT_OPS_MOVE_AFTER "Posunuti po:%Oa" -#define UI_TEXT_ANTI_OOZE "Proti kapani" -#define UI_TEXT_PRINT_FILE "Tisknout soubor" -#define UI_TEXT_PAUSE_PRINT "Pozastavit tisk" -#define UI_TEXT_CONTINUE_PRINT "Pokracovani tisku" -#define UI_TEXT_UNMOUNT_CARD "Odpojit kartu" -#define UI_TEXT_MOUNT_CARD "Pripojit kartu" -#define UI_TEXT_DELETE_FILE "Smazat soubor" -#define UI_TEXT_FEEDRATE "Rychlost" -#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_MAX_Z_DELTA "Max:%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_FEED_HOME_Z_DELTA "Home:%fZ" -#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Min koncak:%sx","Max koncak:%sX","" -#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Min koncak:%sy","Max koncak:%sY","" -#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Min koncak:%sz","Max koncak:%sZ","" -#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Min koncak:%sx","Max koncak:%sX","" -#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Min koncak:%sy","Max koncak:%sY","" -#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Min koncak:%sz","Max koncak:%sZ","" -#define UI_TEXT_ACTION_EPOSITION_FAST2 "E:%x3 mm","1 kliknuti = 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 "Rychlost vetraku" -#define UI_TEXT_ACTION_FANSPEED "Aktualni rychlost:%Fs%%%" -#define UI_TEXT_FAN_OFF "Vypnout" -#define UI_TEXT_FAN_25 "Vetrak na 25%%%" -#define UI_TEXT_FAN_50 "Vetrak na 50%%%" -#define UI_TEXT_FAN_75 "Vetrak na 75%%%" -#define UI_TEXT_FAN_FULL "Vetrak na plno" -#define UI_TEXT_STEPPER_INACTIVE "Neaktivni motory" -#define UI_TEXT_STEPPER_INACTIVE2 "Vypnout po :%i m","[min] 0=Off" -#define UI_TEXT_POWER_INACTIVE "Max. neaktivni" -#define UI_TEXT_POWER_INACTIVE2 "Vypnout po: %i m","[min] 0=Off" -#define UI_TEXT_GENERAL "Zakladni" -#define UI_TEXT_BAUDRATE "Rychlost:%oc" -#define UI_TEXT_EXTR_STEPS "kroku/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 "Zrychl.:%XA" -#define UI_TEXT_EXTR_WATCH "Stab.cas:%Xw" -#define UI_TEXT_EXTR_ADVANCE_L "Rozsir. lin:%Xl" -#define UI_TEXT_EXTR_ADVANCE_K "Rozsir. 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 "Akce:%la" -#define UI_TEXT_HEATING_EXTRUDER "Ohrivani extruderu" -#define UI_TEXT_HEATING_BED "Ohrivani desky" -#define UI_TEXT_KILLED "Zastaveno" -#define UI_TEXT_STEPPER_DISABLED "Motor vypnut" -#define UI_TEXT_EEPROM_STORED "Konfigurace","ulozena v EEPROM" -#define UI_TEXT_EEPROM_LOADED "Konfigurace","nactena z EEPROM" -#define UI_TEXT_UPLOADING "Nahravam..." -#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_EXTRUDER3 "E3:%e2/%E2\002C\176%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb\002C\176%ob" -#define UI_TEXT_SPEED_MULTIPLY "Rychlost:%om%%%" -#define UI_TEXT_FLOW_MULTIPLY "Extruder:%of%%%" -#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "Tepl. cekani%XT\002C" -#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Jedn. cekani:%XUmm" -#define UI_TEXT_PRINTER_READY "Tiskarna OK" -#define UI_TEXT_SD_REMOVED "SD karta vyjmuta." -#define UI_TEXT_SD_INSERTED "Vlozena SD karta" -// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES -// ___88 days 12:45 -#define UI_TEXT_PRINTTIME_DAYS " dnu " -#define UI_TEXT_PRINTTIME_HOURS ":" -#define UI_TEXT_PRINTTIME_MINUTES "" -#define UI_TEXT_PRINT_TIME "Cas tisku" -#define UI_TEXT_PRINT_FILAMENT "Protisknuto" -#define UI_TEXT_PRINTED "Protisknuto" -#define UI_TEXT_POWER "Zapnout ATX zdroj" -#define UI_TEXT_STRING_HM_DEADTIME "Dead Time" -#define UI_TEXT_STRING_HM_SLOWBANG "SlowBang" -#define UI_TEXT_STOP_PRINT "Zastavit tisk" - -#endif - - -// *************** Polish translation **************** -// *************** By MIS **************** -// version: 2015/01/18 -#if UI_LANGUAGE==9 - -#define UI_TEXT_ON "Zal" -#define UI_TEXT_OFF "Wyl" -#define UI_TEXT_NA "Brak" // Output for not available -#define UI_TEXT_YES "Tak" -#define UI_TEXT_NO "Nie" -#define UI_TEXT_SEL "\003" -#define UI_TEXT_NOSEL "\004" -#define UI_TEXT_PRINT_POS "Drukowanie..." -#define UI_TEXT_PRINTING "Drukowanie" -#define UI_TEXT_IDLE "Wolna" -#define UI_TEXT_NOSDCARD "Brak karty SD" -#define UI_TEXT_ERROR "**** BLAD ****" -#define UI_TEXT_BACK "Powrot \001" -#define UI_TEXT_QUICK_SETTINGS "Szybkie ustawienia" -#define UI_TEXT_CONFIGURATION "Konfiguracja" -#define UI_TEXT_POSITION "Pozycja" -#define UI_TEXT_EXTRUDER "Ekstruder" -#define UI_TEXT_SD_CARD "Karta SD" -#define UI_TEXT_DEBUGGING "Testowanie" -#define UI_TEXT_HOME_ALL "Zeruj wszystkie osie" -#define UI_TEXT_HOME_X "Zeruj X" -#define UI_TEXT_HOME_Y "Zeruj Y" -#define UI_TEXT_HOME_Z "Zeruj Z" -#define UI_TEXT_PREHEAT_PLA "Rozgrzej PLA" -#define UI_TEXT_PREHEAT_ABS "Rozgrzej ABS" -#define UI_TEXT_LIGHTS_ONOFF "Oswietlenie :%lo" -#define UI_TEXT_COOLDOWN "Chlodzenie" -#define UI_TEXT_SET_TO_ORIGIN "Ustaw jako zero" -#define UI_TEXT_DISABLE_STEPPER "Wylacz silniki" -#define UI_TEXT_X_POSITION "Pozycja X" -#define UI_TEXT_X_POS_FAST "Pozycja X Szybko" -#define UI_TEXT_Y_POSITION "Pozycja Y" -#define UI_TEXT_Y_POS_FAST "Pozycja Y Szybko" -#define UI_TEXT_Z_POSITION "Pozycja Z" -#define UI_TEXT_Z_POS_FAST "Pozycja Z Szybko" -#define UI_TEXT_E_POSITION "Pozycja Extrudera" -#define UI_TEXT_BED_TEMP "Temp.Stolu: %Eb\002C" -#define UI_TEXT_EXTR0_TEMP "Temp.Extr1: %E0\002C" -#define UI_TEXT_EXTR1_TEMP "Temp.Extr2: %E1\002C" -#define UI_TEXT_EXTR2_TEMP "Temp.Extr3: %E2\002C" -#define UI_TEXT_EXTR0_OFF "Wyl. Extruder 1" -#define UI_TEXT_EXTR1_OFF "Wyl. Extruder 2" -#define UI_TEXT_EXTR2_OFF "Wyl. Extruder 3" -#define UI_TEXT_EXTR0_SELECT "%X0 Wybierz Extr. 1" -#define UI_TEXT_EXTR1_SELECT "%X1 Wybierz Extr. 2" -#define UI_TEXT_EXTR2_SELECT "%X1 Wybierz Extr. 3" -#define UI_TEXT_EXTR_ORIGIN "Ustaw jako zero" -#define UI_TEXT_PRINT_X "Drukow. X :%ax" -#define UI_TEXT_PRINT_Y "Drukow. Y :%ay" -#define UI_TEXT_PRINT_Z "Drukow. Z :%az" -#define UI_TEXT_PRINT_Z_DELTA "Drukowania :%az" -#define UI_TEXT_MOVE_X "Przesuw. X :%aX" -#define UI_TEXT_MOVE_Y "Przesuw. Y :%aY" -#define UI_TEXT_MOVE_Z "Przesuw. Z :%aZ" -#define UI_TEXT_MOVE_Z_DELTA "Przesuwania :%aZ" -#define UI_TEXT_JERK "Jerk:%aj" -#define UI_TEXT_ZJERK "Z-Jerk:%aJ" -#define UI_TEXT_ACCELERATION "Przyspieszenie" -#define UI_TEXT_STORE_TO_EEPROM "Zapisz do EEPROM" -#define UI_TEXT_LOAD_EEPROM "Odczyt z EEPROM" -#define UI_TEXT_DBG_ECHO "Echo : %do" -#define UI_TEXT_DBG_INFO "Informacje : %di" -#define UI_TEXT_DBG_ERROR "Bledy : %de" -#define UI_TEXT_DBG_DRYRUN "Bez wydruku : %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 "Przesun po:%Oa" -#define UI_TEXT_ANTI_OOZE "Anti Ooze" -#define UI_TEXT_PRINT_FILE "Drukuj z pliku" -#define UI_TEXT_PAUSE_PRINT "Wstrzymaj druk" -#define UI_TEXT_CONTINUE_PRINT "Wznow drukow." -#define UI_TEXT_UNMOUNT_CARD "Odmontuj karte" -#define UI_TEXT_MOUNT_CARD "Zamontuj karte" -#define UI_TEXT_DELETE_FILE "Usun plik" -#define UI_TEXT_FEEDRATE "Szybkosc" -#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_MAX_Z_DELTA "Max:%fz" -#define UI_TEXT_FEED_HOME_X "Powrot X:%fX" -#define UI_TEXT_FEED_HOME_Y "Powrot Y:%fY" -#define UI_TEXT_FEED_HOME_Z "Powrot Z:%fZ" -#define UI_TEXT_FEED_HOME_Z_DELTA "Powrot:%fZ" -#define UI_TEXT_ACTION_XPOSITION4 "X:%x0 mm","Krancowka MIN: %sx","Krancowka MAX: %sX","" -#define UI_TEXT_ACTION_YPOSITION4 "Y:%x1 mm","Krancowka MIN: %sy","Krancowka Max: %sY","" -#define UI_TEXT_ACTION_ZPOSITION4 "Z:%x2 mm","Krancowka MIN: %sz","Krancowka Max: %sZ","" -#define UI_TEXT_ACTION_XPOSITION_FAST4 "X:%x0 mm","Krancowka MIN: %sx","Krancowka MAX: %sX","" -#define UI_TEXT_ACTION_YPOSITION_FAST4 "Y:%x1 mm","Krancowka MIN: %sy","Krancowka MAX: %sY","" -#define UI_TEXT_ACTION_ZPOSITION_FAST4 "Z:%x2 mm","Krancowka MIN: %sz","Krancowka MAX: %sZ","" -#define UI_TEXT_ACTION_EPOSITION_FAST2 "E:%x3 mm","Jednostka 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 "Obroty wiatraka" -#define UI_TEXT_ACTION_FANSPEED "Obroty wiatraka:%Fs%%%" -#define UI_TEXT_FAN_OFF "Wylacz wiatrak" -#define UI_TEXT_FAN_25 "Ustaw na 25%%%" -#define UI_TEXT_FAN_50 "Ustaw na 50%%%" -#define UI_TEXT_FAN_75 "Ustaw na 75%%%" -#define UI_TEXT_FAN_FULL "Ustaw na 100%%%" -#define UI_TEXT_STEPPER_INACTIVE "Wylacz silniki po" -#define UI_TEXT_STEPPER_INACTIVE2 "Wylacz po: %is min.","0=Nie wylaczaj" -#define UI_TEXT_POWER_INACTIVE "Wylacz zasil. po" -#define UI_TEXT_POWER_INACTIVE2 "Wylacz po: %ip min.","0=Nie wylaczaj" -#define UI_TEXT_GENERAL "Ustawienia glowne" -#define UI_TEXT_BAUDRATE "Szybkosc USB:%oc" -#define UI_TEXT_EXTR_STEPS "Kroki/mm : %Se" -#define UI_TEXT_EXTR_START_FEED "Poczatkowa SZ:%Xf" -#define UI_TEXT_EXTR_MAX_FEED "Max Szybkosc :%XF" -#define UI_TEXT_EXTR_ACCEL "Przyspiesz. :%XA" -#define UI_TEXT_EXTR_WATCH "Czas stabil. :%Xws" -#define UI_TEXT_EXTR_ADVANCE_L "Advance lin :%Xl" -#define UI_TEXT_EXTR_ADVANCE_K "Advance quad :%Xa" -#define UI_TEXT_EXTR_MANAGER "Regulator:%Xh" -#define UI_TEXT_EXTR_DEADTIME "Deadtime :%Xp" -#define UI_TEXT_EXTR_DMAX_DT "Max. PWM :%XD" -#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 "Min I war: %Xm" -#define UI_TEXT_EXTR_DMAX "Max I war: %XM" -#define UI_TEXT_EXTR_PMAX "Max ster.: %XD" -#define UI_TEXT_EXTR_XOFF "Ofset X :%Xx" -#define UI_TEXT_EXTR_YOFF "Ofset Y :%Xy" -#define UI_TEXT_STRING_HM_BANGBANG "Dwustanowy" -#define UI_TEXT_STRING_HM_PID "PID" -#define UI_TEXT_STRING_ACTION "Akcja:%la" -#define UI_TEXT_HEATING_EXTRUDER "Grzanie glowicy" -#define UI_TEXT_HEATING_BED "Grzanie stolu" -#define UI_TEXT_KILLED "Zatrzymany" -#define UI_TEXT_STEPPER_DISABLED "Silniki wylaczone" -#define UI_TEXT_EEPROM_STORED "Konfiguracja","zapisana do EEPROM" -#define UI_TEXT_EEPROM_LOADED "Konfiguracja","odczytana z EEPROM" -#define UI_TEXT_UPLOADING "Ladowanie..." -#define UI_TEXT_PAGE_BUFFER "Bufor:%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_EXTRUDER3 "E3:%e2/%E2\002C\176%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb\002C\176%ob" -#define UI_TEXT_SPEED_MULTIPLY "Szybkosc druku :%om%%%" -#define UI_TEXT_FLOW_MULTIPLY "Przeplyw filam.:%of%%%" -#define UI_TEXT_EXTR_WAIT_RETRACT_TEMP "MinTemp wysuwu:%XT\002" -#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Wysuw rozgrzew:%XUmm" -#define UI_TEXT_SD_REMOVED "Karta SD wyjeta" -#define UI_TEXT_SD_INSERTED "Karta SD wlozona" -#define UI_TEXT_PRINTER_READY "Drukarka gotowa" -// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES -// ___88 days 12:45 -#define UI_TEXT_PRINTTIME_DAYS " dni, " -#define UI_TEXT_PRINTTIME_HOURS ":" -#define UI_TEXT_PRINTTIME_MINUTES " h." -#define UI_TEXT_PRINT_TIME "Czas pracy" -#define UI_TEXT_PRINT_FILAMENT "Zuzyto filamentu" -#define UI_TEXT_POWER "Wl/Wyl zasilanie" -#define UI_TEXT_STRING_HM_DEADTIME "Dead Time" -#define UI_TEXT_STRING_HM_SLOWBANG "SlowBang" -#define UI_TEXT_STOP_PRINT "Przerwij wydruk" -#define UI_TEXT_Z_BABYSTEPPING "Doreguluj Z:%oYmm" -#define UI_TEXT_CHANGE_FILAMENT "Zmiana filamentu" -#define UI_TEXT_WIZ_CH_FILAMENT1 "Zmien filament" -#define UI_TEXT_WIZ_CH_FILAMENT2 "Krec aby przesuwac" -#define UI_TEXT_WIZ_CH_FILAMENT3 "filament w gore/dol" -#define UI_TEXT_CLICK_DONE "Kliknij jak gotowe" -#define UI_TEXT_AUTOLEVEL_ONOFF "Autopoziomow.: %ll" -#define UI_TEXT_SERVOPOS "Pozycja Serwa: %oS" -#define UI_TEXT_IGNORE_M106 "Ignoruj kom. M106 %Fi" - -#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 cSEL -#define UI_TEXT_NOSEL cUNSEL -#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 " cUP -#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" cDEG "C" -#define UI_TEXT_EXTR0_TEMP "Temp. 1 : %E0" cDEG "C" -#define UI_TEXT_EXTR1_TEMP "Temp. 2 : %E1" cDEG "C" -#define UI_TEXT_EXTR2_TEMP "Temp. 2 : %E2" cDEG "C" -#define UI_TEXT_EXTR0_OFF "Extruder 1 Off" -#define UI_TEXT_EXTR1_OFF "Extruder 2 Off" -#define UI_TEXT_EXTR2_OFF "Extruder 3 Off" -#define UI_TEXT_EXTR0_SELECT "%X0 Select Extr. 1" -#define UI_TEXT_EXTR1_SELECT "%X1 Select Extr. 2" -#define UI_TEXT_EXTR2_SELECT "%X1 Select Extr. 3" -#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_PRINT_Z_DELTA "Print:%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_MOVE_Z_DELTA "Move:%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_MAX_Z_DELTA "Max:%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_FEED_HOME_Z_DELTA "Home:%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_ACTION_FANSPEED "Fan speed:%Fs%%%" -#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","[min] 0=Off" -#define UI_TEXT_POWER_INACTIVE "Max. Inactive" -#define UI_TEXT_POWER_INACTIVE2 "Dis. After: %ip","[min] 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_DEADTIME "Deadtime:%Xp" -#define UI_TEXT_EXTR_DMAX_DT "Control PWM:%XM" -#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" cDEG "C" cARROW "%oC" -#define UI_TEXT_PAGE_EXTRUDER1 "E1:%e0/%E0" cDEG "C" cARROW "%o0" -#define UI_TEXT_PAGE_EXTRUDER2 "E2:%e1/%E1" cDEG "C" cARROW "%o1" -#define UI_TEXT_PAGE_EXTRUDER3 "E3:%e2/%E2" cDEG "C" cARROW "%o2" -#define UI_TEXT_PAGE_BED " B:%eb/%Eb" cDEG "C" cARROW "%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" cDEG "C" -#define UI_TEXT_EXTR_WAIT_RETRACT_UNITS "Wait Units:%XUmm" -#define UI_TEXT_PRINTER_READY "Printer ready." -// Printtime output gets aggregated like UI_TEXT_PRINTTIME_DAYSUI_TEXT_PRINTTIME_HOURSUI_TEXT_PRINTTIME_MINUTES -// ___88 days 12:45 -#define UI_TEXT_PRINTTIME_DAYS " days " -#define UI_TEXT_PRINTTIME_HOURS ":" -#define UI_TEXT_PRINTTIME_MINUTES "" -#define UI_TEXT_PRINT_TIME "Printing time" -#define UI_TEXT_PRINT_FILAMENT "Filament printed" -#define UI_TEXT_PRINTED "printed" -#define UI_TEXT_POWER "ATX power on/off" -#define UI_TEXT_STRING_HM_DEADTIME "Dead Time" -#define UI_TEXT_STRING_HM_SLOWBANG "SlowBang" -#define UI_TEXT_STOP_PRINT "Stop Print" -#define UI_TEXT_Z_BABYSTEPPING "Z Babystep.:%oYmm" -#define UI_TEXT_CHANGE_FILAMENT "Change filament" -#define UI_TEXT_WIZ_CH_FILAMENT1 "Change filament" -#define UI_TEXT_WIZ_CH_FILAMENT2 "Rotate to move" -#define UI_TEXT_WIZ_CH_FILAMENT3 "filament up/down" -#define UI_TEXT_CLICK_DONE "Click when done" -#define UI_TEXT_AUTOLEVEL_ONOFF "Autolevel: %ll" -#define UI_TEXT_SERVOPOS "Servo pos.: %oS" -#define UI_TEXT_IGNORE_M106 "Ignore M106 cmd %Fi" -#define UI_TEXT_WIZ_REHEAT1 "Click to reheat" -#define UI_TEXT_WIZ_REHEAT2 "extruders." -#define UI_TEXT_WIZ_WAITTEMP1 "Wait for target" -#define UI_TEXT_WIZ_WAITTEMP2 "temperatures ..." -#define UI_TEXT_EXTRUDER_JAM "Extruder Jam" -#define UI_TEXT_STANDBY "Standby" - -#endif - - +#define UI_TEXT_MAINPAGE6_4_TR "Mul: %om%%% \xfd E: %x4m" +#define UI_TEXT_MAINPAGE6_5_TR "Buf: %oB" +#define UI_TEXT_MAINPAGE6_6_TR "%os" +#define UI_TEXT_MAINPAGE_TEMP_BED_TR cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_BED_TR "B%eB/%Eb" cDEG +#define UI_TEXT_MAINPAGE_Z_BUF_TR "Z:%x2 Buf : %oB" +#define UI_TEXT_MAINPAGE_MUL_EUSAGE_TR "Mul: %om E:%x4" +#define UI_TEXT_MAINPAGE_XY_TR "X:%x0 Y:%x1" +#define UI_TEXT_PRINT_TIME_VALUE_TR "%Ut" +#define UI_TEXT_PRINT_FILAMENT_VALUE_TR "%Uf m" +#define UI_TEXT_METER_PRINTED_TR "%Uf m " UI_TEXT_PRINTED_TR +#define UI_TEXT_STATUS_TR "%os" +#define UI_TEXT_EMPTY_TR "" +#define UI_TEXT_TEMP_SET_TR cTEMP "%ec/%Ec" cDEG +#define UI_TEXT_CURRENT_TEMP_TR cTEMP "%ec" cDEG +#define UI_TEXT_COATING_THICKNESS_TR " %oCmm" +#define UI_TEXT_EXTR3_TEMP_TR "Sic. 4 : %E3" cDEG "C" +#define UI_TEXT_EXTR4_TEMP_TR "Sic. 5 : %E4" cDEG "C" +#define UI_TEXT_EXTR5_TEMP_TR "Sic. 6 : %E5" cDEG "C" +#define UI_TEXT_EXTR3_OFF_TR "Ext. 4’u kapat" +#define UI_TEXT_EXTR4_OFF_TR " Ext. 5’i kapat " +#define UI_TEXT_EXTR5_OFF_TR " Ext. 6’yi kapat " +#define UI_TEXT_EXTR3_SELECT_TR "%X3 Ext. 4’u sec " +#define UI_TEXT_EXTR4_SELECT_TR "%X4 Ext. 5’i sec " +#define UI_TEXT_EXTR5_SELECT_TR "%X5 Ext. 6’yi sec " +#define UI_TEXT_DITTO_0_TR "%D0 Kopyalama" +#define UI_TEXT_DITTO_1_TR "%D1 1 kopya" +#define UI_TEXT_DITTO_2_TR "%D2 2 kopya" +#define UI_TEXT_DITTO_3_TR "%D3 3 kopya" +#define UI_TEXT_ZPROBE_HEIGHT_TR "Z-prob yuksekligi:%zh" +#define UI_TEXT_OFFSETS_TR "Set print offsets" +#define UI_TEXT_X_OFFSET_TR "Set X offset:%T0mm" +#define UI_TEXT_Y_OFFSET_TR "Set Y offset:%T1mm" +#define UI_TEXT_Z_OFFSET_TR "Set Z offset:%T2mm" + diff --git a/Repetier/uimenu.h b/Repetier/uimenu.h index d98b467..1d4916f 100644 --- a/Repetier/uimenu.h +++ b/Repetier/uimenu.h @@ -68,7 +68,8 @@ debug %dd : Debug dry run state. extruder -%ec : Current extruder temperature +%ec : Current extruder temperature +%ed : Number of copies for ditto mode %eIc : Current extruder temperature integer (shorter) %eb : Current heated bed temperature %e0..9 : Temp. of extruder 0..9 @@ -76,7 +77,7 @@ extruder %Ec : Target temperature of current extruder %Eb : Target temperature of heated bed %E0-9 : Target temperature of extruder 0..9 - +%D0-3 : Ditto mode selected feed rate %fx : Max. feedrate x direction %fy : Max. feedrate y direction @@ -106,6 +107,7 @@ random stuff %on : current extruder number (1,2,3...) %oS : servo position %oY : babysteps counter +%BC : Bed coating thickness stops %sx : State of x min endstop. @@ -132,6 +134,11 @@ extruder position %x3 : Current extruder position %x4 : Printed since temperature on in meters (for filament usage) +Print offsets +%T0 : X offset +%T1 : Y offset +%T2 : Z offset + extruder parameters %X0..9 : Extruder selected marker %Xi : PID I gain @@ -162,7 +169,10 @@ delta stuff %yX : high (Z) tower x offset mm %yY : high (Z) tower y offset mm %YX : high (Z) tower x offset steps -%YY : high (Z) tower y offset steps +%YY : high (Z) tower y offset steps + +Z-Probing +%zh : z-probe height */ #if UI_DISPLAY_TYPE != NO_DISPLAY @@ -185,6 +195,7 @@ more then one information page. */ /* Define your pages using dynamic strings. To define a page use +UI_PAGE6(name,row1,row2,row3,row4,row5,row6); UI_PAGE4(name,row1,row2,row3,row4); for 4 row displays and UI_PAGE2(name,row1,row2); @@ -195,82 +206,91 @@ for 2 row displays. You can add additional pages or change the default pages lik //graphic main status - UI_PAGE6(ui_page1,"\xa %e0/%E0\xb0 X:%x0", - #if NUM_EXTRUDER > 1 && MIXING_EXTRUDER == 0 - "\xa %e1/%E1\xb0 Y:%x1", - #elif HAVE_HEATED_BED - "\xe %eb/%Eb\xb0 Y:%x1", - #else - " Y:%x1", - #endif - #if HAVE_HEATED_BED && NUM_EXTRUDER > 1 && MIXING_EXTRUDER == 0 - "\xe %eb/%Eb\xb0 Z:%x2", - #else - "Flow:\xfd %of%%% Z:%x2", - #endif - "Mul: %om%%% \xfd E: %x4m", "Buf: %oB", "%os") + UI_PAGE6_T(ui_page1,UI_TEXT_MAINPAGE6_1_ID,UI_TEXT_MAINPAGE6_2_ID,UI_TEXT_MAINPAGE6_3_ID,UI_TEXT_MAINPAGE6_4_ID,UI_TEXT_MAINPAGE6_5_ID,UI_TEXT_MAINPAGE6_6_ID) #if EEPROM_MODE != 0 - UI_PAGE4(ui_page2,UI_TEXT_PRINT_TIME,"%Ut",UI_TEXT_PRINT_FILAMENT,"%Uf m") + UI_PAGE4_T(ui_page2,UI_TEXT_PRINT_TIME_ID,UI_TEXT_PRINT_TIME_VALUE_ID,UI_TEXT_PRINT_FILAMENT_ID,UI_TEXT_PRINT_FILAMENT_VALUE_ID) #define UI_PRINTTIME_PAGES ,&ui_page2 #define UI_PRINTTIME_COUNT 1 #else #define UI_PRINTTIME_PAGES #define UI_PRINTTIME_COUNT 0 + #endif + +#if NUM_EXTRUDER > 2 && MIXING_EXTRUDER == 0 + UI_PAGE6_T(ui_page3,UI_TEXT_EXTR0_TEMP_ID,UI_TEXT_EXTR1_TEMP_ID,UI_TEXT_EXTR2_TEMP_ID, +#if NUM_EXTRUDER > 3 + UI_TEXT_EXTR3_TEMP_ID, +#else + UI_TEXT_EMPTY_ID, +#endif +#if NUM_EXTRUDER > 4 + UI_TEXT_EXTR4_TEMP_ID, +#elif HAVE_HEATED_BED + UI_TEXT_BED_TEMP_ID, +#else + UI_TEXT_EMPTY_ID, +#endif + UI_TEXT_STATUS_ID) + #define UI_EXTRUDERS_PAGES ,&ui_page3 + #define UI_EXTRUDERS_PAGES_COUNT 1 + #else + #define UI_EXTRUDERS_PAGES + #define UI_EXTRUDERS_PAGES_COUNT 0 #endif /* Merge pages together. Use the following pattern: #define UI_PAGES {&name1,&name2,&name3} */ - #define UI_PAGES {&ui_page1 UI_PRINTTIME_PAGES} + #define UI_PAGES {&ui_page1 UI_PRINTTIME_PAGES UI_EXTRUDERS_PAGES} // How many pages do you want to have. Minimum is 1. - #define UI_NUM_PAGES 1+UI_PRINTTIME_COUNT + #define UI_NUM_PAGES 1+UI_PRINTTIME_COUNT+UI_EXTRUDERS_PAGES_COUNT #elif UI_ROWS >= 4 #if HAVE_HEATED_BED #if NUM_EXTRUDER > 0 // UI_PAGE4(ui_page1,cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG,"Z:%x2 Buf : %oB","Mul: %om Flow: %of","%os") - UI_PAGE4(ui_page1,cTEMP "%ec/%Ec" cDEG "B%eB/%Eb" cDEG,"Z:%x2 Buf : %oB","Mul: %om E:%x4","%os") + UI_PAGE4_T(ui_page1,UI_TEXT_MAINPAGE_TEMP_BED_ID,UI_TEXT_MAINPAGE_Z_BUF_ID,UI_TEXT_MAINPAGE_MUL_EUSAGE_ID,UI_TEXT_STATUS_ID) #else // UI_PAGE4(ui_page1,"B%eB/%Eb" cDEG,"Z:%x2 Buf : %oB","Mul: %om Flow: %of","%os") - UI_PAGE4(ui_page1,"B%eB/%Eb" cDEG,"Z:%x2 Buf : %oB","Mul: %om E:%x4","%os") + UI_PAGE4_T(ui_page1,UI_TEXT_MAINPAGE_BED_ID,UI_TEXT_MAINPAGE_Z_BUF_ID,UI_TEXT_MAINPAGE_MUL_EUSAGE_ID,UI_TEXT_STATUS_ID) #endif //UI_PAGE4(ui_page1,UI_TEXT_PAGE_EXTRUDER,UI_TEXT_PAGE_BED,UI_TEXT_PAGE_BUFFER,"%os"); #else #if NUM_EXTRUDER > 0 - UI_PAGE4(ui_page1,UI_TEXT_PAGE_EXTRUDER,"Z:%x2 mm",UI_TEXT_PAGE_BUFFER,"%os") + UI_PAGE4_T(ui_page1,UI_TEXT_PAGE_EXTRUDER_ID,UI_TEXT_ACTION_ZPOSITION4A_ID,UI_TEXT_PAGE_BUFFER_ID,UI_TEXT_STATUS_ID) #else - UI_PAGE4(ui_page1,"","Z:%x2 mm",UI_TEXT_PAGE_BUFFER,"%os") + UI_PAGE4_T(ui_page1,UI_TEXT_EMPTY_ID,UI_TEXT_ACTION_ZPOSITION4A_ID,UI_TEXT_PAGE_BUFFER_ID,UI_TEXT_STATUS_ID) #endif #endif - UI_PAGE4(ui_page2,"X:%x0 mm","Y:%x1 mm","Z:%x2 mm","%os") + UI_PAGE4_T(ui_page2,UI_TEXT_ACTION_XPOSITION4A_ID,UI_TEXT_ACTION_YPOSITION4A_ID,UI_TEXT_ACTION_ZPOSITION4A_ID,UI_TEXT_STATUS_ID) //UI_PAGE4(ui_page2,"dX:%y0 mm %sX","dY:%y1 mm %sY","dZ:%y2 mm %sZ","%os"); - #if NUM_EXTRUDER>0 - UI_PAGE4(ui_page3,UI_TEXT_PAGE_EXTRUDER1 + #if NUM_EXTRUDER > 0 + UI_PAGE4_T(ui_page3,UI_TEXT_PAGE_EXTRUDER1_ID #else - UI_PAGE4(ui_page3 + UI_PAGE4_T(ui_page3 #endif - #if NUM_EXTRUDER>1 && MIXING_EXTRUDER == 0 - ,UI_TEXT_PAGE_EXTRUDER2 + #if NUM_EXTRUDER > 1 && MIXING_EXTRUDER == 0 + ,UI_TEXT_PAGE_EXTRUDER2_ID #endif #if NUM_EXTRUDER>2 && MIXING_EXTRUDER == 0 - ,UI_TEXT_PAGE_EXTRUDER3 + ,UI_TEXT_PAGE_EXTRUDER3_ID #endif #if HAVE_HEATED_BED - ,UI_TEXT_PAGE_BED + ,UI_TEXT_PAGE_BED_ID #endif #if (NUM_EXTRUDER >= 3 && MIXING_EXTRUDER == 0 && !HAVE_HEATED_BED) || (NUM_EXTRUDER==2 && MIXING_EXTRUDER == 0 && HAVE_HEATED_BED==true) - ,"%os" + ,UI_TEXT_STATUS_ID #elif (NUM_EXTRUDER == 2 && MIXING_EXTRUDER == 0) || ((NUM_EXTRUDER == 1 || MIXING_EXTRUDER == 1) && HAVE_HEATED_BED) - ,"","%os" + ,UI_TEXT_EMPTY_ID,UI_TEXT_STATUS_ID #elif (NUM_EXTRUDER == 1 || MIXING_EXTRUDER == 1) || (NUM_EXTRUDER == 0 && HAVE_HEATED_BED) - ,"","","%os" + ,UI_TEXT_EMPTY_ID,UI_TEXT_EMPTY_ID,UI_TEXT_STATUS_ID #elif NUM_EXTRUDER == 0 - ,"","","","%os" + ,UI_TEXT_EMPTY_ID,UI_TEXT_EMPTY_ID,UI_TEXT_EMPTY_ID,UI_TEXT_STATUS_ID #endif ) #if EEPROM_MODE != 0 - UI_PAGE4(ui_page4,UI_TEXT_PRINT_TIME,"%Ut",UI_TEXT_PRINT_FILAMENT,"%Uf m") + UI_PAGE4_T(ui_page4,UI_TEXT_PRINT_TIME_ID,UI_TEXT_PRINT_TIME_VALUE_ID,UI_TEXT_PRINT_FILAMENT_ID,UI_TEXT_PRINT_FILAMENT_VALUE_ID) #define UI_PRINTTIME_PAGES ,&ui_page4 #define UI_PRINTTIME_COUNT 1 #else @@ -286,12 +306,12 @@ Merge pages together. Use the following pattern: #define UI_NUM_PAGES 3+UI_PRINTTIME_COUNT #else #if HAVE_HEATED_BED -UI_PAGE2(ui_page1,UI_TEXT_PAGE_EXTRUDER,UI_TEXT_PAGE_BED) +UI_PAGE2_T(ui_page1,UI_TEXT_PAGE_EXTRUDER_ID,UI_TEXT_PAGE_BED_ID) #else -UI_PAGE2(ui_page1,UI_TEXT_PAGE_EXTRUDER,"%os") +UI_PAGE2_T(ui_page1,UI_TEXT_PAGE_EXTRUDER_ID,UI_TEXT_STATUS_ID) #endif -UI_PAGE2(ui_page2,"X:%x0 Y:%x1","%os") -UI_PAGE2(ui_page3,"Z:%x2 mm","%os") +UI_PAGE2_T(ui_page2,UI_TEXT_MAINPAGE_XY_ID,UI_TEXT_STATUS_ID) +UI_PAGE2_T(ui_page3,UI_TEXT_ACTION_ZPOSITION4A_DE,UI_TEXT_STATUS_ID) /* Merge pages together. Use the following pattern: #define UI_PAGES {&name1,&name2,&name3} @@ -299,7 +319,8 @@ Merge pages together. Use the following pattern: #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 +#endif + /* ============ MENU definition ================ The menu works the same as pages. In addion you need to define what the lines do @@ -314,47 +335,201 @@ next/previous changes the value ok sets the value if not already done and goes back to previous menu. */ +UI_MENU_ACTIONCOMMAND_T(ui_menu_back,UI_TEXT_BACK_ID,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 + + +// Language selection menu + +#if EEPROM_MODE != 0 +#define FIRSTLANG 1 +#if LANGUAGE_EN_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_en,"English",UI_ACTION_LANGUAGE_EN | UI_ACTION_TOPMENU) +#define ADD_LANG_EN &ui_menu_setlang_en +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_EN +#endif // LANGUAGE_EN_ACTIVE +#if LANGUAGE_DE_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_de,"Deutsch",UI_ACTION_LANGUAGE_DE | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_DE &ui_menu_setlang_de +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_DE ,&ui_menu_setlang_de +#endif +#else +#define ADD_LANG_DE +#endif // LANGUAGE_DE_ACTIVE +#if LANGUAGE_ES_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_es,"Espanol",UI_ACTION_LANGUAGE_ES | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_ES &ui_menu_setlang_es +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_ES ,&ui_menu_setlang_es +#endif +#else +#define ADD_LANG_ES +#endif // LANGUAGE_ES_ACTIVE +#if LANGUAGE_PT_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_pt,"Portugues",UI_ACTION_LANGUAGE_PT | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_PT &ui_menu_setlang_pt +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_PT ,&ui_menu_setlang_pt +#endif +#else +#define ADD_LANG_PT +#endif // LANGUAGE_PT_ACTIVE +#if LANGUAGE_FR_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_fr,"Francais",UI_ACTION_LANGUAGE_FR | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_FR &ui_menu_setlang_fr +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_FR ,&ui_menu_setlang_fr +#endif +#else +#define ADD_LANG_FR +#endif // LANGUAGE_FR_ACTIVE +#if LANGUAGE_NL_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_nl,"Nederlandse",UI_ACTION_LANGUAGE_NL | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_NL &ui_menu_setlang_nl +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_NL ,&ui_menu_setlang_nl +#endif +#else +#define ADD_LANG_NL +#endif // LANGUAGE_NL_ACTIVE +#if LANGUAGE_IT_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_it,"Italiano",UI_ACTION_LANGUAGE_IT | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_IT &ui_menu_setlang_it +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_IT ,&ui_menu_setlang_it +#endif +#else +#define ADD_LANG_IT +#endif // LANGUAGE_IT_ACTIVE +#if LANGUAGE_SE_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_se,"Svenska",UI_ACTION_LANGUAGE_SE | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_SE &ui_menu_setlang_se +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_SE ,&ui_menu_setlang_se +#endif +#else +#define ADD_LANG_SE +#endif // LANGUAGE_SE_ACTIVE +#if LANGUAGE_CZ_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_cz,"Cestina",UI_ACTION_LANGUAGE_CZ | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_CZ &ui_menu_setlang_cz +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_CZ ,&ui_menu_setlang_cz +#endif +#else +#define ADD_LANG_CZ +#endif // LANGUAGE_CZ_ACTIVE +#if LANGUAGE_PL_ACTIVE + UI_MENU_ACTIONCOMMAND(ui_menu_setlang_pl,"Polski",UI_ACTION_LANGUAGE_PL | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_PL &ui_menu_setlang_pl +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_PL ,&ui_menu_setlang_pl +#endif +#else +#define ADD_LANG_PL +#endif // LANGUAGE_PL_ACTIVE +#if LANGUAGE_TR_ACTIVE +UI_MENU_ACTIONCOMMAND(ui_menu_setlang_tr,"T" STR_uuml "rk",UI_ACTION_LANGUAGE_PL | UI_ACTION_TOPMENU) +#if FIRSTLANG +#define ADD_LANG_TR &ui_menu_setlang_tr +#undef FIRSTLANG +#define FIRSTLANG 0 +#else +#define ADD_LANG_TR ,&ui_menu_setlang_tr +#endif +#else +#define ADD_LANG_TR +#endif // LANGUAGE_TR_ACTIVE + +#define UI_MENU_LANGUAGES {UI_MENU_ADDCONDBACK ADD_LANG_EN ADD_LANG_DE ADD_LANG_ES ADD_LANG_PT ADD_LANG_FR ADD_LANG_NL ADD_LANG_IT ADD_LANG_SE ADD_LANG_CZ ADD_LANG_PL ADD_LANG_TR} +#define UI_MENU_LANGUAGES_WIZ {ADD_LANG_EN ADD_LANG_DE ADD_LANG_ES ADD_LANG_PT ADD_LANG_FR ADD_LANG_NL ADD_LANG_IT ADD_LANG_SE ADD_LANG_CZ ADD_LANG_PL ADD_LANG_TR} +UI_MENU(ui_menu_languages,UI_MENU_LANGUAGES,UI_MENU_BACKCNT + LANGUAGE_EN_ACTIVE+LANGUAGE_DE_ACTIVE+LANGUAGE_ES_ACTIVE+LANGUAGE_PT_ACTIVE+LANGUAGE_FR_ACTIVE+LANGUAGE_NL_ACTIVE+LANGUAGE_IT_ACTIVE+LANGUAGE_SE_ACTIVE+LANGUAGE_CZ_ACTIVE+LANGUAGE_PL_ACTIVE+LANGUAGE_TR_ACTIVE) +UI_MENU_SUBMENU_T(ui_menu_conf_lang,UI_TEXT_LANGUAGE_ID,ui_menu_languages) +UI_STICKYMENU(ui_menu_languages_wiz,UI_MENU_LANGUAGES_WIZ,LANGUAGE_EN_ACTIVE+LANGUAGE_DE_ACTIVE+LANGUAGE_ES_ACTIVE+LANGUAGE_PT_ACTIVE+LANGUAGE_FR_ACTIVE+LANGUAGE_NL_ACTIVE+LANGUAGE_IT_ACTIVE+LANGUAGE_SE_ACTIVE+LANGUAGE_CZ_ACTIVE+LANGUAGE_PL_ACTIVE+LANGUAGE_TR_ACTIVE) +#define LANGMENU_ENTRY ,&ui_menu_conf_lang +#define LANGMENU_COUNT 1 +#else +#define LANGMENU_ENTRY +#define LANGMENU_COUNT 0 +#endif + // Error menu -UI_MENU_ACTION2(ui_menu_error,UI_ACTION_DUMMY,UI_TEXT_ERROR,"%oe") +UI_MENU_ACTION2_T(ui_menu_error,UI_ACTION_DUMMY,UI_TEXT_ERROR_ID,UI_TEXT_ERRORMSG_ID) // Filament change wizard #if FEATURE_RETRACTION #if UI_ROWS >= 4 -UI_WIZARD4(ui_wiz_filamentchange, UI_ACTION_WIZARD_FILAMENTCHANGE, UI_TEXT_WIZ_CH_FILAMENT1, UI_TEXT_WIZ_CH_FILAMENT2, UI_TEXT_WIZ_CH_FILAMENT3, UI_TEXT_CLICK_DONE) -UI_WIZARD4(ui_wiz_jamwaitheat, UI_ACTION_WIZARD_JAM_WAITHEAT, UI_TEXT_WIZ_WAITTEMP1, UI_TEXT_WIZ_WAITTEMP2,"",cTEMP "%ec/%Ec" cDEG) -UI_WIZARD4(ui_wiz_jamreheat, UI_ACTION_WIZARD_JAM_REHEAT, UI_TEXT_WIZ_REHEAT1, UI_TEXT_WIZ_REHEAT2,"",cTEMP "%ec" cDEG) +UI_WIZARD4_T(ui_wiz_filamentchange, UI_ACTION_WIZARD_FILAMENTCHANGE, UI_TEXT_WIZ_CH_FILAMENT1_ID, UI_TEXT_WIZ_CH_FILAMENT2_ID, UI_TEXT_WIZ_CH_FILAMENT3_ID, UI_TEXT_CLICK_DONE_ID) +UI_WIZARD4_T(ui_wiz_jamwaitheat, UI_ACTION_WIZARD_JAM_WAITHEAT, UI_TEXT_WIZ_WAITTEMP1_ID, UI_TEXT_WIZ_WAITTEMP2_ID,UI_TEXT_EMPTY_ID,UI_TEXT_TEMP_SET_ID) +UI_WIZARD4_T(ui_wiz_jamreheat, UI_ACTION_WIZARD_JAM_REHEAT, UI_TEXT_WIZ_REHEAT1_ID, UI_TEXT_WIZ_REHEAT2_ID,UI_TEXT_EMPTY_ID,UI_TEXT_CURRENT_TEMP_ID) #else -UI_WIZARD2(ui_wiz_filamentchange, UI_ACTION_WIZARD_FILAMENTCHANGE, UI_TEXT_WIZ_CH_FILAMENT1, UI_TEXT_CLICK_DONE) -UI_WIZARD2(ui_wiz_jamwaitheat, UI_ACTION_WIZARD_JAM_WAITHEAT, UI_TEXT_WIZ_WAITTEMP1, UI_TEXT_WIZ_WAITTEMP2) -UI_WIZARD2(ui_wiz_jamreheat, UI_ACTION_WIZARD_JAM_REHEAT, UI_TEXT_WIZ_REHEAT1, UI_TEXT_WIZ_REHEAT2) +UI_WIZARD2_T(ui_wiz_filamentchange, UI_ACTION_WIZARD_FILAMENTCHANGE, UI_TEXT_WIZ_CH_FILAMENT1_ID, UI_TEXT_CLICK_DONE_ID) +UI_WIZARD2_T(ui_wiz_jamwaitheat, UI_ACTION_WIZARD_JAM_WAITHEAT, UI_TEXT_WIZ_WAITTEMP1_ID, UI_TEXT_WIZ_WAITTEMP2_ID) +UI_WIZARD2_T(ui_wiz_jamreheat, UI_ACTION_WIZARD_JAM_REHEAT, UI_TEXT_WIZ_REHEAT1_ID, UI_TEXT_WIZ_REHEAT2_ID) #endif #endif // **** 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_zpos_notest,UI_ACTION_ZPOSITION_NOTEST,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) -UI_MENU_ACTION4C(ui_menu_zpos_fast_notest,UI_ACTION_ZPOSITION_FAST_NOTEST,UI_TEXT_ACTION_ZPOSITION_FAST4) -#define EPOS_ROWS UI_TEXT_ACTION_EPOSITION_FAST2,UI_TEXT_PAGE_EXTRUDER,"%Uf m " UI_TEXT_PRINTED -UI_MENU_ACTION4C(ui_menu_epos,UI_ACTION_EPOSITION,EPOS_ROWS) +UI_MENU_ACTION4_T(ui_menu_xpos,UI_ACTION_XPOSITION,UI_TEXT_ACTION_XPOSITION4A_ID,UI_TEXT_ACTION_XPOSITION4B_ID,UI_TEXT_ACTION_XPOSITION4C_ID,UI_TEXT_ACTION_XPOSITION4D_ID) +UI_MENU_ACTION4_T(ui_menu_ypos,UI_ACTION_YPOSITION,UI_TEXT_ACTION_YPOSITION4A_ID,UI_TEXT_ACTION_YPOSITION4B_ID,UI_TEXT_ACTION_YPOSITION4C_ID,UI_TEXT_ACTION_YPOSITION4D_ID) +UI_MENU_ACTION4_T(ui_menu_zpos,UI_ACTION_ZPOSITION,UI_TEXT_ACTION_ZPOSITION4A_ID,UI_TEXT_ACTION_ZPOSITION4B_ID,UI_TEXT_ACTION_ZPOSITION4C_ID,UI_TEXT_ACTION_ZPOSITION4D_ID) +UI_MENU_ACTION4_T(ui_menu_zpos_notest,UI_ACTION_ZPOSITION_NOTEST,UI_TEXT_ACTION_ZPOSITION4A_ID,UI_TEXT_ACTION_ZPOSITION4B_ID,UI_TEXT_ACTION_ZPOSITION4C_ID,UI_TEXT_ACTION_ZPOSITION4D_ID) +UI_MENU_ACTION4_T(ui_menu_xpos_fast,UI_ACTION_XPOSITION_FAST,UI_TEXT_ACTION_XPOSITION_FAST4A_ID,UI_TEXT_ACTION_XPOSITION_FAST4B_ID,UI_TEXT_ACTION_XPOSITION_FAST4C_ID,UI_TEXT_ACTION_XPOSITION_FAST4D_ID) +UI_MENU_ACTION4_T(ui_menu_ypos_fast,UI_ACTION_YPOSITION_FAST,UI_TEXT_ACTION_YPOSITION_FAST4A_ID,UI_TEXT_ACTION_YPOSITION_FAST4B_ID,UI_TEXT_ACTION_YPOSITION_FAST4C_ID,UI_TEXT_ACTION_YPOSITION_FAST4D_ID) +UI_MENU_ACTION4_T(ui_menu_zpos_fast,UI_ACTION_ZPOSITION_FAST,UI_TEXT_ACTION_ZPOSITION_FAST4A_ID,UI_TEXT_ACTION_ZPOSITION_FAST4B_ID,UI_TEXT_ACTION_ZPOSITION_FAST4C_ID,UI_TEXT_ACTION_ZPOSITION_FAST4D_ID) +UI_MENU_ACTION4_T(ui_menu_zpos_fast_notest,UI_ACTION_ZPOSITION_FAST_NOTEST,UI_TEXT_ACTION_ZPOSITION_FAST4A_ID,UI_TEXT_ACTION_ZPOSITION_FAST4B_ID,UI_TEXT_ACTION_ZPOSITION_FAST4C_ID,UI_TEXT_ACTION_ZPOSITION_FAST4D_ID) +UI_MENU_ACTION4_T(ui_menu_epos,UI_ACTION_EPOSITION,UI_TEXT_ACTION_EPOSITION_FAST2A_ID,UI_TEXT_ACTION_EPOSITION_FAST2B_ID,UI_TEXT_PAGE_EXTRUDER_ID,UI_TEXT_METER_PRINTED_ID) #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_zpos_notest,UI_ACTION_ZPOSITION_NOTEST,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) -UI_MENU_ACTION2C(ui_menu_zpos_fast_notest,UI_ACTION_ZPOSITION_FAST_NOTEST,UI_TEXT_ACTION_ZPOSITION_FAST2) -UI_MENU_ACTION2C(ui_menu_epos,UI_ACTION_EPOSITION,UI_TEXT_ACTION_EPOSITION_FAST2) +UI_MENU_ACTION2_T(ui_menu_xpos,UI_ACTION_XPOSITION,UI_TEXT_ACTION_XPOSITION2A_ID,UI_TEXT_ACTION_XPOSITION2B_ID) +UI_MENU_ACTION2_T(ui_menu_ypos,UI_ACTION_YPOSITION,UI_TEXT_ACTION_YPOSITION2A_ID,UI_TEXT_ACTION_YPOSITION2B_ID) +UI_MENU_ACTION2_T(ui_menu_zpos,UI_ACTION_ZPOSITION,UI_TEXT_ACTION_ZPOSITION2A_ID,UI_TEXT_ACTION_ZPOSITION2B_ID) +UI_MENU_ACTION2_T(ui_menu_zpos_notest,UI_ACTION_ZPOSITION_NOTEST,UI_TEXT_ACTION_ZPOSITION2A_ID,UI_TEXT_ACTION_ZPOSITION2B_ID) +UI_MENU_ACTION2_T(ui_menu_xpos_fast,UI_ACTION_XPOSITION_FAST,UI_TEXT_ACTION_XPOSITION_FAST2A_ID,UI_TEXT_ACTION_XPOSITION_FAST2B_ID) +UI_MENU_ACTION2_T(ui_menu_ypos_fast,UI_ACTION_YPOSITION_FAST,UI_TEXT_ACTION_YPOSITION_FAST2A_ID,UI_TEXT_ACTION_YPOSITION_FAST2B_ID) +UI_MENU_ACTION2_T(ui_menu_zpos_fast,UI_ACTION_ZPOSITION_FAST,UI_TEXT_ACTION_ZPOSITION_FAST2A_ID,UI_TEXT_ACTION_ZPOSITION_FAST2B_ID) +UI_MENU_ACTION2_T(ui_menu_zpos_fast_notest,UI_ACTION_ZPOSITION_FAST_NOTEST,UI_TEXT_ACTION_ZPOSITION_FAST2A_ID,UI_TEXT_ACTION_ZPOSITION_FAST2B_ID) +UI_MENU_ACTION2_T(ui_menu_epos,UI_ACTION_EPOSITION,UI_TEXT_ACTION_EPOSITION_FAST2A_ID,UI_TEXT_ACTION_EPOSITION_FAST2B_ID) #endif /* @@ -362,28 +537,20 @@ 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_FILTER(ui_menu_home_all,UI_TEXT_HOME_ALL,UI_ACTION_HOME_ALL,0,MENU_MODE_PRINTING) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_home_x,UI_TEXT_HOME_X,UI_ACTION_HOME_X,0,MENU_MODE_PRINTING) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_home_y,UI_TEXT_HOME_Y,UI_ACTION_HOME_Y,0,MENU_MODE_PRINTING) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_home_z,UI_TEXT_HOME_Z,UI_ACTION_HOME_Z,0,MENU_MODE_PRINTING) -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_zpos_notest,UI_TEXT_Z_POSITION,ui_menu_zpos_notest) -UI_MENU_ACTIONSELECTOR(ui_menu_go_epos,UI_TEXT_E_POSITION,ui_menu_epos) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_home_all,UI_TEXT_HOME_ALL_ID,UI_ACTION_HOME_ALL,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_home_x,UI_TEXT_HOME_X_ID,UI_ACTION_HOME_X,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_home_y,UI_TEXT_HOME_Y_ID,UI_ACTION_HOME_Y,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_home_z,UI_TEXT_HOME_Z_ID,UI_ACTION_HOME_Z,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONSELECTOR_T(ui_menu_go_xpos,UI_TEXT_X_POSITION_ID,ui_menu_xpos) +UI_MENU_ACTIONSELECTOR_T(ui_menu_go_ypos,UI_TEXT_Y_POSITION_ID,ui_menu_ypos) +UI_MENU_ACTIONSELECTOR_T(ui_menu_go_zpos,UI_TEXT_Z_POSITION_ID,ui_menu_zpos) +UI_MENU_ACTIONSELECTOR_T(ui_menu_go_zpos_notest,UI_TEXT_Z_POSITION_ID,ui_menu_zpos_notest) +UI_MENU_ACTIONSELECTOR_T(ui_menu_go_epos,UI_TEXT_E_POSITION_ID,ui_menu_epos) #if !UI_SPEEDDEPENDENT_POSITIONING -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) -UI_MENU_ACTIONSELECTOR(ui_menu_go_zfast_notest,UI_TEXT_Z_POS_FAST,ui_menu_zpos_fast_notest) +UI_MENU_ACTIONSELECTOR_T(ui_menu_go_xfast,UI_TEXT_X_POS_FAST_ID,ui_menu_xpos_fast) +UI_MENU_ACTIONSELECTOR_T(ui_menu_go_yfast,UI_TEXT_Y_POS_FAST_ID,ui_menu_ypos_fast) +UI_MENU_ACTIONSELECTOR_T(ui_menu_go_zfast,UI_TEXT_Z_POS_FAST_ID,ui_menu_zpos_fast) +UI_MENU_ACTIONSELECTOR_T(ui_menu_go_zfast_notest,UI_TEXT_Z_POS_FAST_ID,ui_menu_zpos_fast_notest) #define UI_SPEED 2 #define UI_SPEED_X ,&ui_menu_go_xfast,&ui_menu_go_xpos #define UI_SPEED_Y ,&ui_menu_go_yfast,&ui_menu_go_ypos @@ -397,67 +564,137 @@ UI_MENU_ACTIONSELECTOR(ui_menu_go_zfast_notest,UI_TEXT_Z_POS_FAST,ui_menu_zpos_f #define UI_SPEED_Z_NOTEST ,&ui_menu_go_zpos_notest #endif #if FEATURE_SERVO > 0 && UI_SERVO_CONTROL > 0 - UI_MENU_CHANGEACTION(ui_menu_servopos, UI_TEXT_SERVOPOS, UI_ACTION_SERVOPOS) + UI_MENU_CHANGEACTION_T(ui_menu_servopos, UI_TEXT_SERVOPOS_ID, UI_ACTION_SERVOPOS) #define SERVOPOS_COUNT 1 #define SERVOPOS_ENTRY ,&ui_menu_servopos #else #define SERVOPOS_COUNT 0 #define SERVOPOS_ENTRY #endif +// Offsets menu +UI_MENU_CHANGEACTION_T(ui_menu_off_xpos,UI_TEXT_X_OFFSET_ID,UI_ACTION_XOFF) +UI_MENU_CHANGEACTION_T(ui_menu_off_ypos,UI_TEXT_Y_OFFSET_ID,UI_ACTION_YOFF) +UI_MENU_CHANGEACTION_T(ui_menu_off_zpos,UI_TEXT_Z_OFFSET_ID,UI_ACTION_ZOFF) +#define UI_MENU_OFFSETS {UI_MENU_ADDCONDBACK &ui_menu_off_xpos,&ui_menu_off_ypos,&ui_menu_off_zpos} +UI_MENU(ui_menu_offsets,UI_MENU_OFFSETS,UI_MENU_BACKCNT+3) +UI_MENU_SUBMENU_T(ui_menu_go_offsets, UI_TEXT_OFFSETS_ID,ui_menu_offsets) #if DRIVE_SYSTEM != DELTA //Positioning menu for non-delta -#define UI_MENU_POSITIONS {UI_MENU_ADDCONDBACK &ui_menu_home_all,&ui_menu_home_x,&ui_menu_home_y,&ui_menu_home_z UI_SPEED_X UI_SPEED_Y UI_SPEED_Z ,&ui_menu_go_epos SERVOPOS_ENTRY} -UI_MENU(ui_menu_positions,UI_MENU_POSITIONS,5 + 3 * UI_SPEED + UI_MENU_BACKCNT + SERVOPOS_COUNT) +#define UI_MENU_POSITIONS {UI_MENU_ADDCONDBACK &ui_menu_home_all,&ui_menu_home_x,&ui_menu_home_y,&ui_menu_home_z UI_SPEED_X UI_SPEED_Y UI_SPEED_Z ,&ui_menu_go_epos SERVOPOS_ENTRY,&ui_menu_go_offsets} +UI_MENU(ui_menu_positions,UI_MENU_POSITIONS,6 + 3 * UI_SPEED + UI_MENU_BACKCNT + SERVOPOS_COUNT) #else //Positioning menu for delta (removes individual x,y,z homing) -#define UI_MENU_POSITIONS {UI_MENU_ADDCONDBACK &ui_menu_home_all UI_SPEED_X UI_SPEED_Y UI_SPEED_Z ,&ui_menu_go_epos SERVOPOS_ENTRY} -UI_MENU(ui_menu_positions,UI_MENU_POSITIONS,2 + 3 * UI_SPEED + UI_MENU_BACKCNT + SERVOPOS_COUNT) +#define UI_MENU_POSITIONS {UI_MENU_ADDCONDBACK &ui_menu_home_all UI_SPEED_X UI_SPEED_Y UI_SPEED_Z ,&ui_menu_go_epos SERVOPOS_ENTRY,&ui_menu_go_offsets} +UI_MENU(ui_menu_positions,UI_MENU_POSITIONS,3 + 3 * UI_SPEED + UI_MENU_BACKCNT + SERVOPOS_COUNT) #endif // **** Delta calibration menu #if Z_HOME_DIR > 0 -UI_MENU_ACTIONCOMMAND(ui_menu_set_measured_origin,UI_TEXT_SET_MEASURED_ORIGIN,UI_ACTION_SET_MEASURED_ORIGIN) +UI_MENU_ACTIONCOMMAND_T(ui_menu_set_measured_origin,UI_TEXT_SET_MEASURED_ORIGIN_ID,UI_ACTION_SET_MEASURED_ORIGIN) #define UI_MENU_DELTA {UI_MENU_ADDCONDBACK &ui_menu_home_all UI_SPEED_Z_NOTEST,&ui_menu_set_measured_origin} UI_MENU(ui_menu_delta,UI_MENU_DELTA,2 + UI_SPEED + 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) +UI_MENU_ACTIONCOMMAND_T(ui_menu_set_p1,UI_TEXT_SET_P1_ID,UI_ACTION_SET_P1) +UI_MENU_ACTIONCOMMAND_T(ui_menu_set_p2,UI_TEXT_SET_P2_ID,UI_ACTION_SET_P2) +UI_MENU_ACTIONCOMMAND_T(ui_menu_set_p3,UI_TEXT_SET_P3_ID,UI_ACTION_SET_P3) +UI_MENU_ACTIONCOMMAND_T(ui_menu_calculate_leveling,UI_TEXT_CALCULATE_LEVELING_ID,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_SPEED_X UI_SPEED_Y UI_SPEED_Z} UI_MENU(ui_menu_level,UI_MENU_LEVEL,4+3*UI_SPEED+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) -#if NUM_EXTRUDER>2 && MIXING_EXTRUDER == 0 -UI_MENU_CHANGEACTION(ui_menu_ext_temp2,UI_TEXT_EXTR2_TEMP,UI_ACTION_EXTRUDER2_TEMP) +UI_MENU_CHANGEACTION_T(ui_menu_ext_temp0,UI_TEXT_EXTR0_TEMP_ID,UI_ACTION_EXTRUDER0_TEMP) +#if NUM_EXTRUDER > 1 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_ext_temp1,UI_TEXT_EXTR1_TEMP_ID,UI_ACTION_EXTRUDER1_TEMP) +#endif +#if NUM_EXTRUDER > 2 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_ext_temp2,UI_TEXT_EXTR2_TEMP_ID,UI_ACTION_EXTRUDER2_TEMP) #endif -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) -#if NUM_EXTRUDER>2 && MIXING_EXTRUDER == 0 -UI_MENU_ACTIONCOMMAND(ui_menu_ext_sel2,UI_TEXT_EXTR2_SELECT,UI_ACTION_SELECT_EXTRUDER2) +#if NUM_EXTRUDER > 3 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_ext_temp3,UI_TEXT_EXTR3_TEMP_ID,UI_ACTION_EXTRUDER3_TEMP) #endif -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) -#if NUM_EXTRUDER>2 && MIXING_EXTRUDER == 0 -UI_MENU_ACTIONCOMMAND(ui_menu_ext_off2,UI_TEXT_EXTR2_OFF,UI_ACTION_EXTRUDER2_OFF) +#if NUM_EXTRUDER > 4 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_ext_temp4,UI_TEXT_EXTR4_TEMP_ID,UI_ACTION_EXTRUDER4_TEMP) #endif -UI_MENU_ACTIONCOMMAND(ui_menu_ext_origin,UI_TEXT_EXTR_ORIGIN,UI_ACTION_RESET_EXTRUDER) -#if NUM_EXTRUDER==2 && MIXING_EXTRUDER == 0 -#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 -#elif NUM_EXTRUDER > 2 && MIXING_EXTRUDER == 0 -#define UI_MENU_EXTCOND &ui_menu_ext_temp0,&ui_menu_ext_temp1,&ui_menu_ext_temp2,&ui_menu_ext_off0,&ui_menu_ext_off1,&ui_menu_ext_off2,&ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_ext_sel2, -#define UI_MENU_EXTCNT 9 -#else +#if NUM_EXTRUDER > 5 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_ext_temp5,UI_TEXT_EXTR5_TEMP_ID,UI_ACTION_EXTRUDER5_TEMP) +#endif +UI_MENU_CHANGEACTION_T(ui_menu_bed_temp, UI_TEXT_BED_TEMP_ID,UI_ACTION_HEATED_BED_TEMP) +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_sel0,UI_TEXT_EXTR0_SELECT_ID,UI_ACTION_SELECT_EXTRUDER0) +#if NUM_EXTRUDER > 1 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_sel1,UI_TEXT_EXTR1_SELECT_ID,UI_ACTION_SELECT_EXTRUDER1) +#endif +#if NUM_EXTRUDER > 2 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_sel2,UI_TEXT_EXTR2_SELECT_ID,UI_ACTION_SELECT_EXTRUDER2) +#endif +#if NUM_EXTRUDER > 3 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_sel3,UI_TEXT_EXTR3_SELECT_ID,UI_ACTION_SELECT_EXTRUDER3) +#endif +#if NUM_EXTRUDER > 4 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_sel4,UI_TEXT_EXTR4_SELECT_ID,UI_ACTION_SELECT_EXTRUDER4) +#endif +#if NUM_EXTRUDER > 5 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_sel5,UI_TEXT_EXTR5_SELECT_ID,UI_ACTION_SELECT_EXTRUDER5) +#endif +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_off0,UI_TEXT_EXTR0_OFF_ID,UI_ACTION_EXTRUDER0_OFF) +#if NUM_EXTRUDER > 1 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_off1,UI_TEXT_EXTR1_OFF_ID,UI_ACTION_EXTRUDER1_OFF) +#endif +#if NUM_EXTRUDER > 2 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_off2,UI_TEXT_EXTR2_OFF_ID,UI_ACTION_EXTRUDER2_OFF) +#endif +#if NUM_EXTRUDER > 3 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_off3,UI_TEXT_EXTR3_OFF_ID,UI_ACTION_EXTRUDER3_OFF) +#endif +#if NUM_EXTRUDER > 4 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_off4,UI_TEXT_EXTR4_OFF_ID,UI_ACTION_EXTRUDER4_OFF) +#endif +#if NUM_EXTRUDER > 5 && MIXING_EXTRUDER == 0 +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_off5,UI_TEXT_EXTR5_OFF_ID,UI_ACTION_EXTRUDER5_OFF) +#endif +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_origin,UI_TEXT_EXTR_ORIGIN_ID,UI_ACTION_RESET_EXTRUDER) +#if FEATURE_DITTO_PRINTING +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_ditto0,UI_TEXT_DITTO_0_ID,UI_DITTO_0) +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_ditto1,UI_TEXT_DITTO_1_ID,UI_DITTO_1) +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_ditto2,UI_TEXT_DITTO_2_ID,UI_DITTO_2) +UI_MENU_ACTIONCOMMAND_T(ui_menu_ext_ditto3,UI_TEXT_DITTO_3_ID,UI_DITTO_3) +#if NUM_EXTRUDER == 3 +#define UI_DITTO_COMMANDS ,&ui_menu_ext_ditto0,&ui_menu_ext_ditto1,&ui_menu_ext_ditto2 +#define UI_DITTO_COMMANDS_COUNT 3 +#elif NUM_EXTRUDER == 4 +#define UI_DITTO_COMMANDS ,&ui_menu_ext_ditto0,&ui_menu_ext_ditto1,&ui_menu_ext_ditto2,&ui_menu_ext_ditto3 +#define UI_DITTO_COMMANDS_COUNT 4 +#else +#define UI_DITTO_COMMANDS ,&ui_menu_ext_ditto0,&ui_menu_ext_ditto1 +#define UI_DITTO_COMMANDS_COUNT 2 +#endif +#else +#define UI_DITTO_COMMANDS +#define UI_DITTO_COMMANDS_COUNT 0 +#endif +#if MIXING_EXTRUDER || NUM_EXTRUDER == 1 #define UI_MENU_EXTCOND &ui_menu_ext_temp0,&ui_menu_ext_off0, #define UI_MENU_EXTCNT 2 +#elif NUM_EXTRUDER == 2 +#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 +#elif NUM_EXTRUDER == 3 +#define UI_MENU_EXTCOND &ui_menu_ext_temp0,&ui_menu_ext_temp1,&ui_menu_ext_temp2,&ui_menu_ext_off0,&ui_menu_ext_off1,&ui_menu_ext_off2,&ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_ext_sel2, +#define UI_MENU_EXTCNT 9 +#elif NUM_EXTRUDER == 4 +#define UI_MENU_EXTCOND &ui_menu_ext_temp0,&ui_menu_ext_temp1,&ui_menu_ext_temp2,&ui_menu_ext_temp3,&ui_menu_ext_off0,&ui_menu_ext_off1,&ui_menu_ext_off2,&ui_menu_ext_off3,&ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_ext_sel2,&ui_menu_ext_sel3, +#define UI_MENU_EXTCNT 12 +#elif NUM_EXTRUDER == 5 +#define UI_MENU_EXTCOND &ui_menu_ext_temp0,&ui_menu_ext_temp1,&ui_menu_ext_temp2,&ui_menu_ext_temp3,&ui_menu_ext_temp4,&ui_menu_ext_off0,&ui_menu_ext_off1,&ui_menu_ext_off2,&ui_menu_ext_off3,&ui_menu_ext_off4,&ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_ext_sel2,&ui_menu_ext_sel3,&ui_menu_ext_sel4, +#define UI_MENU_EXTCNT 15 +#elif NUM_EXTRUDER == 6 +#define UI_MENU_EXTCOND &ui_menu_ext_temp0,&ui_menu_ext_temp1,&ui_menu_ext_temp2,&ui_menu_ext_temp3,&ui_menu_ext_temp4,&ui_menu_ext_temp5,&ui_menu_ext_off0,&ui_menu_ext_off1,&ui_menu_ext_off2,&ui_menu_ext_off3,&ui_menu_ext_off4,&ui_menu_ext_off5,&ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_ext_sel2,&ui_menu_ext_sel3,&ui_menu_ext_sel4,&ui_menu_ext_sel5, +#define UI_MENU_EXTCNT 18 +#elif NUM_EXTRUDER == 0 +#define UI_MENU_EXTCOND +#define UI_MENU_EXTCNT 0 #endif #if HAVE_HEATED_BED #define UI_MENU_BEDCOND &ui_menu_bed_temp, @@ -467,14 +704,14 @@ UI_MENU_ACTIONCOMMAND(ui_menu_ext_origin,UI_TEXT_EXTR_ORIGIN,UI_ACTION_RESET_EXT #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) +#define UI_MENU_EXTRUDER {UI_MENU_ADDCONDBACK UI_MENU_BEDCOND UI_MENU_EXTCOND &ui_menu_go_epos,&ui_menu_ext_origin UI_DITTO_COMMANDS} +UI_MENU(ui_menu_extruder,UI_MENU_EXTRUDER,UI_MENU_BACKCNT+UI_MENU_BEDCNT+UI_MENU_EXTCNT+2+UI_DITTO_COMMANDS_COUNT) // **** SD card menu // **** Quick menu #if PS_ON_PIN > -1 -UI_MENU_ACTIONCOMMAND(ui_menu_quick_power,UI_TEXT_POWER,UI_ACTION_POWER) +UI_MENU_ACTIONCOMMAND_T(ui_menu_quick_power,UI_TEXT_POWER_ID,UI_ACTION_POWER) #define MENU_PSON_COUNT 1 #define MENU_PSON_ENTRY ,&ui_menu_quick_power #else @@ -482,28 +719,28 @@ UI_MENU_ACTIONCOMMAND(ui_menu_quick_power,UI_TEXT_POWER,UI_ACTION_POWER) #define MENU_PSON_ENTRY #endif #if CASE_LIGHTS_PIN >= 0 -UI_MENU_ACTIONCOMMAND(ui_menu_toggle_light,UI_TEXT_LIGHTS_ONOFF,UI_ACTION_LIGHTS_ONOFF) +UI_MENU_ACTIONCOMMAND_T(ui_menu_toggle_light,UI_TEXT_LIGHTS_ONOFF_ID,UI_ACTION_LIGHTS_ONOFF) #define UI_TOOGLE_LIGHT_ENTRY ,&ui_menu_toggle_light #define UI_TOGGLE_LIGHT_COUNT 1 #else #define UI_TOOGLE_LIGHT_ENTRY #define UI_TOGGLE_LIGHT_COUNT 0 #endif -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_FILTER(ui_menu_quick_origin,UI_TEXT_SET_TO_ORIGIN,UI_ACTION_SET_ORIGIN,0,MENU_MODE_PRINTING) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_quick_stopstepper,UI_TEXT_DISABLE_STEPPER,UI_ACTION_DISABLE_STEPPER,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_T(ui_menu_quick_preheat_pla,UI_TEXT_PREHEAT_PLA_ID,UI_ACTION_PREHEAT_PLA) +UI_MENU_ACTIONCOMMAND_T(ui_menu_quick_preheat_abs,UI_TEXT_PREHEAT_ABS_ID,UI_ACTION_PREHEAT_ABS) +UI_MENU_ACTIONCOMMAND_T(ui_menu_quick_cooldown,UI_TEXT_COOLDOWN_ID,UI_ACTION_COOLDOWN) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_quick_origin,UI_TEXT_SET_TO_ORIGIN_ID,UI_ACTION_SET_ORIGIN,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_quick_stopstepper,UI_TEXT_DISABLE_STEPPER_ID,UI_ACTION_DISABLE_STEPPER,0,MENU_MODE_PRINTING) #if FEATURE_BABYSTEPPING -UI_MENU_CHANGEACTION(ui_menu_quick_zbaby,UI_TEXT_Z_BABYSTEPPING,UI_ACTION_Z_BABYSTEPS) +UI_MENU_CHANGEACTION_T(ui_menu_quick_zbaby,UI_TEXT_Z_BABYSTEPPING_ID,UI_ACTION_Z_BABYSTEPS) #define BABY_CNT 1 #define BABY_ENTRY ,&ui_menu_quick_zbaby #else #define BABY_CNT 0 #define BABY_ENTRY #endif -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) +UI_MENU_CHANGEACTION_T(ui_menu_quick_speedmultiply,UI_TEXT_SPEED_MULTIPLY_ID,UI_ACTION_FEEDRATE_MULTIPLY) +UI_MENU_CHANGEACTION_T(ui_menu_quick_flowmultiply,UI_TEXT_FLOW_MULTIPLY_ID,UI_ACTION_FLOWRATE_MULTIPLY) #ifdef DEBUG_PRINT UI_MENU_ACTIONCOMMAND(ui_menu_quick_debug,"Write Debug",UI_ACTION_WRITE_DEBUG) #define DEBUG_PRINT_COUNT 1 @@ -513,7 +750,7 @@ UI_MENU_ACTIONCOMMAND(ui_menu_quick_debug,"Write Debug",UI_ACTION_WRITE_DEBUG) #define DEBUG_PRINT_EXTRA #endif #if FEATURE_RETRACTION -UI_MENU_ACTIONCOMMAND(ui_menu_quick_changefil,UI_TEXT_CHANGE_FILAMENT,UI_ACTION_WIZARD_FILAMENTCHANGE) +UI_MENU_ACTIONCOMMAND_T(ui_menu_quick_changefil,UI_TEXT_CHANGE_FILAMENT_ID,UI_ACTION_WIZARD_FILAMENTCHANGE) #define UI_CHANGE_FIL_CNT 1 #define UI_CHANGE_FIL_ENT ,&ui_menu_quick_changefil #else @@ -524,19 +761,48 @@ UI_MENU_ACTIONCOMMAND(ui_menu_quick_changefil,UI_TEXT_CHANGE_FILAMENT,UI_ACTION_ #define UI_MENU_QUICK {UI_MENU_ADDCONDBACK &ui_menu_home_all BABY_ENTRY ,&ui_menu_quick_speedmultiply,&ui_menu_quick_flowmultiply UI_TOOGLE_LIGHT_ENTRY UI_CHANGE_FIL_ENT,&ui_menu_quick_preheat_pla,&ui_menu_quick_preheat_abs,&ui_menu_quick_cooldown,&ui_menu_quick_origin,&ui_menu_quick_stopstepper MENU_PSON_ENTRY DEBUG_PRINT_EXTRA} UI_MENU(ui_menu_quick,UI_MENU_QUICK,8+BABY_CNT+UI_MENU_BACKCNT+MENU_PSON_COUNT+DEBUG_PRINT_COUNT+UI_TOGGLE_LIGHT_COUNT+UI_CHANGE_FIL_CNT) +// **** Bed Coating Menu + +#if UI_BED_COATING +UI_MENU_ACTION2_T(ui_menu_nocoating_action, UI_ACTION_DUMMY, UI_TEXT_BED_COATING_SET1_ID, UI_TEXT_NOCOATING_ID) +UI_MENU_ACTION2_T(ui_menu_buildtak_action, UI_ACTION_DUMMY, UI_TEXT_BED_COATING_SET1_ID, UI_TEXT_BUILDTAK_ID) +UI_MENU_ACTION2_T(ui_menu_kapton_action, UI_ACTION_DUMMY, UI_TEXT_BED_COATING_SET1_ID, UI_TEXT_KAPTON_ID) +UI_MENU_ACTION2_T(ui_menu_bluetape_action, UI_ACTION_DUMMY, UI_TEXT_BED_COATING_SET1_ID, UI_TEXT_BLUETAPE_ID) +UI_MENU_ACTION2_T(ui_menu_pettape_action, UI_ACTION_DUMMY, UI_TEXT_BED_COATING_SET1_ID, UI_TEXT_PETTAPE_ID) +UI_MENU_ACTION2_T(ui_menu_gluestick_action, UI_ACTION_DUMMY, UI_TEXT_BED_COATING_SET1_ID, UI_TEXT_GLUESTICK_ID) +UI_MENU_ACTION2_T(ui_menu_coating_custom, UI_ACTION_DUMMY, UI_TEXT_BED_COATING_SET1_ID, UI_TEXT_COATING_THICKNESS_ID) + +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_adjust_nocoating,UI_TEXT_NOCOATING_ID, UI_ACTION_NOCOATING,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_adjust_buildtak,UI_TEXT_BUILDTAK_ID, UI_ACTION_BUILDTAK,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_adjust_kapton,UI_TEXT_KAPTON_ID, UI_ACTION_KAPTON,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_adjust_bluetape,UI_TEXT_BLUETAPE_ID, UI_ACTION_BLUETAPE,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_adjust_pettape,UI_TEXT_PETTAPE_ID, UI_ACTION_PETTAPE,0,MENU_MODE_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_adjust_gluestick,UI_TEXT_GLUESTICK_ID, UI_ACTION_GLUESTICK,0,MENU_MODE_PRINTING) +UI_MENU_CHANGEACTION_FILTER_T(ui_menu_adjust_custom,UI_TEXT_COATING_CUSTOM_ID,UI_ACTION_COATING_CUSTOM,0,MENU_MODE_PRINTING) +#define UI_MENU_ADJUST {UI_MENU_ADDCONDBACK &ui_menu_adjust_nocoating,&ui_menu_adjust_buildtak,&ui_menu_adjust_kapton,&ui_menu_adjust_bluetape,&ui_menu_adjust_pettape,&ui_menu_adjust_gluestick,&ui_menu_adjust_custom} +UI_MENU(ui_menu_adjust,UI_MENU_ADJUST,7+UI_MENU_BACKCNT) +#define UI_MENU_COATING_CNT 1 +#define UI_MENU_COATING_COND &ui_menu_prepare, +UI_MENU_SUBMENU_FILTER_T(ui_menu_prepare, UI_TEXT_BED_COATING_ID, ui_menu_adjust,0,MENU_MODE_PRINTING) + +#else +#define UI_MENU_COATING_CNT 0 +#define UI_MENU_COATING_COND +#endif + // **** Fan menu #if FAN_PIN>-1 && FEATURE_FAN_CONTROL -UI_MENU_CHANGEACTION(ui_menu_fan_fanspeed, UI_TEXT_ACTION_FANSPEED,UI_ACTION_FANSPEED) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_fan_off,UI_TEXT_FAN_OFF,UI_ACTION_FAN_OFF,MENU_MODE_FAN_RUNNING,0) -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) -UI_MENU_ACTIONCOMMAND(ui_menu_fan_ignoreM106,UI_TEXT_IGNORE_M106,UI_ACTION_IGNORE_M106) +UI_MENU_CHANGEACTION_T(ui_menu_fan_fanspeed, UI_TEXT_ACTION_FANSPEED_ID,UI_ACTION_FANSPEED) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_fan_off,UI_TEXT_FAN_OFF_ID,UI_ACTION_FAN_OFF,MENU_MODE_FAN_RUNNING,0) +UI_MENU_ACTIONCOMMAND_T(ui_menu_fan_25,UI_TEXT_FAN_25_ID,UI_ACTION_FAN_25) +UI_MENU_ACTIONCOMMAND_T(ui_menu_fan_50,UI_TEXT_FAN_50_ID,UI_ACTION_FAN_50) +UI_MENU_ACTIONCOMMAND_T(ui_menu_fan_75,UI_TEXT_FAN_75_ID,UI_ACTION_FAN_75) +UI_MENU_ACTIONCOMMAND_T(ui_menu_fan_full,UI_TEXT_FAN_FULL_ID,UI_ACTION_FAN_FULL) +UI_MENU_ACTIONCOMMAND_T(ui_menu_fan_ignoreM106,UI_TEXT_IGNORE_M106_ID,UI_ACTION_IGNORE_M106) #define UI_MENU_FAN {UI_MENU_ADDCONDBACK &ui_menu_fan_fanspeed,&ui_menu_fan_off,&ui_menu_fan_25,&ui_menu_fan_50,&ui_menu_fan_75,&ui_menu_fan_full,&ui_menu_fan_ignoreM106} UI_MENU(ui_menu_fan,UI_MENU_FAN,7+UI_MENU_BACKCNT) -UI_MENU_SUBMENU(ui_menu_fan_sub,UI_TEXT_FANSPEED,ui_menu_fan) +UI_MENU_SUBMENU_T(ui_menu_fan_sub,UI_TEXT_FANSPEED_ID,ui_menu_fan) #define UI_MENU_FAN_COND &ui_menu_fan_sub, #define UI_MENU_FAN_CNT 1 #else @@ -548,35 +814,35 @@ UI_MENU_SUBMENU(ui_menu_fan_sub,UI_TEXT_FANSPEED,ui_menu_fan) #if SDSUPPORT -UI_MENU_HEADLINE(ui_menu_sd_askstop_head,UI_TEXT_STOP_PRINT) -UI_MENU_ACTIONCOMMAND(ui_menu_sd_askstop_no,UI_TEXT_NO,UI_ACTION_BACK) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_sd_askstop_yes, UI_TEXT_YES, UI_ACTION_SD_STOP | UI_ACTION_TOPMENU, MENU_MODE_SD_PRINTING, 0) +UI_MENU_HEADLINE_T(ui_menu_sd_askstop_head,UI_TEXT_STOP_PRINT_ID) +UI_MENU_ACTIONCOMMAND_T(ui_menu_sd_askstop_no,UI_TEXT_NO_ID,UI_ACTION_BACK) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_sd_askstop_yes, UI_TEXT_YES_ID, UI_ACTION_SD_STOP | UI_ACTION_TOPMENU, MENU_MODE_SD_PRINTING, 0) #define UI_MENU_SD_ASKSTOP {&ui_menu_sd_askstop_head,&ui_menu_sd_askstop_no,&ui_menu_sd_askstop_yes} UI_MENU(ui_menu_sd_askstop,UI_MENU_SD_ASKSTOP,3) #define UI_MENU_SD_FILESELECTOR {&ui_menu_back} UI_MENU_FILESELECT(ui_menu_sd_fileselector,UI_MENU_SD_FILESELECTOR,1) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_sd_printfile, UI_TEXT_PRINT_FILE, UI_ACTION_SD_PRINT, MENU_MODE_SD_MOUNTED, MENU_MODE_SD_PRINTING) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_sd_pause, UI_TEXT_PAUSE_PRINT, UI_ACTION_SD_PAUSE, MENU_MODE_SD_PRINTING, MENU_MODE_SD_PAUSED) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_sd_continue, UI_TEXT_CONTINUE_PRINT, UI_ACTION_SD_CONTINUE, MENU_MODE_SD_PAUSED, 0) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_sd_printfile, UI_TEXT_PRINT_FILE_ID, UI_ACTION_SD_PRINT, MENU_MODE_SD_MOUNTED, MENU_MODE_SD_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_sd_pause, UI_TEXT_PAUSE_PRINT_ID, UI_ACTION_SD_PAUSE, MENU_MODE_SD_PRINTING, MENU_MODE_SD_PAUSED) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_sd_continue, UI_TEXT_CONTINUE_PRINT_ID, UI_ACTION_SD_CONTINUE, MENU_MODE_SD_PAUSED, 0) // two versions of stop. Second is with security question since pausing can trigger stop with bad luck! -//UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_sd_stop, UI_TEXT_STOP_PRINT, UI_ACTION_SD_STOP, MENU_MODE_SD_PRINTING, 0) -UI_MENU_SUBMENU_FILTER(ui_menu_sd_stop, UI_TEXT_STOP_PRINT,ui_menu_sd_askstop, MENU_MODE_SD_PRINTING, 0 ) +//UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_sd_stop, UI_TEXT_STOP_PRINT_ID, UI_ACTION_SD_STOP, MENU_MODE_SD_PRINTING, 0) +UI_MENU_SUBMENU_FILTER_T(ui_menu_sd_stop, UI_TEXT_STOP_PRINT_ID,ui_menu_sd_askstop, MENU_MODE_SD_PRINTING, 0 ) #define SD_PRINTFILE_ENTRY &ui_menu_sd_printfile, #define SD_PRINTFILE_ENTRY_CNT 1 #if SDCARDDETECT > -1 #define UI_MOUNT_CNT 0 #define UI_MOUNT_CMD #else -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_sd_unmount,UI_TEXT_UNMOUNT_CARD,UI_ACTION_SD_UNMOUNT,MENU_MODE_SD_MOUNTED,0) -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_sd_mount,UI_TEXT_MOUNT_CARD,UI_ACTION_SD_MOUNT,0,MENU_MODE_SD_MOUNTED) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_sd_unmount,UI_TEXT_UNMOUNT_CARD_ID,UI_ACTION_SD_UNMOUNT,MENU_MODE_SD_MOUNTED,0) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_sd_mount,UI_TEXT_MOUNT_CARD_ID,UI_ACTION_SD_MOUNT,0,MENU_MODE_SD_MOUNTED) #define UI_MOUNT_CNT 2 #define UI_MOUNT_CMD ,&ui_menu_sd_unmount,&ui_menu_sd_mount #endif -UI_MENU_ACTIONCOMMAND_FILTER(ui_menu_sd_delete,UI_TEXT_DELETE_FILE,UI_ACTION_SD_DELETE,MENU_MODE_SD_MOUNTED,MENU_MODE_SD_PRINTING) +UI_MENU_ACTIONCOMMAND_FILTER_T(ui_menu_sd_delete,UI_TEXT_DELETE_FILE_ID,UI_ACTION_SD_DELETE,MENU_MODE_SD_MOUNTED,MENU_MODE_SD_PRINTING) #define UI_MENU_SD {UI_MENU_ADDCONDBACK &ui_menu_sd_printfile,&ui_menu_sd_pause,&ui_menu_sd_continue,&ui_menu_sd_stop UI_MOUNT_CMD ,&ui_menu_sd_delete} UI_MENU(ui_menu_sd, UI_MENU_SD, UI_MENU_BACKCNT + 5 + UI_MOUNT_CNT) -UI_MENU_SUBMENU(ui_menu_sd_sub, UI_TEXT_SD_CARD, ui_menu_sd) +UI_MENU_SUBMENU_T(ui_menu_sd_sub, UI_TEXT_SD_CARD_ID, ui_menu_sd) #define UI_MENU_SD_COND &ui_menu_sd_sub, #define UI_MENU_SD_CNT 1 @@ -589,59 +855,59 @@ UI_MENU_SUBMENU(ui_menu_sd_sub, UI_TEXT_SD_CARD, ui_menu_sd) // **** 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) +UI_MENU_ACTIONCOMMAND_T(ui_menu_debug_echo, UI_TEXT_DBG_ECHO_ID, UI_ACTION_DEBUG_ECHO) +UI_MENU_ACTIONCOMMAND_T(ui_menu_debug_info, UI_TEXT_DBG_INFO_ID, UI_ACTION_DEBUG_INFO) +UI_MENU_ACTIONCOMMAND_T(ui_menu_debug_error, UI_TEXT_DBG_ERROR_ID, UI_ACTION_DEBUG_ERROR) +UI_MENU_ACTIONCOMMAND_T(ui_menu_debug_dryrun, UI_TEXT_DBG_DRYRUN_ID, 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) // **** Acceleration settings #if DRIVE_SYSTEM != DELTA -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) +UI_MENU_CHANGEACTION_T(ui_menu_accel_printx, UI_TEXT_PRINT_X_ID,UI_ACTION_PRINT_ACCEL_X) +UI_MENU_CHANGEACTION_T(ui_menu_accel_printy, UI_TEXT_PRINT_Y_ID,UI_ACTION_PRINT_ACCEL_Y) +UI_MENU_CHANGEACTION_T(ui_menu_accel_printz, UI_TEXT_PRINT_Z_ID,UI_ACTION_PRINT_ACCEL_Z) +UI_MENU_CHANGEACTION_T(ui_menu_accel_travelx, UI_TEXT_MOVE_X_ID,UI_ACTION_MOVE_ACCEL_X) +UI_MENU_CHANGEACTION_T(ui_menu_accel_travely, UI_TEXT_MOVE_Y_ID,UI_ACTION_MOVE_ACCEL_Y) +UI_MENU_CHANGEACTION_T(ui_menu_accel_travelz, UI_TEXT_MOVE_Z_ID,UI_ACTION_MOVE_ACCEL_Z) +UI_MENU_CHANGEACTION_T(ui_menu_accel_jerk, UI_TEXT_JERK_ID,UI_ACTION_MAX_JERK) +UI_MENU_CHANGEACTION_T(ui_menu_accel_zjerk, UI_TEXT_ZJERK_ID,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) +UI_MENU_CHANGEACTION_T(ui_menu_feedrate_maxx, UI_TEXT_FEED_MAX_X_ID, UI_ACTION_MAX_FEEDRATE_X) +UI_MENU_CHANGEACTION_T(ui_menu_feedrate_maxy, UI_TEXT_FEED_MAX_Y_ID, UI_ACTION_MAX_FEEDRATE_Y) +UI_MENU_CHANGEACTION_T(ui_menu_feedrate_maxz, UI_TEXT_FEED_MAX_Z_ID, UI_ACTION_MAX_FEEDRATE_Z) +UI_MENU_CHANGEACTION_T(ui_menu_feedrate_homex, UI_TEXT_FEED_HOME_X_ID, UI_ACTION_HOMING_FEEDRATE_X) +UI_MENU_CHANGEACTION_T(ui_menu_feedrate_homey, UI_TEXT_FEED_HOME_Y_ID, UI_ACTION_HOMING_FEEDRATE_Y) +UI_MENU_CHANGEACTION_T(ui_menu_feedrate_homez, UI_TEXT_FEED_HOME_Z_ID, 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_FEEDRATE,6 + UI_MENU_BACKCNT) #else -UI_MENU_CHANGEACTION(ui_menu_accel_printz,UI_TEXT_PRINT_Z_DELTA,UI_ACTION_PRINT_ACCEL_Z) -UI_MENU_CHANGEACTION(ui_menu_accel_travelz,UI_TEXT_MOVE_Z_DELTA,UI_ACTION_MOVE_ACCEL_Z) -UI_MENU_CHANGEACTION(ui_menu_accel_jerk,UI_TEXT_JERK,UI_ACTION_MAX_JERK) +UI_MENU_CHANGEACTION_T(ui_menu_accel_printz,UI_TEXT_PRINT_Z_DELTA_ID,UI_ACTION_PRINT_ACCEL_Z) +UI_MENU_CHANGEACTION_T(ui_menu_accel_travelz,UI_TEXT_MOVE_Z_DELTA_ID,UI_ACTION_MOVE_ACCEL_Z) +UI_MENU_CHANGEACTION_T(ui_menu_accel_jerk,UI_TEXT_JERK_ID,UI_ACTION_MAX_JERK) #define UI_MENU_ACCEL {UI_MENU_ADDCONDBACK &ui_menu_accel_printz,&ui_menu_accel_travelz,&ui_menu_accel_jerk} UI_MENU(ui_menu_accel,UI_MENU_ACCEL,3+UI_MENU_BACKCNT) // **** Feedrates -UI_MENU_CHANGEACTION(ui_menu_feedrate_maxz,UI_TEXT_FEED_MAX_Z_DELTA,UI_ACTION_MAX_FEEDRATE_Z) -UI_MENU_CHANGEACTION(ui_menu_feedrate_homez,UI_TEXT_FEED_HOME_Z_DELTA,UI_ACTION_HOMING_FEEDRATE_Z) +UI_MENU_CHANGEACTION_T(ui_menu_feedrate_maxz,UI_TEXT_FEED_MAX_Z_DELTA_ID,UI_ACTION_MAX_FEEDRATE_Z) +UI_MENU_CHANGEACTION_T(ui_menu_feedrate_homez,UI_TEXT_FEED_HOME_Z_DELTA_ID,UI_ACTION_HOMING_FEEDRATE_Z) #define UI_MENU_FEEDRATE {UI_MENU_ADDCONDBACK &ui_menu_feedrate_maxz,&ui_menu_feedrate_homez} UI_MENU(ui_menu_feedrate,UI_MENU_FEEDRATE,2+UI_MENU_BACKCNT) #endif // **** 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) +UI_MENU_ACTION2_T(ui_menu_stepper2,UI_ACTION_STEPPER_INACTIVE,UI_TEXT_STEPPER_INACTIVE2A_ID,UI_TEXT_STEPPER_INACTIVE2B_ID) +UI_MENU_ACTION2_T(ui_menu_maxinactive2,UI_ACTION_MAX_INACTIVE,UI_TEXT_POWER_INACTIVE2A_ID,UI_TEXT_POWER_INACTIVE2B_ID) +UI_MENU_CHANGEACTION_T(ui_menu_general_baud,UI_TEXT_BAUDRATE_ID,UI_ACTION_BAUDRATE) +UI_MENU_ACTIONSELECTOR_T(ui_menu_general_stepper_inactive,UI_TEXT_STEPPER_INACTIVE_ID,ui_menu_stepper2) +UI_MENU_ACTIONSELECTOR_T(ui_menu_general_max_inactive,UI_TEXT_POWER_INACTIVE_ID,ui_menu_maxinactive2) #if FEATURE_AUTOLEVEL - UI_MENU_ACTIONCOMMAND(ui_menu_toggle_autolevel,UI_TEXT_AUTOLEVEL_ONOFF,UI_ACTION_AUTOLEVEL_ONOFF) + UI_MENU_ACTIONCOMMAND_T(ui_menu_toggle_autolevel,UI_TEXT_AUTOLEVEL_ONOFF_ID,UI_ACTION_AUTOLEVEL_ONOFF) #define UI_TOOGLE_AUTOLEVEL_ENTRY ,&ui_menu_toggle_autolevel #define UI_TOGGLE_AUTOLEVEL_COUNT 1 #else @@ -653,49 +919,68 @@ UI_MENU(ui_menu_general,UI_MENU_GENERAL,3+UI_MENU_BACKCNT+UI_TOGGLE_AUTOLEVEL_CO // **** 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) +UI_MENU_CHANGEACTION_T(ui_menu_cext_steps, UI_TEXT_EXTR_STEPS_ID, UI_ACTION_EXTR_STEPS) +UI_MENU_CHANGEACTION_T(ui_menu_cext_start_feedrate, UI_TEXT_EXTR_START_FEED_ID, UI_ACTION_EXTR_START_FEEDRATE) +UI_MENU_CHANGEACTION_T(ui_menu_cext_max_feedrate, UI_TEXT_EXTR_MAX_FEED_ID, UI_ACTION_EXTR_MAX_FEEDRATE) +UI_MENU_CHANGEACTION_T(ui_menu_cext_acceleration, UI_TEXT_EXTR_ACCEL_ID, UI_ACTION_EXTR_ACCELERATION) +UI_MENU_CHANGEACTION_T(ui_menu_cext_watch_period, UI_TEXT_EXTR_WATCH_ID, UI_ACTION_EXTR_WATCH_PERIOD) +UI_MENU_CHANGEACTION_T(ui_menu_ext_wait_temp, UI_TEXT_EXTR_WAIT_RETRACT_TEMP_ID, UI_ACTION_EXTR_WAIT_RETRACT_TEMP) +UI_MENU_CHANGEACTION_T(ui_menu_ext_wait_units, UI_TEXT_EXTR_WAIT_RETRACT_UNITS_ID, UI_ACTION_EXTR_WAIT_RETRACT_UNITS) #define UI_MENU_ADV_CNT 0 #define UI_MENU_ADVANCE #if USE_ADVANCE +#undef UI_MENU_ADV_CNT #define UI_MENU_ADV_CNT 1 +#undef UI_MENU_ADVANCE #define UI_MENU_ADVANCE ,&ui_menu_cext_advancel #if ENABLE_QUADRATIC_ADVANCE +#undef UI_MENU_ADV_CNT #define UI_MENU_ADV_CNT 2 +#undef UI_MENU_ADVANCE #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) +UI_MENU_CHANGEACTION_T(ui_menu_cext_advancek,UI_TEXT_EXTR_ADVANCE_K_ID,UI_ACTION_ADVANCE_K) #endif -UI_MENU_CHANGEACTION(ui_menu_cext_advancel,UI_TEXT_EXTR_ADVANCE_L,UI_ACTION_ADVANCE_L) +UI_MENU_CHANGEACTION_T(ui_menu_cext_advancel,UI_TEXT_EXTR_ADVANCE_L_ID,UI_ACTION_ADVANCE_L) #endif -UI_MENU_CHANGEACTION( ui_menu_cext_manager, UI_TEXT_EXTR_MANAGER, UI_ACTION_EXTR_HEATMANAGER) -UI_MENU_CHANGEACTION( ui_menu_cext_pmax, UI_TEXT_EXTR_PMAX, UI_ACTION_PID_MAX) +UI_MENU_CHANGEACTION_T( ui_menu_cext_manager, UI_TEXT_EXTR_MANAGER_ID, UI_ACTION_EXTR_HEATMANAGER) +UI_MENU_CHANGEACTION_T( ui_menu_cext_pmax, UI_TEXT_EXTR_PMAX_ID, UI_ACTION_PID_MAX) #if TEMP_PID -UI_MENU_CHANGEACTION_FILTER(ui_menu_cext_pgain, UI_TEXT_EXTR_PGAIN, UI_ACTION_PID_PGAIN, MENU_MODE_FULL_PID, 0) -UI_MENU_CHANGEACTION_FILTER(ui_menu_cext_igain, UI_TEXT_EXTR_IGAIN, UI_ACTION_PID_IGAIN, MENU_MODE_FULL_PID, 0) -UI_MENU_CHANGEACTION_FILTER(ui_menu_cext_dgain, UI_TEXT_EXTR_DGAIN, UI_ACTION_PID_DGAIN, MENU_MODE_FULL_PID, 0) -UI_MENU_CHANGEACTION_FILTER(ui_menu_cext_dmin, UI_TEXT_EXTR_DMIN, UI_ACTION_DRIVE_MIN, MENU_MODE_FULL_PID, 0) -UI_MENU_CHANGEACTION_FILTER(ui_menu_cext_dmax, UI_TEXT_EXTR_DMAX, UI_ACTION_DRIVE_MAX, MENU_MODE_FULL_PID, 0) -UI_MENU_CHANGEACTION_FILTER(ui_menu_cext_pgain_dt, UI_TEXT_EXTR_DEADTIME, UI_ACTION_PID_PGAIN, MENU_MODE_DEADTIME, 0) -UI_MENU_CHANGEACTION_FILTER(ui_menu_cext_dmax_dt, UI_TEXT_EXTR_DMAX_DT, UI_ACTION_DRIVE_MAX, MENU_MODE_DEADTIME, 0) +UI_MENU_CHANGEACTION_FILTER_T(ui_menu_cext_pgain, UI_TEXT_EXTR_PGAIN_ID, UI_ACTION_PID_PGAIN, MENU_MODE_FULL_PID, 0) +UI_MENU_CHANGEACTION_FILTER_T(ui_menu_cext_igain, UI_TEXT_EXTR_IGAIN_ID, UI_ACTION_PID_IGAIN, MENU_MODE_FULL_PID, 0) +UI_MENU_CHANGEACTION_FILTER_T(ui_menu_cext_dgain, UI_TEXT_EXTR_DGAIN_ID, UI_ACTION_PID_DGAIN, MENU_MODE_FULL_PID, 0) +UI_MENU_CHANGEACTION_FILTER_T(ui_menu_cext_dmin, UI_TEXT_EXTR_DMIN_ID, UI_ACTION_DRIVE_MIN, MENU_MODE_FULL_PID, 0) +UI_MENU_CHANGEACTION_FILTER_T(ui_menu_cext_dmax, UI_TEXT_EXTR_DMAX_ID, UI_ACTION_DRIVE_MAX, MENU_MODE_FULL_PID, 0) +UI_MENU_CHANGEACTION_FILTER_T(ui_menu_cext_pgain_dt, UI_TEXT_EXTR_DEADTIME_ID, UI_ACTION_PID_PGAIN, MENU_MODE_DEADTIME, 0) +UI_MENU_CHANGEACTION_FILTER_T(ui_menu_cext_dmax_dt, UI_TEXT_EXTR_DMAX_DT_ID, UI_ACTION_DRIVE_MAX, MENU_MODE_DEADTIME, 0) #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_pgain_dt,&ui_menu_cext_dmax_dt,&ui_menu_cext_pmax #define UI_MENU_PIDCNT 9 #else #define UI_MENU_PIDCOND ,&ui_menu_cext_manager, &ui_menu_cext_pmax #define UI_MENU_PIDCNT 2 #endif -#if NUM_EXTRUDER>2 && MIXING_EXTRUDER == 0 -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) +#if NUM_EXTRUDER > 5 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_cext_xoffset,UI_TEXT_EXTR_XOFF_ID,UI_ACTION_X_OFFSET) +UI_MENU_CHANGEACTION_T(ui_menu_cext_yoffset,UI_TEXT_EXTR_YOFF_ID,UI_ACTION_Y_OFFSET) +#define UI_MENU_CONFEXTCOND &ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_ext_sel2,&ui_menu_ext_sel3,&ui_menu_ext_sel4,&ui_menu_ext_sel5,&ui_menu_cext_xoffset,&ui_menu_cext_yoffset, +#define UI_MENU_CONFEXTCNT 8 +#elif NUM_EXTRUDER > 4 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_cext_xoffset,UI_TEXT_EXTR_XOFF_ID,UI_ACTION_X_OFFSET) +UI_MENU_CHANGEACTION_T(ui_menu_cext_yoffset,UI_TEXT_EXTR_YOFF_ID,UI_ACTION_Y_OFFSET) +#define UI_MENU_CONFEXTCOND &ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_ext_sel2,&ui_menu_ext_sel3,&ui_menu_ext_sel4,&ui_menu_cext_xoffset,&ui_menu_cext_yoffset, +#define UI_MENU_CONFEXTCNT 7 +#elif NUM_EXTRUDER > 3 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_cext_xoffset,UI_TEXT_EXTR_XOFF_ID,UI_ACTION_X_OFFSET) +UI_MENU_CHANGEACTION_T(ui_menu_cext_yoffset,UI_TEXT_EXTR_YOFF_ID,UI_ACTION_Y_OFFSET) +#define UI_MENU_CONFEXTCOND &ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_ext_sel2,&ui_menu_ext_sel3,&ui_menu_cext_xoffset,&ui_menu_cext_yoffset, +#define UI_MENU_CONFEXTCNT 6 +#elif NUM_EXTRUDER > 2 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_cext_xoffset,UI_TEXT_EXTR_XOFF_ID,UI_ACTION_X_OFFSET) +UI_MENU_CHANGEACTION_T(ui_menu_cext_yoffset,UI_TEXT_EXTR_YOFF_ID,UI_ACTION_Y_OFFSET) #define UI_MENU_CONFEXTCOND &ui_menu_ext_sel0,&ui_menu_ext_sel1,&ui_menu_ext_sel2,&ui_menu_cext_xoffset,&ui_menu_cext_yoffset, #define UI_MENU_CONFEXTCNT 5 -#elif NUM_EXTRUDER>1 && MIXING_EXTRUDER == 0 -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) +#elif NUM_EXTRUDER > 1 && MIXING_EXTRUDER == 0 +UI_MENU_CHANGEACTION_T(ui_menu_cext_xoffset,UI_TEXT_EXTR_XOFF_ID,UI_ACTION_X_OFFSET) +UI_MENU_CHANGEACTION_T(ui_menu_cext_yoffset,UI_TEXT_EXTR_YOFF_ID,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 @@ -717,12 +1002,13 @@ UI_MENU(ui_menu_cextr,UI_MENU_CEXTR,7+UI_MENU_BACKCNT+UI_MENU_PIDCNT+UI_MENU_CON #endif // **** 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) + +UI_MENU_SUBMENU_T(ui_menu_conf_general, UI_TEXT_GENERAL_ID, ui_menu_general) +UI_MENU_SUBMENU_T(ui_menu_conf_accel, UI_TEXT_ACCELERATION_ID, ui_menu_accel) +UI_MENU_SUBMENU_T(ui_menu_conf_feed, UI_TEXT_FEEDRATE_ID, ui_menu_feedrate) +UI_MENU_SUBMENU_T(ui_menu_conf_extr, UI_TEXT_EXTRUDER_ID, ui_menu_cextr) #if HAVE_HEATED_BED - UI_MENU_SUBMENU(ui_menu_conf_bed, UI_TEXT_HEATING_BED, ui_menu_bedconf) + UI_MENU_SUBMENU_T(ui_menu_conf_bed, UI_TEXT_HEATING_BED_ID, ui_menu_bedconf) #define UI_MENU_BEDCONF_COND ,&ui_menu_conf_bed #define UI_MENU_BEDCONF_CNT 1 #else @@ -730,20 +1016,20 @@ UI_MENU_SUBMENU(ui_menu_conf_extr, UI_TEXT_EXTRUDER, ui_menu_cextr) #define UI_MENU_BEDCONF_CNT 0 #endif #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) +UI_MENU_ACTIONCOMMAND_T(ui_menu_conf_to_eeprom,UI_TEXT_STORE_TO_EEPROM_ID,UI_ACTION_STORE_EEPROM) +UI_MENU_ACTIONCOMMAND_T(ui_menu_conf_from_eeprom,UI_TEXT_LOAD_EEPROM_ID,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) +UI_MENU_ACTION2_T(ui_menu_eeprom_saved, UI_ACTION_DUMMY, UI_TEXT_EEPROM_STOREDA_ID, UI_TEXT_EEPROM_STOREDB_ID) +UI_MENU_ACTION2_T(ui_menu_eeprom_loaded, UI_ACTION_DUMMY, UI_TEXT_EEPROM_LOADEDA_ID, UI_TEXT_EEPROM_LOADEDB_ID) #else #define UI_MENU_EEPROM_COND #define UI_MENU_EEPROM_CNT 0 #endif -#ifdef SOFTWARE_LEVELING +#if defined(SOFTWARE_LEVELING) && DRIVE_SYSTEM == DELTA #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) +UI_MENU_SUBMENU_T(ui_menu_conf_level, UI_TEXT_LEVEL_ID, ui_menu_level) #else #define UI_MENU_SL_COND #define UI_MENU_SL_CNT 0 @@ -751,21 +1037,21 @@ UI_MENU_SUBMENU(ui_menu_conf_level, UI_TEXT_LEVEL, ui_menu_level) #if Z_HOME_DIR > 0 #define UI_MENU_DELTA_COND ,&ui_menu_conf_delta #define UI_MENU_DELTA_CNT 1 -UI_MENU_SUBMENU(ui_menu_conf_delta, UI_TEXT_ZCALIB, ui_menu_delta) +UI_MENU_SUBMENU_T(ui_menu_conf_delta, UI_TEXT_ZCALIB_ID, 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_conf_accel,&ui_menu_conf_feed,&ui_menu_conf_extr UI_MENU_BEDCONF_COND UI_MENU_EEPROM_COND UI_MENU_DELTA_COND UI_MENU_SL_COND} -UI_MENU(ui_menu_configuration,UI_MENU_CONFIGURATION,UI_MENU_BACKCNT+UI_MENU_EEPROM_CNT+UI_MENU_BEDCONF_CNT+UI_MENU_DELTA_CNT+UI_MENU_SL_CNT+4) +#define UI_MENU_CONFIGURATION {UI_MENU_ADDCONDBACK &ui_menu_conf_general LANGMENU_ENTRY ,&ui_menu_conf_accel,&ui_menu_conf_feed,&ui_menu_conf_extr UI_MENU_BEDCONF_COND UI_MENU_EEPROM_COND UI_MENU_DELTA_COND UI_MENU_SL_COND} +UI_MENU(ui_menu_configuration,UI_MENU_CONFIGURATION,UI_MENU_BACKCNT+LANGMENU_COUNT+UI_MENU_EEPROM_CNT+UI_MENU_BEDCONF_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,SD_PRINTFILE_ENTRY &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+SD_PRINTFILE_ENTRY_CNT) +UI_MENU_SUBMENU_T(ui_menu_main1, UI_TEXT_QUICK_SETTINGS_ID,ui_menu_quick) +UI_MENU_SUBMENU_T(ui_menu_main2, UI_TEXT_POSITION_ID,ui_menu_positions) +UI_MENU_SUBMENU_T(ui_menu_main3, UI_TEXT_EXTRUDER_ID,ui_menu_extruder) +UI_MENU_SUBMENU_T(ui_menu_main4, UI_TEXT_DEBUGGING_ID,ui_menu_debugging) +UI_MENU_SUBMENU_T(ui_menu_main5, UI_TEXT_CONFIGURATION_ID,ui_menu_configuration) +#define UI_MENU_MAIN {UI_MENU_ADDCONDBACK &ui_menu_main1,SD_PRINTFILE_ENTRY &ui_menu_main2,&ui_menu_main3,UI_MENU_FAN_COND UI_MENU_COATING_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+SD_PRINTFILE_ENTRY_CNT+UI_MENU_COATING_CNT) /* Define menus accessible by action commands @@ -788,5 +1074,3 @@ the change of temperature with the next/previous buttons. */ #endif #endif // __UI_MENU_H - -