chiark / gitweb /
Merged Marlin, Marlin non gen6 and Ultimaker changes
authorErik van der Zalm <erik@vdzalm.eu>
Fri, 4 Nov 2011 17:02:56 +0000 (18:02 +0100)
committerErik van der Zalm <erik@vdzalm.eu>
Fri, 4 Nov 2011 17:02:56 +0000 (18:02 +0100)
22 files changed:
Marlin/Configuration.h
Marlin/EEPROM.h [new file with mode: 0644]
Marlin/Makefile
Marlin/Marlin.h
Marlin/Marlin.pde
Marlin/fastio.h
Marlin/lcd.h [new file with mode: 0644]
Marlin/lcd.pde [new file with mode: 0644]
Marlin/pins.h
Marlin/planner.cpp [new file with mode: 0644]
Marlin/planner.h [new file with mode: 0644]
Marlin/speed_lookuptable.h
Marlin/stepper.cpp [new file with mode: 0644]
Marlin/stepper.h [new file with mode: 0644]
Marlin/streaming.h [new file with mode: 0644]
Marlin/temperature.cpp [new file with mode: 0644]
Marlin/temperature.h [new file with mode: 0644]
Marlin/thermistortables.h
Marlin/ultralcd.h [new file with mode: 0644]
Marlin/ultralcd.pde [new file with mode: 0644]
Marlin/wiring.c [deleted file]
Marlin/wiring_serial.c [deleted file]

index 39480939d78041f42a8c263c638d5a6b6099a1a7..2cef365b098453b324e62daaf7a2e066488e3ad7 100644 (file)
@@ -1,39 +1,71 @@
 #ifndef CONFIGURATION_H
 #define CONFIGURATION_H
 
+//#define DEBUG_STEPS
+
 // BASIC SETTINGS: select your board type, thermistor type, axis scaling, and endstop configuration
 
 //// The following define selects which electronics board you have. Please choose the one that matches your setup
-// Gen6 = 5, 
-#define MOTHERBOARD 5 
+// MEGA/RAMPS up to 1.2 = 3,
+// RAMPS 1.3 = 33
+// Gen6 = 5,
+// Sanguinololu 1.2 and above = 62
+// Ultimaker = 7,
+#define MOTHERBOARD 7
+//#define MOTHERBOARD 5
 
 //// Thermistor settings:
 // 1 is 100k thermistor
 // 2 is 200k thermistor
 // 3 is mendel-parts thermistor
 #define THERMISTORHEATER 3
+// Select one of these only to define how the nozzle temp is read.
+//#define HEATER_USES_THERMISTOR
+#define HEATER_USES_AD595
+
+// Select one of these only to define how the bed temp is read.
+//#define BED_USES_THERMISTOR
+//#define BED_USES_AD595
 
+#define HEATER_CHECK_INTERVAL 50
+#define BED_CHECK_INTERVAL 5000
+#define BNUMTEMPS NUMTEMPS
+#define bedtemptable temptable
 
-//// Calibration variables
-// X, Y, Z, E steps per unit - Metric Mendel / Orca with V9 extruder:
-float axis_steps_per_unit[] = {40, 40, 3333.92, 67}; 
-// For E steps per unit = 67 for v9 with direct drive (needs finetuning) for other extruders this needs to be changed 
-// Metric Prusa Mendel with Makergear geared stepper extruder:
-//float axis_steps_per_unit[] = {80,80,3200/1.25,1380}; 
 
 //// Endstop Settings
 #define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
 // The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
-const bool ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops. 
+const bool ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. 
 // For optos H21LOB set to true, for Mendel-Parts newer optos TCST2103 set to false
 
 // This determines the communication speed of the printer
-#define BAUDRATE 250000
+//#define BAUDRATE 250000
+#define BAUDRATE 115200
+//#define BAUDRATE 230400
 
 // Comment out (using // at the start of the line) to disable SD support:
-//#define SDSUPPORT
+
+// #define ULTRA_LCD  //any lcd 
+#define LCD_WIDTH 16
+#define LCD_HEIGHT 2
+
+#define ULTIPANEL
+#ifdef ULTIPANEL
+ //#define NEWPANEL  //enable this if you have a click-encoder panel
+ #define SDSUPPORT
+ #define ULTRA_LCD
+ #define LCD_WIDTH 20
+#define LCD_HEIGHT 4
+#endif
+
+
+//#define SDSUPPORT // Enable SD Card Support in Hardware Console
 
 
+
+const int dropsegments=5; //everything with this number of steps  will be ignored as move
+
 //// ADVANCED SETTINGS - to tweak parameters
 
 #include "thermistortables.h"
@@ -47,14 +79,14 @@ const bool ENDSTOPS_INVERTING = false; // set to true to invert the logic of the
 // Disables axis when it's not being used.
 #define DISABLE_X false
 #define DISABLE_Y false
-#define DISABLE_Z true
+#define DISABLE_Z false
 #define DISABLE_E false
 
 // Inverting axis direction
 #define INVERT_X_DIR true    // for Mendel set to false, for Orca set to true
 #define INVERT_Y_DIR false   // for Mendel set to true, for Orca set to false
 #define INVERT_Z_DIR true    // for Mendel set to false, for Orca set to true
-#define INVERT_E_DIR true   // for direct drive extruder v9 set to true, for geared extruder set to false
+#define INVERT_E_DIR false   // for direct drive extruder v9 set to true, for geared extruder set to false
 
 //// ENDSTOP SETTINGS:
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -63,51 +95,81 @@ const bool ENDSTOPS_INVERTING = false; // set to true to invert the logic of the
 #define Z_HOME_DIR -1
 
 #define min_software_endstops false //If true, axis won't move to coordinates less than zero.
-#define max_software_endstops true  //If true, axis won't move to coordinates greater than the defined lengths below.
-#define X_MAX_LENGTH 200
-#define Y_MAX_LENGTH 200
-#define Z_MAX_LENGTH 100
+#define max_software_endstops false  //If true, axis won't move to coordinates greater than the defined lengths below.
+#define X_MAX_LENGTH 210
+#define Y_MAX_LENGTH 210
+#define Z_MAX_LENGTH 210
 
 //// MOVEMENT SETTINGS
 #define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
-float max_feedrate[] = {60000, 60000, 100, 500000}; // set the max speeds
-float homing_feedrate[] = {2400, 2400, 80, 0};  // set the homing speeds
-bool axis_relative_modes[] = {false, false, false, false};
-
-//// Acceleration settings
-// X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
-float acceleration = 2000;         // Normal acceleration mm/s^2
-float retract_acceleration = 7000; // Normal acceleration mm/s^2
-float max_xy_jerk = 20.0*60;
-float max_z_jerk = 0.4*60;
-long max_acceleration_units_per_sq_second[] = {7000,7000,100,10000}; // X, Y, Z and E max acceleration in mm/s^2 for printing moves or retracts
+//note: on bernhards ultimaker 200 200 12 are working well.
+#define HOMING_FEEDRATE {50*60, 50*60, 12*60, 0}  // set the homing speeds
+//the followint checks if an extrusion is existent in the move. if _not_, the speed of the move is set to the maximum speed. 
+//!!!!!!Use only if you know that your printer works at the maximum declared speeds.
+// works around the skeinforge cool-bug. There all moves are slowed to have a minimum layer time. However slow travel moves= ooze
+#define TRAVELING_AT_MAXSPEED  
+#define AXIS_RELATIVE_MODES {false, false, false, false}
+
+#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step)
+
+// default settings 
+
+#define DEFAULT_AXIS_STEPS_PER_UNIT   {79.87220447,79.87220447,200*8/3,14}                    // default steps per unit for ultimaker 
+#define DEFAULT_MAX_FEEDRATE          {160*60, 160*60, 10*60, 500000}        
+#define DEFAULT_MAX_ACCELERATION      {9000,9000,150,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
+
+#define DEFAULT_ACCELERATION          3000    // X, Y, Z and E max acceleration in mm/s^2 for printing moves 
+#define DEFAULT_RETRACT_ACCELERATION  7000   // X, Y, Z and E max acceleration in mm/s^2 for r retracts
+
+#define DEFAULT_MINIMUMFEEDRATE       10     // minimum feedrate
+#define DEFAULT_MINTRAVELFEEDRATE     10
+
+// minimum time in microseconds that a movement needs to take if the buffer is emptied.   Increase this number if you see blobs while printing high speed & high detail.  It will slowdown on the detailed stuff.
+#define DEFAULT_MINSEGMENTTIME        20000
+#define DEFAULT_XYJERK                30.0*60    
+#define DEFAULT_ZJERK                 10.0*60
+
 
 // The watchdog waits for the watchperiod in milliseconds whenever an M104 or M109 increases the target temperature
+//this enables the watchdog interrupt.
+#define USE_WATCHDOG
+//you cannot reboot on a mega2560 due to a bug in he bootloader. Hence, you have to reset manually, and this is done hereby:
+#define RESET_MANUAL
+
+#define WATCHDOG_TIMEOUT 4
+
+
 // If the temperature has not increased at the end of that period, the target temperature is set to zero. It can be reset with another M104/M109
 //#define WATCHPERIOD 5000 //5 seconds
 
 //// The minimal temperature defines the temperature below which the heater will not be enabled
 #define MINTEMP 5
+#define BED_MINTEMP 5
 
 
 // When temperature exceeds max temp, your heater will be switched off.
 // This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
 // You should use MINTEMP for thermistor short/failure protection.
 #define MAXTEMP 275
-
+#define BED_MAXTEMP 150
 
 /// PID settings:
 // Uncomment the following line to enable PID support.
-//#define PIDTEMP
+//#define SMOOTHING
+//#define SMOOTHFACTOR 5.0
+//float current_raw_average=0;
+
+#define PIDTEMP
 #ifdef PIDTEMP
-//#define PID_DEBUG // Sends debug data to the serial port. 
+//#define PID_DEBUG // Sends debug data to the serial port. 
 //#define PID_OPENLOOP 1 // Puts PID in open loop. M104 sets the output power in %
-#define PID_MAX 156 // limits current to nozzle
-#define PID_INTEGRAL_DRIVE_MAX 156.0
-#define PID_dT 0.16
-double Kp = 20.0;
-double Ki = 1.5*PID_dT;
-double Kd = 80/PID_dT;
+#define PID_MAX 255 // limits current to nozzle
+#define PID_INTEGRAL_DRIVE_MAX 255
+#define PID_dT 0.10 // 100ms sample time
+#define DEFAULT_Kp 20.0
+#define DEFAULT_Ki 1.5*PID_dT
+#define DEFAULT_Kd 80/PID_dT
+#define DEFAULT_Kc 0
 #endif // PIDTEMP
 
 
@@ -121,7 +183,7 @@ double Kd = 80/PID_dT;
 //#define ADVANCE
 
 #ifdef ADVANCE
-#define EXTRUDER_ADVANCE_K 0.02
+#define EXTRUDER_ADVANCE_K .3
 
 #define D_FILAMENT 1.7
 #define STEPS_MM_E 65
@@ -130,4 +192,15 @@ double Kd = 80/PID_dT;
 
 #endif // ADVANCE
 
+#if defined SDSUPPORT
+// The number of linear motions that can be in the plan at any give time.  
+  #define BLOCK_BUFFER_SIZE 16   // SD,LCD,Buttons take more memory, block buffer needs to be smaller
+#else
+  #define BLOCK_BUFFER_SIZE 16 // maximize block buffer
+#endif
+
+#ifdef SIMPLE_LCD
+  #define BLOCK_BUFFER_SIZE 16 // A little less buffer for just a simple LCD
+#endif
+
 #endif
diff --git a/Marlin/EEPROM.h b/Marlin/EEPROM.h
new file mode 100644 (file)
index 0000000..0390d94
--- /dev/null
@@ -0,0 +1,123 @@
+
+#include "planner.h"
+#include "temperature.h"
+
+//======================================================================================
+template <class T> int EEPROM_writeAnything(int &ee, const T& value)
+{
+    const byte* p = (const byte*)(const void*)&value;
+    int i;
+    for (i = 0; i < sizeof(value); i++)
+         EEPROM.write(ee++, *p++);
+    return i;
+}
+//======================================================================================
+template <class T> int EEPROM_readAnything(int &ee, T& value)
+{
+    byte* p = (byte*)(void*)&value;
+    int i;
+    for (i = 0; i < sizeof(value); i++)
+         *p++ = EEPROM.read(ee++);
+    return i;
+}
+//======================================================================================
+
+#define EEPROM_OFFSET 100
+
+#define EEPROM_VERSION "V04"  // IMPORTANT:  Whenever there are changes made to the variables stored in EEPROM
+                              // in the functions below, also increment the version number. This makes sure that
+                              // the default values are used whenever there is a change to the data, to prevent
+                              // wrong data being written to the variables.
+                              // ALSO:  always make sure the variables in the Store and retrieve sections are in the same order.
+void StoreSettings() {
+  char ver[4]= "000";
+  int i=EEPROM_OFFSET;
+  EEPROM_writeAnything(i,ver); // invalidate data first 
+  EEPROM_writeAnything(i,axis_steps_per_unit);  
+  EEPROM_writeAnything(i,max_feedrate);  
+  EEPROM_writeAnything(i,max_acceleration_units_per_sq_second);
+  EEPROM_writeAnything(i,acceleration);
+  EEPROM_writeAnything(i,retract_acceleration);
+  EEPROM_writeAnything(i,minimumfeedrate);
+  EEPROM_writeAnything(i,mintravelfeedrate);
+  EEPROM_writeAnything(i,minsegmenttime);
+  EEPROM_writeAnything(i,max_xy_jerk);
+  EEPROM_writeAnything(i,max_z_jerk);
+  #ifdef PIDTEMP
+  EEPROM_writeAnything(i,Kp);
+  EEPROM_writeAnything(i,Ki);
+  EEPROM_writeAnything(i,Kd);
+#else
+  EEPROM_writeAnything(i,3000);
+  EEPROM_writeAnything(i,0);
+  EEPROM_writeAnything(i,0);
+#endif
+  char ver2[4]=EEPROM_VERSION;
+  i=EEPROM_OFFSET;
+  EEPROM_writeAnything(i,ver2); // validate data
+   ECHOLN("Settings Stored");
+
+}
+
+void RetrieveSettings(bool def=false){  // if def=true, the default values will be used
+  int i=EEPROM_OFFSET;
+  char stored_ver[4];
+  char ver[4]=EEPROM_VERSION;
+  EEPROM_readAnything(i,stored_ver); //read stored version
+//  ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]");
+  if ((!def)&&(strncmp(ver,stored_ver,3)==0)) {   // version number match
+      EEPROM_readAnything(i,axis_steps_per_unit);  
+      EEPROM_readAnything(i,max_feedrate);  
+      EEPROM_readAnything(i,max_acceleration_units_per_sq_second);
+      EEPROM_readAnything(i,acceleration);
+      EEPROM_readAnything(i,retract_acceleration);
+      EEPROM_readAnything(i,minimumfeedrate);
+      EEPROM_readAnything(i,mintravelfeedrate);
+      EEPROM_readAnything(i,minsegmenttime);
+      EEPROM_readAnything(i,max_xy_jerk);
+      EEPROM_readAnything(i,max_z_jerk);
+#ifndef PIDTEMP
+      float Kp,Ki,Kd;
+#endif
+      EEPROM_readAnything(i,Kp);
+      EEPROM_readAnything(i,Ki);
+      EEPROM_readAnything(i,Kd);
+
+      ECHOLN("Stored settings retreived:");
+  }
+  else {
+    float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT;
+    float tmp2[]=DEFAULT_MAX_FEEDRATE;
+    long tmp3[]=DEFAULT_MAX_ACCELERATION;
+    for (int i=0;i<4;i++) {
+      axis_steps_per_unit[i]=tmp1[i];  
+      max_feedrate[i]=tmp2[i];  
+      max_acceleration_units_per_sq_second[i]=tmp3[i];
+    }
+    acceleration=DEFAULT_ACCELERATION;
+    retract_acceleration=DEFAULT_RETRACT_ACCELERATION;
+    minimumfeedrate=DEFAULT_MINIMUMFEEDRATE;
+    minsegmenttime=DEFAULT_MINSEGMENTTIME;       
+    mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
+    max_xy_jerk=DEFAULT_XYJERK;
+    max_z_jerk=DEFAULT_ZJERK;
+    ECHOLN("Using Default settings:");
+  }
+  ECHOLN("Steps per unit:");
+  ECHOLN("   M92 X"   <<_FLOAT(axis_steps_per_unit[0],3) << " Y" <<  _FLOAT(axis_steps_per_unit[1],3) << " Z" << _FLOAT(axis_steps_per_unit[2],3) << " E" << _FLOAT(axis_steps_per_unit[3],3));
+  ECHOLN("Maximum feedrates (mm/s):");
+  ECHOLN("   M203 X"  <<_FLOAT(max_feedrate[0]/60,2)<<" Y" << _FLOAT(max_feedrate[1]/60,2) << " Z" << _FLOAT(max_feedrate[2]/60,2) << " E" << _FLOAT(max_feedrate[3]/60,2));
+  ECHOLN("Maximum Acceleration (mm/s2):");
+  ECHOLN("   M201 X"  <<_FLOAT(max_acceleration_units_per_sq_second[0],0) << " Y" << _FLOAT(max_acceleration_units_per_sq_second[1],0) << " Z" << _FLOAT(max_acceleration_units_per_sq_second[2],0) << " E" << _FLOAT(max_acceleration_units_per_sq_second[3],0));
+  ECHOLN("Acceleration: S=acceleration, T=retract acceleration");
+  ECHOLN("   M204 S"  <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2));
+  ECHOLN("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum xY jerk (mm/s),  Z=maximum Z jerk (mm/s)");
+  ECHOLN("   M205 S"  <<_FLOAT(minimumfeedrate/60,2) << " T" << _FLOAT(mintravelfeedrate/60,2) << " B" << _FLOAT(minsegmenttime,2) << " X" << _FLOAT(max_xy_jerk/60,2) << " Z" << _FLOAT(max_z_jerk/60,2));
+#ifdef PIDTEMP
+  ECHOLN("PID settings:");
+  ECHOLN("   M301 P"  << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));  
+#endif
+  
+}  
+
+
index 06e643d4aa57cdc4c57a61941b4b5eacad6fb9cf..6fafba13b070543b75d90597bbcfdc93cb0dd548 100644 (file)
-# Marlin Arduino Project Makefile
-# 
-# Makefile Based on:
-# Arduino 0011 Makefile
-# Arduino adaptation by mellis, eighthave, oli.keller
 #
-# This has been tested with Arduino 0022.
-# 
-# This makefile allows you to build sketches from the command line
-# without the Arduino environment (or Java).
+# Arduino 0022 Makefile 
+# Uno with DOGS102 Shield
 #
-# Detailed instructions for using the makefile:
+# written by olikraus@gmail.com
 #
-#  1. Modify the line containg "INSTALL_DIR" to point to the directory that
-#     contains the Arduino installation (for example, under Mac OS X, this
-#     might be /Applications/arduino-0012).
+# Features:
+#   - boards.txt is used to derive parameters
+#   - All intermediate files are put into a separate directory (TMPDIRNAME)
+#   - Simple use: Copy Makefile into the same directory of the .pde file
 #
-#  2. Modify the line containing "PORT" to refer to the filename
-#     representing the USB or serial connection to your Arduino board
-#     (e.g. PORT = /dev/tty.USB0).  If the exact name of this file
-#     changes, you can use * as a wildcard (e.g. PORT = /dev/tty.usb*).
+# Limitations:
+#   - requires UNIX environment
+#   - TMPDIRNAME must be subdirectory of the current directory.
 #
-#  3. Set the line containing "MCU" to match your board's processor. 
-#     Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth
-#     or Diecimila have the atmega168.  If you're using a LilyPad Arduino,
-#     change F_CPU to 8000000.
+# Targets
+#      all             build everything
+#      upload  build and upload to arduino
+#      clean   remove all temporary files (includes final hex file)
 #
-#  4. Type "make" and press enter to compile/verify your program.
+# History
+#      001     28 Apr 2010     first  release
+#      002  05 Oct 2010        added 'uno'
 #
-#  5. Type "make upload", reset your Arduino board, and press enter to
-#     upload your program to the Arduino board.
-#
-# $Id$
-
-TARGET = Marlin
-INSTALL_DIR = ../../Desktop/arduino-0018/
-UPLOAD_RATE = 38400
-AVRDUDE_PROGRAMMER = stk500v1
-PORT = /dev/ttyUSB0
-#MCU = atmega2560
-#For "old" Arduino Mega
-#MCU = atmega1280
-#For Sanguinololu
-MCU = atmega644p 
-F_CPU = 16000000
-
-
-############################################################################
-# Below here nothing should be changed...
-
-ARDUINO = $(INSTALL_DIR)/hardware/Sanguino/cores/arduino
-AVR_TOOLS_PATH = $(INSTALL_DIR)/hardware/tools/avr/bin
-SRC =  $(ARDUINO)/pins_arduino.c wiring.c wiring_serial.c \
-$(ARDUINO)/wiring_analog.c $(ARDUINO)/wiring_digital.c \
-$(ARDUINO)/wiring_pulse.c \
-$(ARDUINO)/wiring_shift.c $(ARDUINO)/WInterrupts.c
-CXXSRC = $(ARDUINO)/HardwareSerial.cpp $(ARDUINO)/WMath.cpp \
-$(ARDUINO)/Print.cpp ./SdFile.cpp ./SdVolume.cpp ./Sd2Card.cpp
-FORMAT = ihex
-
-
-# Name of this Makefile (used for "make depend").
-MAKEFILE = Makefile
-
-# Debugging format.
-# Native formats for AVR-GCC's -g are stabs [default], or dwarf-2.
-# AVR (extended) COFF requires stabs, plus an avr-objcopy run.
-DEBUG = stabs
-
-OPT = s
-
-# Place -D or -U options here
-CDEFS = -DF_CPU=$(F_CPU)
-CXXDEFS = -DF_CPU=$(F_CPU)
-
-# Place -I options here
-CINCS = -I$(ARDUINO)
-CXXINCS = -I$(ARDUINO)
-
-# Compiler flag to set the C Standard level.
-# c89   - "ANSI" C
-# gnu89 - c89 plus GCC extensions
-# c99   - ISO C99 standard (not yet fully implemented)
-# gnu99 - c99 plus GCC extensions
-#CSTANDARD = -std=gnu99
-CDEBUG = -g$(DEBUG)
-CWARN = -Wall -Wunused-variable
-CTUNING = -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -w -ffunction-sections -fdata-sections -DARDUINO=22
-#CEXTRA = -Wa,-adhlns=$(<:.c=.lst)
-
-CFLAGS = $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CEXTRA) $(CTUNING)
-CXXFLAGS = $(CDEFS) $(CINCS) -O$(OPT) -Wall $(CEXTRA) $(CTUNING)
-#ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs 
-LDFLAGS = -lm
-
-
-# Programming support using avrdude. Settings and variables.
-AVRDUDE_PORT = $(PORT)
-AVRDUDE_WRITE_FLASH = -U flash:w:applet/$(TARGET).hex:i
-AVRDUDE_FLAGS = -D -C $(INSTALL_DIR)/hardware/tools/avrdude.conf \
--p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) \
--b $(UPLOAD_RATE)
-
-# Program settings
-CC = $(AVR_TOOLS_PATH)/avr-gcc
-CXX = $(AVR_TOOLS_PATH)/avr-g++
-OBJCOPY = $(AVR_TOOLS_PATH)/avr-objcopy
-OBJDUMP = $(AVR_TOOLS_PATH)/avr-objdump
-AR  = $(AVR_TOOLS_PATH)/avr-ar
-SIZE = $(AVR_TOOLS_PATH)/avr-size
-NM = $(AVR_TOOLS_PATH)/avr-nm
-AVRDUDE = $(INSTALL_DIR)/hardware/tools/avrdude
-REMOVE = rm -f
-MV = mv -f
-
-# Define all object files.
-OBJ = $(SRC:.c=.o) $(CXXSRC:.cpp=.o) $(ASRC:.S=.o) 
-
-# Define all listing files.
-LST = $(ASRC:.S=.lst) $(CXXSRC:.cpp=.lst) $(SRC:.c=.lst)
-
-# Combine all necessary flags and optional flags.
-# Add target processor to flags.
-ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS)
-ALL_CXXFLAGS = -mmcu=$(MCU) -I. $(CXXFLAGS)
-ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
-
-
-# Default target.
-all: applet_files_ez build sizeafter
-
-build: elf hex 
-
-applet_files_ez: $(TARGET).pde
-       # Here is the "preprocessing".
-       # It creates a .cpp file based with the same name as the .pde file.
-       # On top of the new .cpp file comes the WProgram.h header.
-       # At the end there is a generic main() function attached.
-       # Then the .cpp file will be compiled. Errors during compile will
-       # refer to this new, automatically generated, file. 
-       # Not the original .pde file you actually edit...
-       test -d applet || mkdir applet
-       echo '#include "WProgram.h"' > applet/$(TARGET).cpp
-       cat $(TARGET).pde >> applet/$(TARGET).cpp
-       cat $(ARDUINO)/main.cpp >> applet/$(TARGET).cpp
-
-elf: applet/$(TARGET).elf
-hex: applet/$(TARGET).hex
-eep: applet/$(TARGET).eep
-lss: applet/$(TARGET).lss 
-sym: applet/$(TARGET).sym
 
-# Program the device.  
-upload: applet/$(TARGET).hex
-       $(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH)
+#=== user configuration ===
+# All ...PATH variables must have a '/' at the end
 
+# Board (and prozessor) information: see $(ARDUINO_PATH)hardware/arduino/boards.txt
+# Some examples:
+#      BOARD           DESCRIPTION
+#      uno                     Arduino Uno
+#      atmega328       Arduino Duemilanove or Nano w/ ATmega328
+#      diecimila               Arduino Diecimila, Duemilanove, or Nano w/ ATmega168
+#      mega            Arduino Mega
+#      mini                    Arduino Mini
+#      lilypad328      LilyPad Arduino w/ ATmega328  
+BOARD:=mega
 
-       # Display size of file.
-HEXSIZE = $(SIZE) --target=$(FORMAT) applet/$(TARGET).hex
-ELFSIZE = $(SIZE)  applet/$(TARGET).elf
-sizebefore:
-       @if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(HEXSIZE); echo; fi
+# additional (comma separated) defines 
+# -DDOGM128_HW         board is connected to DOGM128 display
+# -DDOGM132_HW         board is connected to DOGM132 display
+# -DDOGS102_HW         board is connected to DOGS102 display
+# -DDOG_REVERSE                180 degree rotation
+# -DDOG_SPI_SW_ARDUINO force SW shiftOut
+DEFS=-DDOGS102_HW -DDOG_DOUBLE_MEMORY -DDOG_SPI_SW_ARDUINO
 
-sizeafter:
-       @if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(HEXSIZE); echo; fi
+# The location where the avr tools (e.g. avr-gcc) are located. Requires a '/' at the end.
+# Can be empty if all tools are accessable through the search path
+AVR_TOOLS_PATH:=/usr/bin/
+
+# Install path of the arduino software. Requires a '/' at the end.
+ARDUINO_PATH:=/home/bkubicek/software/arduino-0022/
+
+# Install path for avrdude. Requires a '/' at the end. Can be empty if avrdude is in the search path.
+AVRDUDE_PATH:= 
+
+# The unix device where we can reach the arduino board
+# Uno: /dev/ttyACM0
+# Duemilanove: /dev/ttyUSB0
+AVRDUDE_PORT:=/dev/ttyACM0
+
+# List of all libaries which should be included.
+#EXTRA_DIRS=$(ARDUINO_PATH)libraries/LiquidCrystal/
+#EXTRA_DIRS+=$(ARDUINO_PATH)libraries/Dogm/
+#EXTRA_DIRS+=/home/kraus/src/arduino/dogm128/hg/libraries/Dogm/
+
+#=== fetch parameter from boards.txt processor parameter ===
+# the basic idea is to get most of the information from boards.txt
 
+BOARDS_TXT:=$(ARDUINO_PATH)hardware/arduino/boards.txt
+
+# get the MCU value from the $(BOARD).build.mcu variable. For the atmega328 board this is atmega328p
+MCU:=$(shell sed -n -e "s/$(BOARD).build.mcu=\(.*\)/\1/p" $(BOARDS_TXT))
+# get the F_CPU value from the $(BOARD).build.f_cpu variable. For the atmega328 board this is 16000000
+F_CPU:=$(shell sed -n -e "s/$(BOARD).build.f_cpu=\(.*\)/\1/p" $(BOARDS_TXT))
 
-# Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
-COFFCONVERT=$(OBJCOPY) --debugging \
---change-section-address .data-0x800000 \
---change-section-address .bss-0x800000 \
---change-section-address .noinit-0x800000 \
---change-section-address .eeprom-0x810000 
+# avrdude
+# get the AVRDUDE_UPLOAD_RATE value from the $(BOARD).upload.speed variable. For the atmega328 board this is 57600
+AVRDUDE_UPLOAD_RATE:=$(shell sed -n -e "s/$(BOARD).upload.speed=\(.*\)/\1/p" $(BOARDS_TXT))
+# get the AVRDUDE_PROGRAMMER value from the $(BOARD).upload.protocol variable. For the atmega328 board this is stk500
+# AVRDUDE_PROGRAMMER:=$(shell sed -n -e "s/$(BOARD).upload.protocol=\(.*\)/\1/p" $(BOARDS_TXT))
+# use stk500v1, because stk500 will default to stk500v2
+AVRDUDE_PROGRAMMER:=stk500v1
 
+#=== identify user files ===
+PDESRC:=$(shell ls *.pde)
+TARGETNAME=$(basename $(PDESRC))
 
-coff: applet/$(TARGET).elf
-       $(COFFCONVERT) -O coff-avr applet/$(TARGET).elf $(TARGET).cof
+CDIRS:=$(EXTRA_DIRS) $(addsuffix utility/,$(EXTRA_DIRS))
+CDIRS:=*.c utility/*.c $(addsuffix *.c,$(CDIRS)) $(ARDUINO_PATH)hardware/arduino/cores/arduino/*.c
+CSRC:=$(shell ls $(CDIRS) 2>/dev/null)
 
+CCSRC:=$(shell ls *.cc 2>/dev/null)
 
-extcoff: $(TARGET).elf
-       $(COFFCONVERT) -O coff-ext-avr applet/$(TARGET).elf $(TARGET).cof
+CPPDIRS:=$(EXTRA_DIRS) $(addsuffix utility/,$(EXTRA_DIRS))
+CPPDIRS:=*.cpp utility/*.cpp $(addsuffix *.cpp,$(CPPDIRS)) $(ARDUINO_PATH)hardware/arduino/cores/arduino/*.cpp 
+CPPSRC:=$(shell ls $(CPPDIRS) 2>/dev/null)
 
+#=== build internal variables ===
 
-.SUFFIXES: .elf .hex .eep .lss .sym
+# the name of the subdirectory where everything is stored
+TMPDIRNAME:=tmp
+TMPDIRPATH:=$(TMPDIRNAME)/
+
+AVRTOOLSPATH:=$(AVR_TOOLS_PATH)
+
+OBJCOPY:=$(AVRTOOLSPATH)avr-objcopy
+OBJDUMP:=$(AVRTOOLSPATH)avr-objdump
+SIZE:=$(AVRTOOLSPATH)avr-size
+
+CPPSRC:=$(addprefix $(TMPDIRPATH),$(PDESRC:.pde=.cpp)) $(CPPSRC)
+
+COBJ:=$(CSRC:.c=.o)
+CCOBJ:=$(CCSRC:.cc=.o)
+CPPOBJ:=$(CPPSRC:.cpp=.o)
+
+OBJFILES:=$(COBJ)  $(CCOBJ)  $(CPPOBJ)
+DIRS:= $(dir $(OBJFILES))
+
+DEPFILES:=$(OBJFILES:.o=.d)
+# assembler files from avr-gcc -S
+ASSFILES:=$(OBJFILES:.o=.s)
+# disassembled object files with avr-objdump -S
+DISFILES:=$(OBJFILES:.o=.dis)
 
-.elf.hex:
-       $(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
 
-.elf.eep:
-       -$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
-       --change-section-lma .eeprom=0 -O $(FORMAT) $< $@
+LIBNAME:=$(TMPDIRPATH)$(TARGETNAME).a
+ELFNAME:=$(TMPDIRPATH)$(TARGETNAME).elf
+HEXNAME:=$(TMPDIRPATH)$(TARGETNAME).hex
 
-# Create extended listing file from ELF output file.
-.elf.lss:
-       $(OBJDUMP) -h -S $< > $@
+AVRDUDE_FLAGS = -V -F
+AVRDUDE_FLAGS += -C $(ARDUINO_PATH)/hardware/tools/avrdude.conf 
+AVRDUDE_FLAGS += -p $(MCU)
+AVRDUDE_FLAGS += -P $(AVRDUDE_PORT)
+AVRDUDE_FLAGS += -c $(AVRDUDE_PROGRAMMER) 
+AVRDUDE_FLAGS += -b $(AVRDUDE_UPLOAD_RATE)
+AVRDUDE_FLAGS += -U flash:w:$(HEXNAME)
 
-# Create a symbol table from ELF output file.
-.elf.sym:
-       $(NM) -n $< > $@
+AVRDUDE = avrdude
 
-       # Link: create ELF output file from library.
-applet/$(TARGET).elf: $(TARGET).pde applet/core.a 
-       $(CC) $(ALL_CFLAGS) -Wl,--gc-sections -o $@ applet/$(TARGET).cpp -L. applet/core.a $(LDFLAGS)
+#=== predefined variable override ===
+# use "make -p -f/dev/null" to see the default rules and definitions
 
-applet/core.a: $(OBJ)
-       @for i in $(OBJ); do echo $(AR) rcs applet/core.a $$i; $(AR) rcs applet/core.a $$i; done
+# Build C and C++ flags. Include path information must be placed here
+COMMON_FLAGS = -DF_CPU=$(F_CPU) -mmcu=$(MCU) $(DEFS)
+# COMMON_FLAGS += -gdwarf-2
+COMMON_FLAGS += -Os
+COMMON_FLAGS += -Wall -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
+COMMON_FLAGS += -I. 
+COMMON_FLAGS += -I$(ARDUINO_PATH)hardware/arduino/cores/arduino
+COMMON_FLAGS += $(addprefix -I,$(EXTRA_DIRS))
+COMMON_FLAGS += -ffunction-sections -fdata-sections -Wl,--gc-sections
+COMMON_FLAGS += -Wl,--relax
+COMMON_FLAGS += -mcall-prologues
 
+CFLAGS = $(COMMON_FLAGS) -std=gnu99 -Wstrict-prototypes  
+CXXFLAGS = $(COMMON_FLAGS) 
 
+# Replace standard build tools by avr tools
+CC = $(AVRTOOLSPATH)avr-gcc
+CXX = $(AVRTOOLSPATH)avr-g++
+AR  = @$(AVRTOOLSPATH)avr-ar
 
-# Compile: create object files from C++ source files.
-.cpp.o:
-       $(CXX) -c $(ALL_CXXFLAGS) $< -o $@ 
 
-# Compile: create object files from C source files.
-.c.o:
-       $(CC) -c $(ALL_CFLAGS) $< -o $@ 
+# "rm" must be able to delete a directory tree
+RM = rm -rf 
 
+#=== rules ===
 
-# Compile: create assembler files from C source files.
-.c.s:
-       $(CC) -S $(ALL_CFLAGS) $< -o $@
+# add rules for the C/C++ files where the .o file is placed in the TMPDIRPATH
+# reuse existing variables as far as possible
 
+$(TMPDIRPATH)%.o: %.c
+       @echo compile $<
+       @$(COMPILE.c) $(OUTPUT_OPTION) $<
+
+$(TMPDIRPATH)%.o: %.cc
+       @echo compile $< 
+       @$(COMPILE.cc) $(OUTPUT_OPTION) $<
+
+$(TMPDIRPATH)%.o: %.cpp
+       @echo compile $<
+       @$(COMPILE.cpp) $(OUTPUT_OPTION) $<
+
+$(TMPDIRPATH)%.s: %.c
+       @$(COMPILE.c) $(OUTPUT_OPTION) -S $<
+
+$(TMPDIRPATH)%.s: %.cc
+       @$(COMPILE.cc) $(OUTPUT_OPTION) -S $<
+
+$(TMPDIRPATH)%.s: %.cpp
+       @$(COMPILE.cpp) $(OUTPUT_OPTION) -S $<
+
+$(TMPDIRPATH)%.dis: $(TMPDIRPATH)%.o
+       @$(OBJDUMP) -S $< > $@
+
+.SUFFIXES: .elf .hex .pde
+
+.elf.hex:
+       @$(OBJCOPY) -O ihex -R .eeprom $< $@
+       
+$(TMPDIRPATH)%.cpp: %.pde
+       @cat $(ARDUINO_PATH)hardware/arduino/cores/arduino/main.cpp > $@
+       @cat $< >> $@
+       @echo >> $@
+       @echo 'extern "C" void __cxa_pure_virtual() { while (1); }' >> $@
 
-# Assemble: create object files from assembler source files.
-.S.o:
-       $(CC) -c $(ALL_ASFLAGS) $< -o $@
 
+.PHONY: all
+all: tmpdir $(HEXNAME) assemblersource showsize
+       ls -al $(HEXNAME) $(ELFNAME)
 
+$(ELFNAME): $(LIBNAME)($(addprefix $(TMPDIRPATH),$(OBJFILES))) 
+       $(LINK.o) $(COMMON_FLAGS) $(LIBNAME) $(LOADLIBES) $(LDLIBS) -o $@
 
-# Target: clean project.
+$(LIBNAME)(): $(addprefix $(TMPDIRPATH),$(OBJFILES))
+
+#=== create temp directory ===
+# not really required, because it will be also created during the dependency handling
+.PHONY: tmpdir
+tmpdir:
+       @test -d $(TMPDIRPATH) || mkdir $(TMPDIRPATH)
+
+#=== create assembler files for each C/C++ file ===
+.PHONY: assemblersource
+assemblersource: $(addprefix $(TMPDIRPATH),$(ASSFILES)) $(addprefix $(TMPDIRPATH),$(DISFILES))
+
+
+#=== show the section sizes of the ELF file ===
+.PHONY: showsize
+showsize: $(ELFNAME)
+       $(SIZE) $<
+
+#=== clean up target ===
+# this is simple: the TMPDIRPATH is removed
+.PHONY: clean
 clean:
-       $(REMOVE) applet/$(TARGET).hex applet/$(TARGET).eep applet/$(TARGET).cof applet/$(TARGET).elf \
-       applet/$(TARGET).map applet/$(TARGET).sym applet/$(TARGET).lss applet/core.a \
-       $(OBJ) $(LST) $(SRC:.c=.s) $(SRC:.c=.d) $(CXXSRC:.cpp=.s) $(CXXSRC:.cpp=.d)
-
-depend:
-       if grep '^# DO NOT DELETE' $(MAKEFILE) >/dev/null; \
-       then \
-               sed -e '/^# DO NOT DELETE/,$$d' $(MAKEFILE) > \
-                       $(MAKEFILE).$$$$ && \
-               $(MV) $(MAKEFILE).$$$$ $(MAKEFILE); \
-       fi
-       echo '# DO NOT DELETE THIS LINE -- make depend depends on it.' \
-               >> $(MAKEFILE); \
-       $(CC) -M -mmcu=$(MCU) $(CDEFS) $(CINCS) $(SRC) $(ASRC) >> $(MAKEFILE)
-
-.PHONY:        all build elf hex eep lss sym program coff extcoff clean depend applet_files sizebefore sizeafter
+       $(RM) $(TMPDIRPATH)
+
+# Program the device.  
+# step 1: reset the arduino board with the stty command
+# step 2: user avrdude to upload the software
+.PHONY: upload
+upload: $(HEXNAME)
+       stty -F $(AVRDUDE_PORT) hupcl
+       $(AVRDUDE) $(AVRDUDE_FLAGS)
+
+
+# === dependency handling ===
+# From the gnu make manual (section 4.14, Generating Prerequisites Automatically)
+# Additionally (because this will be the first executed rule) TMPDIRPATH is created here.
+# Instead of "sed" the "echo" command is used
+# cd $(TMPDIRPATH); mkdir -p $(DIRS) 2> /dev/null; cd ..
+DEPACTION=test -d $(TMPDIRPATH) || mkdir $(TMPDIRPATH);\
+mkdir -p $(addprefix $(TMPDIRPATH),$(DIRS));\
+set -e; echo -n $@ $(dir $@) > $@; $(CC) -MM $(COMMON_FLAGS) $< >> $@
+
+
+$(TMPDIRPATH)%.d: %.c
+       @$(DEPACTION)
+
+$(TMPDIRPATH)%.d: %.cc
+       @$(DEPACTION)
+
+
+$(TMPDIRPATH)%.d: %.cpp
+       @$(DEPACTION)
+
+# Include dependency files. If a .d file is missing, a warning is created and the .d file is created
+# This warning is not a problem (gnu make manual, section 3.3 Including Other Makefiles)
+-include $(addprefix $(TMPDIRPATH),$(DEPFILES))
+
+
index 56d716542d1b0620837e6cf7beea967da591f37f..cc43f00b2d61b083978079bb390977c58d26d5ef 100644 (file)
@@ -1,27 +1,20 @@
+#ifndef __MARLINH
+#define __MARLINH
+
 // Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
 // Licence: GPL
 #include <WProgram.h>
 #include "fastio.h"
-extern "C" void __cxa_pure_virtual();
-void __cxa_pure_virtual(){};
+
+
+#define ECHO(x) Serial << "echo: " << x;
+#define ECHOLN(x) Serial << "echo: "<<x<<endl;
+
 void get_command();
 void process_commands();
 
 void manage_inactivity(byte debug);
 
-void manage_heater();
-int temp2analogu(int celsius, const short table[][2], int numtemps);
-float analog2tempu(int raw, const short table[][2], int numtemps);
-#ifdef HEATER_USES_THERMISTOR
-    #define HEATERSOURCE 1
-#endif
-#ifdef BED_USES_THERMISTOR
-    #define BEDSOURCE 1
-#endif
-
-#define temp2analogh( c ) temp2analogu((c),temptable,NUMTEMPS)
-#define analog2temp( c ) analog2tempu((c),temptable,NUMTEMPS)
-
 #if X_ENABLE_PIN > -1
 #define  enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
 #define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
@@ -43,9 +36,12 @@ float analog2tempu(int raw, const short table[][2], int numtemps);
 #define enable_z() ;
 #define disable_z() ;
 #endif
+
 #if E_ENABLE_PIN > -1
-#define  enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
-#define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
+
+       #define  enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
+       #define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
+
 #else
 #define enable_e() ;
 #define disable_e() ;
@@ -61,47 +57,27 @@ void ClearToSend();
 
 void get_coordinates();
 void prepare_move();
-void linear_move(unsigned long steps_remaining[]);
-void do_step(int axis);
 void kill(byte debug);
 
-// This struct is used when buffering the setup for each linear movement "nominal" values are as specified in 
-// the source g-code and may never actually be reached if acceleration management is active.
-typedef struct {
-  // Fields used by the bresenham algorithm for tracing the line
-  long steps_x, steps_y, steps_z, steps_e;  // Step count along each axis
-  long step_event_count;                    // The number of step events required to complete this block
-  volatile long accelerate_until;                    // The index of the step event on which to stop acceleration
-  volatile long decelerate_after;                    // The index of the step event on which to start decelerating
-  volatile long acceleration_rate;                   // The acceleration rate used for acceleration calculation
-  unsigned char direction_bits;             // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
-
-  long advance_rate;
-  volatile long initial_advance;
-  volatile long final_advance;
-  float advance;
-
-  // Fields used by the motion planner to manage acceleration
-  float speed_x, speed_y, speed_z, speed_e;          // Nominal mm/minute for each axis
-  float nominal_speed;                               // The nominal speed for this block in mm/min  
-  float millimeters;                                 // The total travel of this block in mm
-  float entry_speed;
-  float acceleration;                                // acceleration mm/sec^2
-
-  // Settings for the trapezoid generator
-  long nominal_rate;                                 // The nominal step rate for this block in step_events/sec 
-  volatile long initial_rate;                        // The jerk-adjusted step rate at start of block  
-  volatile long final_rate;                          // The minimal rate at exit
-  long acceleration_st;                              // acceleration steps/sec^2
-  volatile char busy;
-} block_t;
-
-void check_axes_activity();
-void plan_init();
-void st_init();
-void tp_init();
-void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
-void plan_set_position(float x, float y, float z, float e);
-void st_wake_up();
-void st_synchronize();
+//void check_axes_activity();
+//void plan_init();
+//void st_init();
+//void tp_init();
+//void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
+//void plan_set_position(float x, float y, float z, float e);
+//void st_wake_up();
+//void st_synchronize();
+void enquecommand(const char *cmd);
+void wd_reset();
+
+#ifndef CRITICAL_SECTION_START
+#define CRITICAL_SECTION_START  unsigned char _sreg = SREG; cli();
+#define CRITICAL_SECTION_END    SREG = _sreg;
+#endif //CRITICAL_SECTION_START
 
+extern float homing_feedrate[];
+extern bool axis_relative_modes[];
+
+void manage_inactivity(byte debug);
+
+#endif
index c1ece44cbc82131ecf659dd9fc3134812165ef03..6922b8a1fe5fbd2e9cc7e13b99bbbc5dc385b956 100644 (file)
  
  It has preliminary support for Matthew Roberts advance algorithm 
     http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
-
- This firmware is optimized for gen6 electronics.
  */
 
+#include <EEPROM.h>
 #include "fastio.h"
 #include "Configuration.h"
 #include "pins.h"
 #include "Marlin.h"
-#include "speed_lookuptable.h"
+#include "ultralcd.h"
+#include "streaming.h"
+#include "planner.h"
+#include "stepper.h"
+#include "temperature.h"
+
+#ifdef SIMPLE_LCD
+  #include "Simplelcd.h"
+#endif
 
-char version_string[] = "0.9.10";
+char version_string[] = "1.0.0 Alpha 1";
 
 #ifdef SDSUPPORT
 #include "SdFat.h"
 #endif //SDSUPPORT
 
-#ifndef CRITICAL_SECTION_START
-#define CRITICAL_SECTION_START  unsigned char _sreg = SREG; cli()
-#define CRITICAL_SECTION_END    SREG = _sreg
-#endif //CRITICAL_SECTION_START
 
 // look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
 // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
@@ -87,9 +90,17 @@ char version_string[] = "0.9.10";
 // M115        - Capabilities string
 // M140 - Set bed target temp
 // M190 - Wait for bed current temp to reach target temp.
+// M200 - Set filament diameter
 // M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
-// M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000)
+// M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
+// M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
+// M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2  also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
+// M205 -  advanced settings:  minimum travel speed S=while printing T=travel only,  B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
+// M220 - set speed factor override percentage S:factor in percent
 // M301 - Set PID parameters P I and D
+// M500 - stores paramters in EEPROM
+// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).  D
+// M502 - reverts to the default "factory settings".  You still need to store them in EEPROM afterwards if you want to.
 
 //Stepper Movement Variables
 
@@ -100,15 +111,23 @@ float destination[NUM_AXIS] = {
 float current_position[NUM_AXIS] = {
   0.0, 0.0, 0.0, 0.0};
 bool home_all_axis = true;
-long feedrate = 1500, next_feedrate, saved_feedrate;
+float feedrate = 1500.0, next_feedrate, saved_feedrate;
 long gcode_N, gcode_LastN;
+
+float homing_feedrate[] = HOMING_FEEDRATE;
+bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
+
 bool relative_mode = false;  //Determines Absolute or Relative Coordinates
 bool relative_mode_e = false;  //Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode.
-unsigned long axis_steps_per_sqr_second[NUM_AXIS];
 
+uint8_t fanpwm=0;
+
+volatile int feedmultiply=100; //100->1 200->2
+int saved_feedmultiply;
+volatile bool feedmultiplychanged=false;
 // comm variables
 #define MAX_CMD_SIZE 96
-#define BUFSIZE 8
+#define BUFSIZE 4
 char cmdbuffer[BUFSIZE][MAX_CMD_SIZE];
 bool fromsd[BUFSIZE];
 int bufindr = 0;
@@ -119,45 +138,23 @@ char serial_char;
 int serial_count = 0;
 boolean comment_mode = false;
 char *strchr_pointer; // just a pointer to find chars in the cmd string like X, Y, Z, E, etc
+extern float HeaterPower;
 
-// Manage heater variables.
-
-int target_raw = 0;
-int current_raw = 0;
-unsigned char temp_meas_ready = false;
-
-#ifdef PIDTEMP
-  double temp_iState = 0;
-  double temp_dState = 0;
-  double pTerm;
-  double iTerm;
-  double dTerm;
-      //int output;
-  double pid_error;
-  double temp_iState_min;
-  double temp_iState_max;
-  double pid_setpoint = 0.0;
-  double pid_input;
-  double pid_output;
-  bool pid_reset;
-#endif //PIDTEMP
+#include "EEPROM.h"
 
+float tt = 0, bt = 0;
 #ifdef WATCHPERIOD
 int watch_raw = -1000;
 unsigned long watchmillis = 0;
 #endif //WATCHPERIOD
-#ifdef MINTEMP
-int minttemp = temp2analogh(MINTEMP);
-#endif //MINTEMP
-#ifdef MAXTEMP
-int maxttemp = temp2analogh(MAXTEMP);
-#endif //MAXTEMP
 
 //Inactivity shutdown variables
 unsigned long previous_millis_cmd = 0;
 unsigned long max_inactive_time = 0;
 unsigned long stepper_inactive_time = 0;
 
+unsigned long starttime=0;
+unsigned long stoptime=0;
 #ifdef SDSUPPORT
 Sd2Card card;
 SdVolume volume;
@@ -169,6 +166,7 @@ bool sdmode = false;
 bool sdactive = false;
 bool savetosd = false;
 int16_t n;
+long autostart_atmillis=0;
 
 void initsd(){
   sdactive = false;
@@ -184,10 +182,18 @@ void initsd(){
   else if (!root.openRoot(&volume)) 
     Serial.println("openRoot failed");
   else 
+       {
     sdactive = true;
+               Serial.println("SD card ok");
+       }
 #endif //SDSS
 }
 
+void quickinitsd(){
+       sdactive=false;
+       autostart_atmillis=millis()+5000;
+}
+
 inline void write_command(char *buf){
   char* begin = buf;
   char* npos = 0;
@@ -210,147 +216,131 @@ inline void write_command(char *buf){
 #endif //SDSUPPORT
 
 
+///adds an command to the main command buffer
+void enquecommand(const char *cmd)
+{
+  if(buflen < BUFSIZE)
+  {
+    //this is dangerous if a mixing of serial and this happsens
+    strcpy(&(cmdbuffer[bufindw][0]),cmd);
+    Serial.print("en:");Serial.println(cmdbuffer[bufindw]);
+    bufindw= (bufindw + 1)%BUFSIZE;
+    buflen += 1;
+  }
+}
+
 void setup()
 { 
+       
   Serial.begin(BAUDRATE);
-  Serial.print("Marlin ");
-  Serial.println(version_string);
+  ECHOLN("Marlin "<<version_string);
   Serial.println("start");
-
+#if defined FANCY_LCD || defined SIMPLE_LCD
+  lcd_init();
+#endif
   for(int i = 0; i < BUFSIZE; i++){
     fromsd[i] = false;
   }
+  
+  RetrieveSettings(); // loads data from EEPROM if available
 
-  //Initialize Dir Pins
-#if X_DIR_PIN > -1
-  SET_OUTPUT(X_DIR_PIN);
-#endif
-#if Y_DIR_PIN > -1 
-  SET_OUTPUT(Y_DIR_PIN);
-#endif
-#if Z_DIR_PIN > -1 
-  SET_OUTPUT(Z_DIR_PIN);
-#endif
-#if E_DIR_PIN > -1 
-  SET_OUTPUT(E_DIR_PIN);
-#endif
-
-  //Initialize Enable Pins - steppers default to disabled.
-
-#if (X_ENABLE_PIN > -1)
-  SET_OUTPUT(X_ENABLE_PIN);
-  if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
-#endif
-#if (Y_ENABLE_PIN > -1)
-  SET_OUTPUT(Y_ENABLE_PIN);
-  if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
-#endif
-#if (Z_ENABLE_PIN > -1)
-  SET_OUTPUT(Z_ENABLE_PIN);
-  if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
-#endif
-#if (E_ENABLE_PIN > -1)
-  SET_OUTPUT(E_ENABLE_PIN);
-  if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH);
-#endif
 
-  //endstops and pullups
-#ifdef ENDSTOPPULLUPS
-#if X_MIN_PIN > -1
-  SET_INPUT(X_MIN_PIN); 
-  WRITE(X_MIN_PIN,HIGH);
-#endif
-#if X_MAX_PIN > -1
-  SET_INPUT(X_MAX_PIN); 
-  WRITE(X_MAX_PIN,HIGH);
-#endif
-#if Y_MIN_PIN > -1
-  SET_INPUT(Y_MIN_PIN); 
-  WRITE(Y_MIN_PIN,HIGH);
-#endif
-#if Y_MAX_PIN > -1
-  SET_INPUT(Y_MAX_PIN); 
-  WRITE(Y_MAX_PIN,HIGH);
-#endif
-#if Z_MIN_PIN > -1
-  SET_INPUT(Z_MIN_PIN); 
-  WRITE(Z_MIN_PIN,HIGH);
-#endif
-#if Z_MAX_PIN > -1
-  SET_INPUT(Z_MAX_PIN); 
-  WRITE(Z_MAX_PIN,HIGH);
-#endif
-#else //ENDSTOPPULLUPS
-#if X_MIN_PIN > -1
-  SET_INPUT(X_MIN_PIN); 
-#endif
-#if X_MAX_PIN > -1
-  SET_INPUT(X_MAX_PIN); 
-#endif
-#if Y_MIN_PIN > -1
-  SET_INPUT(Y_MIN_PIN); 
-#endif
-#if Y_MAX_PIN > -1
-  SET_INPUT(Y_MAX_PIN); 
-#endif
-#if Z_MIN_PIN > -1
-  SET_INPUT(Z_MIN_PIN); 
-#endif
-#if Z_MAX_PIN > -1
-  SET_INPUT(Z_MAX_PIN); 
-#endif
-#endif //ENDSTOPPULLUPS
-
-#if (HEATER_0_PIN > -1) 
-  SET_OUTPUT(HEATER_0_PIN);
-#endif  
-#if (HEATER_1_PIN > -1) 
-  SET_OUTPUT(HEATER_1_PIN);
-#endif  
-
-  //Initialize Step Pins
-#if (X_STEP_PIN > -1) 
-  SET_OUTPUT(X_STEP_PIN);
-#endif  
-#if (Y_STEP_PIN > -1) 
-  SET_OUTPUT(Y_STEP_PIN);
-#endif  
-#if (Z_STEP_PIN > -1) 
-  SET_OUTPUT(Z_STEP_PIN);
-#endif  
-#if (E_STEP_PIN > -1) 
-  SET_OUTPUT(E_STEP_PIN);
-#endif  
   for(int i=0; i < NUM_AXIS; i++){
     axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i];
   }
 
-#ifdef PIDTEMP
-  temp_iState_min = 0.0;
-  temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
-#endif //PIDTEMP
-
 #ifdef SDSUPPORT
   //power to SD reader
 #if SDPOWER > -1
   SET_OUTPUT(SDPOWER); 
   WRITE(SDPOWER,HIGH);
 #endif //SDPOWER
-  initsd();
+  quickinitsd();
 
 #endif //SDSUPPORT
   plan_init();  // Initialize planner;
   st_init();    // Initialize stepper;
   tp_init();    // Initialize temperature loop
+       //checkautostart();
 }
 
+#ifdef SDSUPPORT
+bool autostart_stilltocheck=true;
+
+
+void checkautostart(bool force)
+{
+       //this is to delay autostart and hence the initialisaiton of the sd card to some seconds after the normal init, so the device is available quick after a reset
+       if(!force)
+       {
+               if(!autostart_stilltocheck)
+                       return;
+               if(autostart_atmillis<millis())
+                       return;
+       }
+       autostart_stilltocheck=false;
+       if(!sdactive)
+       {
+               initsd();
+               if(!sdactive) //fail
+               return;
+       }
+       static int lastnr=0;
+       char autoname[30];
+       sprintf(autoname,"auto%i.g",lastnr);
+       for(int i=0;i<strlen(autoname);i++)
+               autoname[i]=tolower(autoname[i]);
+       dir_t p;
+
+       root.rewind();
+       char filename[11];
+       int cnt=0;
+
+       bool found=false;
+       while (root.readDir(p) > 0) 
+       {
+               for(int i=0;i<strlen((char*)p.name);i++)
+                       p.name[i]=tolower(p.name[i]);
+               //Serial.print((char*)p.name);
+               //Serial.print(" ");
+               //Serial.println(autoname);
+               if(p.name[9]!='~') //skip safety copies
+               if(strncmp((char*)p.name,autoname,5)==0)
+               {
+                       char cmd[30];
+                       
+                       sprintf(cmd,"M23 %s",autoname);
+                       //sprintf(cmd,"M115");
+                       //enquecommand("G92 Z0");
+                       //enquecommand("G1 Z10 F2000");
+                       //enquecommand("G28 X-105 Y-105");
+                       enquecommand(cmd);
+                       enquecommand("M24");
+                       found=true;
+                       
+               }
+       }
+       if(!found)
+               lastnr=-1;
+       else
+               lastnr++;
+       
+}
+#else
+
+inline void checkautostart(bool x)
+{
+}
+#endif
+
 
 void loop()
 {
   if(buflen<3)
     get_command();
-
-  if(buflen){
+       checkautostart(false);
+  if(buflen)
+  {
 #ifdef SDSUPPORT
     if(savetosd){
       if(strstr(cmdbuffer[bufindr],"M29") == NULL){
@@ -376,6 +366,7 @@ void loop()
   //check heater every n milliseconds
   manage_heater();
   manage_inactivity(1);
+  LCD_STATUS;
 }
 
 
@@ -482,6 +473,16 @@ inline void get_command()
       if(sdpos >= filesize){
         sdmode = false;
         Serial.println("Done printing file");
+                               stoptime=millis();
+                               char time[30];
+                               unsigned long t=(stoptime-starttime)/1000;
+                               int sec,min;
+                               min=t/60;
+                               sec=t%60;
+                               sprintf(time,"%i min, %i sec",min,sec);
+                               Serial.println(time);
+                               LCD_MESSAGE(time);
+                               checkautostart(true);
       }
       if(!serial_count) return; //if empty line
       cmdbuffer[bufindw][serial_count] = 0; //terminate string
@@ -548,38 +549,41 @@ inline void process_commands()
       break;
     case 28: //G28 Home all Axis one at a time
       saved_feedrate = feedrate;
+      saved_feedmultiply = feedmultiply;
+      feedmultiply = 100;
+      
       for(int i=0; i < NUM_AXIS; i++) {
         destination[i] = current_position[i];
       }
-      feedrate = 0;
+      feedrate = 0.0;
 
       home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
 
       if((home_all_axis) || (code_seen(axis_codes[X_AXIS]))) {
         if ((X_MIN_PIN > -1 && X_HOME_DIR==-1) || (X_MAX_PIN > -1 && X_HOME_DIR==1)){
-          st_synchronize();
+//          st_synchronize();
           current_position[X_AXIS] = 0;
           plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
           destination[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;
           feedrate = homing_feedrate[X_AXIS];
           prepare_move();
-
-          st_synchronize();        
+          
+//          st_synchronize();        
           current_position[X_AXIS] = 0;
           plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
           destination[X_AXIS] = -5 * X_HOME_DIR;
           prepare_move();
-
-          st_synchronize();         
+          
+//          st_synchronize();         
           destination[X_AXIS] = 10 * X_HOME_DIR;
           feedrate = homing_feedrate[X_AXIS]/2 ;
           prepare_move();
-          st_synchronize();
-
+          
+//          st_synchronize();
           current_position[X_AXIS] = (X_HOME_DIR == -1) ? 0 : X_MAX_LENGTH;
           plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
           destination[X_AXIS] = current_position[X_AXIS];
-          feedrate = 0;
+          feedrate = 0.0;
         }
       }
 
@@ -590,23 +594,23 @@ inline void process_commands()
           destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR;
           feedrate = homing_feedrate[Y_AXIS];
           prepare_move();
-          st_synchronize();
+//          st_synchronize();
 
           current_position[Y_AXIS] = 0;
           plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
           destination[Y_AXIS] = -5 * Y_HOME_DIR;
           prepare_move();
-          st_synchronize();
+//          st_synchronize();
 
           destination[Y_AXIS] = 10 * Y_HOME_DIR;
           feedrate = homing_feedrate[Y_AXIS]/2;
           prepare_move();
-          st_synchronize();
+//          st_synchronize();
 
           current_position[Y_AXIS] = (Y_HOME_DIR == -1) ? 0 : Y_MAX_LENGTH;
           plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
           destination[Y_AXIS] = current_position[Y_AXIS];
-          feedrate = 0;
+          feedrate = 0.0;
         }
       }
 
@@ -617,26 +621,27 @@ inline void process_commands()
           destination[Z_AXIS] = 1.5 * Z_MAX_LENGTH * Z_HOME_DIR;
           feedrate = homing_feedrate[Z_AXIS];
           prepare_move();
-          st_synchronize();
+//          st_synchronize();
 
           current_position[Z_AXIS] = 0;
           plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
           destination[Z_AXIS] = -2 * Z_HOME_DIR;
           prepare_move();
-          st_synchronize();
+//          st_synchronize();
 
           destination[Z_AXIS] = 3 * Z_HOME_DIR;
           feedrate = homing_feedrate[Z_AXIS]/2;
           prepare_move();
-          st_synchronize();
+//          st_synchronize();
 
           current_position[Z_AXIS] = (Z_HOME_DIR == -1) ? 0 : Z_MAX_LENGTH;
           plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
           destination[Z_AXIS] = current_position[Z_AXIS];
-          feedrate = 0;         
+          feedrate = 0.0;         
         }
       }       
       feedrate = saved_feedrate;
+      feedmultiply = saved_feedmultiply;
       previous_millis_cmd = millis();
       break;
     case 90: // G90
@@ -653,7 +658,6 @@ inline void process_commands()
       }
       plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
       break;
-
     }
   }
 
@@ -701,6 +705,7 @@ inline void process_commands()
     case 24: //M24 - Start SD print
       if(sdactive){
         sdmode = true;
+                               starttime=millis();
       }
       break;
     case 25: //M25 - Pause SD print
@@ -753,70 +758,141 @@ inline void process_commands()
       //processed in write to file routine above
       //savetosd = false;
       break;
+               case 30:
+               {
+                       stoptime=millis();
+                               char time[30];
+                               unsigned long t=(stoptime-starttime)/1000;
+                               int sec,min;
+                               min=t/60;
+                               sec=t%60;
+                               sprintf(time,"%i min, %i sec",min,sec);
+                               Serial.println(time);
+                               LCD_MESSAGE(time);
+               }
+                               break;
 #endif //SDSUPPORT
-    case 104: // M104
-#ifdef PID_OPENLOOP
-      if (code_seen('S')) PidTemp_Output = code_value() * (PID_MAX/100.0);
-      if(pid_output > PID_MAX) pid_output = PID_MAX;
-      if(pid_output < 0) pid_output = 0;
-#else //PID_OPENLOOP
-      if (code_seen('S')) {
-        target_raw = temp2analogh(code_value());
+      case 104: // M104
+                if (code_seen('S')) target_raw[0] = temp2analog(code_value());
 #ifdef PIDTEMP
-        pid_setpoint = code_value();
-#endif //PIDTEMP
-      }
-#ifdef WATCHPERIOD
-      if(target_raw > current_raw){
-        watchmillis = max(1,millis());
-        watch_raw = current_raw;
-      }
-      else{
-        watchmillis = 0;
-      }
-#endif //WATCHPERIOD
-#endif //PID_OPENLOOP
-      break;
-    case 105: // M105
-      Serial.print("ok T:");
-      Serial.println(analog2temp(current_raw)); 
-      return;
-      //break;
-    case 109: // M109 - Wait for extruder heater to reach target.
-      if (code_seen('S')) {
-        target_raw = temp2analogh(code_value());
+                pid_setpoint = code_value();
+#endif //PIDTEM
+        #ifdef WATCHPERIOD
+            if(target_raw[0] > current_raw[0]){
+                watchmillis = max(1,millis());
+                watch_raw[0] = current_raw[0];
+            }else{
+                watchmillis = 0;
+            }
+        #endif
+        break;
+      case 140: // M140 set bed temp
+                if (code_seen('S')) target_raw[1] = temp2analogBed(code_value());
+        break;
+      case 105: // M105
+        #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
+                tt = analog2temp(current_raw[0]);
+        #endif
+        #if TEMP_1_PIN > -1
+                bt = analog2tempBed(current_raw[1]);
+        #endif
+        #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
+            Serial.print("ok T:");
+            Serial.print(tt); 
+//            Serial.print(", raw:");
+//            Serial.print(current_raw);       
+          #if TEMP_1_PIN > -1 
 #ifdef PIDTEMP
-        pid_setpoint = code_value();
-#endif //PIDTEMP
-      }
-#ifdef WATCHPERIOD
-      if(target_raw>current_raw){
-        watchmillis = max(1,millis());
-        watch_raw = current_raw;
-      }
-      else{
-        watchmillis = 0;
-      }
-#endif //WATCHERPERIOD
-      codenum = millis(); 
-      while(current_raw < target_raw) {
-        if( (millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
-        {
-          Serial.print("T:");
-          Serial.println( analog2temp(current_raw)); 
+            Serial.print(" B:");
+            #if TEMP_1_PIN > -1
+            Serial.println(bt); 
+            #else
+            Serial.println(HeaterPower); 
+            #endif
+#else
+            Serial.println();
+#endif
+          #else
+            Serial.println();
+          #endif
+        #else
+          Serial.println("No thermistors - no temp");
+        #endif
+        return;
+        //break;
+      case 109: // M109 - Wait for extruder heater to reach target.
+        LCD_MESSAGE("Heating...");
+               if (code_seen('S')) target_raw[0] = temp2analog(code_value());
+#ifdef PIDTEMP
+               pid_setpoint = code_value();
+#endif //PIDTEM
+        #ifdef WATCHPERIOD
+          if(target_raw[0]>current_raw[0]){
+              watchmillis = max(1,millis());
+              watch_raw[0] = current_raw[0];
+          }else{
+              watchmillis = 0;
+          }
+        #endif
           codenum = millis(); 
+          starttime=millis();
+          while(current_raw[0] < target_raw[0]) {
+            if( (millis() - codenum) > 1000 ) { //Print Temp Reading every 1 second while heating up.
+              Serial.print("T:");
+              Serial.println( analog2temp(current_raw[0]) ); 
+              codenum = millis();
+            }
+            LCD_STATUS;
+            manage_heater();
+          }
+          LCD_MESSAGE("UltiMarlin ready.");
+          break;
+      case 190: // M190 - Wait bed for heater to reach target.
+      #if TEMP_1_PIN > -1
+          if (code_seen('S')) target_raw[1] = temp2analog(code_value());
+        codenum = millis(); 
+          while(current_raw[1] < target_raw[1]) 
+                                {
+          if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
+          {
+            float tt=analog2temp(current_raw[0]);
+            Serial.print("T:");
+            Serial.println( tt );
+            Serial.print("ok T:");
+            Serial.print( tt ); 
+            Serial.print(" B:");
+            Serial.println( analog2temp(current_raw[1]) ); 
+            codenum = millis(); 
+          }
+            manage_heater();
         }
-        manage_heater();
-      }
-      break;
-    case 190:
+      #endif
       break;
+#if FAN_PIN > -1
+      case 106: //M106 Fan On
+        if (code_seen('S')){
+            WRITE(FAN_PIN,HIGH);
+            fanpwm=constrain(code_value(),0,255);
+            analogWrite(FAN_PIN,  fanpwm);
+        }
+        else {
+          WRITE(FAN_PIN,HIGH);
+          fanpwm=255;
+          analogWrite(FAN_PIN, fanpwm);                        
+        }
+        break;
+      case 107: //M107 Fan Off
+        WRITE(FAN_PIN,LOW);
+        analogWrite(FAN_PIN, 0);
+        break;
+#endif
     case 82:
       axis_relative_modes[3] = false;
       break;
     case 83:
       axis_relative_modes[3] = true;
       break;
+               case 18:
     case 84:
       if(code_seen('S')){ 
         stepper_inactive_time = code_value() * 1000; 
@@ -849,8 +925,17 @@ inline void process_commands()
       Serial.print(current_position[Y_AXIS]);
       Serial.print("Z:");
       Serial.print(current_position[Z_AXIS]);
-      Serial.print("E:");
-      Serial.println(current_position[E_AXIS]);
+      Serial.print("E:");      
+      Serial.print(current_position[E_AXIS]);
+      #ifdef DEBUG_STEPS
+        Serial.print(" Count X:");
+        Serial.print(float(count_position[X_AXIS])/axis_steps_per_unit[X_AXIS]);
+        Serial.print("Y:");
+        Serial.print(float(count_position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]);
+        Serial.print("Z:");
+        Serial.println(float(count_position[Z_AXIS])/axis_steps_per_unit[Z_AXIS]);
+      #endif
+      Serial.println("");
       break;
     case 119: // M119
 #if (X_MIN_PIN > -1)
@@ -892,18 +977,67 @@ inline void process_commands()
       }
       break;
 #endif
+    case 203: // M203 max feedrate mm/sec
+      for(int i=0; i < NUM_AXIS; i++) {
+        if(code_seen(axis_codes[i])) max_feedrate[i] = code_value()*60 ;
+      }
+      break;
+    case 204: // M204 acclereration S normal moves T filmanent only moves
+      {
+        if(code_seen('S')) acceleration = code_value() ;
+        if(code_seen('T')) retract_acceleration = code_value() ;
+      }
+      break;
+      case 205: //M205 advanced settings:  minimum travel speed S=while printing T=travel only,  B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
+      {
+        if(code_seen('S')) minimumfeedrate = code_value()*60 ;
+        if(code_seen('T')) mintravelfeedrate = code_value()*60 ;
+        if(code_seen('B')) minsegmenttime = code_value() ;
+        if(code_seen('X')) max_xy_jerk = code_value()*60 ;
+        if(code_seen('Z')) max_z_jerk = code_value()*60 ;
+      }
+      break;
+      case 220: // M220 S<factor in percent>- set speed factor override percentage
+      {
+        if(code_seen('S')) 
+        {
+          feedmultiply = code_value() ;
+          feedmultiplychanged=true;
+        }
+      }
+      break;
 #ifdef PIDTEMP
     case 301: // M301
       if(code_seen('P')) Kp = code_value();
       if(code_seen('I')) Ki = code_value()*PID_dT;
       if(code_seen('D')) Kd = code_value()/PID_dT;
-      Serial.print("Kp ");Serial.println(Kp);
-      Serial.print("Ki ");Serial.println(Ki/PID_dT);
-      Serial.print("Kd ");Serial.println(Kd*PID_dT);
-      temp_iState_min = 0.0;
-      temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
+//      ECHOLN("Kp "<<_FLOAT(Kp,2));
+//      ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2));
+//      ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2));
+
+//      temp_iState_min = 0.0;
+//      if (Ki!=0) {
+//      temp_iState_max = PID_INTEGRAL_DRIVE_MAX / (Ki/100.0);
+//      }
+//      else       temp_iState_max = 1.0e10;
       break;
 #endif //PIDTEMP
+      case 500: // Store settings in EEPROM
+      {
+          StoreSettings();
+      }
+      break;
+      case 501: // Read settings from EEPROM
+      {
+        RetrieveSettings();
+      }
+      break;
+      case 502: // Revert to default settings
+      {
+        RetrieveSettings(true);
+      }
+      break;
+
     }
   }
   else{
@@ -947,141 +1081,89 @@ inline void get_coordinates()
 
 void prepare_move()
 {
-  if (min_software_endstops) {
-    if (destination[X_AXIS] < 0) destination[X_AXIS] = 0.0;
-    if (destination[Y_AXIS] < 0) destination[Y_AXIS] = 0.0;
-    if (destination[Z_AXIS] < 0) destination[Z_AXIS] = 0.0;
-  }
-
-  if (max_software_endstops) {
-    if (destination[X_AXIS] > X_MAX_LENGTH) destination[X_AXIS] = X_MAX_LENGTH;
-    if (destination[Y_AXIS] > Y_MAX_LENGTH) destination[Y_AXIS] = Y_MAX_LENGTH;
-    if (destination[Z_AXIS] > Z_MAX_LENGTH) destination[Z_AXIS] = Z_MAX_LENGTH;
-  }
-
-  plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60.0);
+  plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60.0/100.0);
   for(int i=0; i < NUM_AXIS; i++) {
     current_position[i] = destination[i];
   }
 }
 
-void manage_heater()
-{
-  float pid_input;
-  float pid_output;
-  if(temp_meas_ready != true)
-    return;
-
-CRITICAL_SECTION_START;
-  temp_meas_ready = false;
-CRITICAL_SECTION_END;
 
-#ifdef PIDTEMP
-  pid_input = analog2temp(current_raw);
 
-#ifndef PID_OPENLOOP
-  pid_error = pid_setpoint - pid_input;
-  if(pid_error > 10){
-    pid_output = PID_MAX;
-    pid_reset = true;
-  }
-  else if(pid_error < -10) {
-    pid_output = 0;
-    pid_reset = true;
-  }
-  else {
-    if(pid_reset == true) {
-      temp_iState = 0.0;
-      pid_reset = false;
-    }
-    pTerm = Kp * pid_error;
-    temp_iState += pid_error;
-    temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max);
-    iTerm = Ki * temp_iState;
-    #define K1 0.8
-    #define K2 (1.0-K1)
-    dTerm = (Kd * (pid_input - temp_dState))*K2 + (K1 * dTerm);
-    temp_dState = pid_input;
-    pid_output = constrain(pTerm + iTerm - dTerm, 0, PID_MAX);
-  }
-#endif //PID_OPENLOOP
-#ifdef PID_DEBUG
-   Serial.print(" Input ");
-   Serial.print(pid_input);
-   Serial.print(" Output ");
-   Serial.print(pid_output);    
-   Serial.print(" pTerm ");
-   Serial.print(pTerm); 
-   Serial.print(" iTerm ");
-   Serial.print(iTerm); 
-   Serial.print(" dTerm ");
-   Serial.print(dTerm); 
-   Serial.println();
-#endif //PID_DEBUG
-  OCR2B = pid_output;
-#endif //PIDTEMP
-}
+#ifdef USE_WATCHDOG
 
+#include  <avr/wdt.h>
+#include  <avr/interrupt.h>
 
-int temp2analogu(int celsius, const short table[][2], int numtemps) {
-  int raw = 0;
-  byte i;
+volatile uint8_t timeout_seconds=0;
 
-  for (i=1; i<numtemps; i++) {
-    if (table[i][1] < celsius) {
-      raw = table[i-1][0] + 
-           (celsius - table[i-1][1]) * 
-           (table[i][0] - table[i-1][0]) /
-           (table[i][1] - table[i-1][1]);
+void(* ctrlaltdelete) (void) = 0;
 
-    break;
-    }
+ISR(WDT_vect) { //Watchdog timer interrupt, called if main program blocks >1sec
+  if(timeout_seconds++ >= WATCHDOG_TIMEOUT)
+  {
+   kill();
+#ifdef RESET_MANUAL
+    LCD_MESSAGE("Please Reset!");
+    ECHOLN("echo_: Something is wrong, please turn off the printer.");
+#else
+    LCD_MESSAGE("Timeout, resetting!");
+#endif 
+    //disable watchdog, it will survife reboot.
+    WDTCSR |= (1<<WDCE) | (1<<WDE);
+    WDTCSR = 0;
+#ifdef RESET_MANUAL
+    while(1); //wait for user or serial reset
+#else
+    ctrlaltdelete();
+#endif
   }
-  // Overflow: Set to last value in the table
-  if (i == numtemps) raw = table[i-1][0];
-
-  return 16383 - raw;
 }
 
-float analog2tempu(int raw,const short table[][2], int numtemps) {
-  float celsius = 0.0;
-  byte i;
-
-  raw = 16383 - raw;
-  for (i=1; i<numtemps; i++) {
-    if (table[i][0] > raw) {
-       celsius  = (float)table[i-1][1] + 
-                  (float)(raw - table[i-1][0]) * 
-                  (float)(table[i][1] - table[i-1][1]) /
-                 (float)(table[i][0] - table[i-1][0]);
-
-      break;
-    }
-  }
-  // Overflow: Set to last value in the table
-  if (i == numtemps) celsius = table[i-1][1];
+/// intialise watch dog with a 1 sec interrupt time
+void wd_init() {
+  WDTCSR = (1<<WDCE )|(1<<WDE ); //allow changes
+  WDTCSR = (1<<WDIF)|(1<<WDIE)| (1<<WDCE )|(1<<WDE )|  (1<<WDP2 )|(1<<WDP1)|(0<<WDP0);
+}
 
-  return celsius;
+/// reset watchdog. MUST be called every 1s after init or avr will reset.
+void wd_reset() {
+  wdt_reset();
+  timeout_seconds=0; //reset counter for resets
 }
+#endif /* USE_WATCHDOG */
 
 
 inline void kill()
 {
-  target_raw=0;
-#ifdef PIDTEMP
-  pid_setpoint = 0.0;
-#endif //PIDTEMP
-  OCR2B = 0;
-  WRITE(HEATER_0_PIN,LOW);
-
+  #if TEMP_0_PIN > -1
+  target_raw[0]=0;
+   #if HEATER_0_PIN > -1  
+     WRITE(HEATER_0_PIN,LOW);
+   #endif
+  #endif
+  #if TEMP_1_PIN > -1
+  target_raw[1]=0;
+  #if HEATER_1_PIN > -1 
+    WRITE(HEATER_1_PIN,LOW);
+  #endif
+  #endif
+  #if TEMP_2_PIN > -1
+  target_raw[2]=0;
+  #if HEATER_2_PIN > -1  
+    WRITE(HEATER_2_PIN,LOW);
+  #endif
+  #endif
   disable_x();
   disable_y();
   disable_z();
   disable_e();
-
+  
+  if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
+  Serial.println("!! Printer halted. kill() called!!");
+  while(1); // Wait for reset
 }
 
-inline void manage_inactivity(byte debug) { 
+void manage_inactivity(byte debug) { 
   if( (millis()-previous_millis_cmd) >  max_inactive_time ) if(max_inactive_time) kill(); 
   if( (millis()-previous_millis_cmd) >  stepper_inactive_time ) if(stepper_inactive_time) { 
     disable_x(); 
@@ -1091,965 +1173,3 @@ inline void manage_inactivity(byte debug) {
   }
   check_axes_activity();
 }
-
-// Planner
-
-/*  
- Reasoning behind the mathematics in this module (in the key of 'Mathematica'):
- s == speed, a == acceleration, t == time, d == distance
- Basic definitions:
- Speed[s_, a_, t_] := s + (a*t) 
- Travel[s_, a_, t_] := Integrate[Speed[s, a, t], t]
- Distance to reach a specific speed with a constant acceleration:
- Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t]
- d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance()
- Speed after a given distance of travel with constant acceleration:
- Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t]
- m -> Sqrt[2 a d + s^2]    
- DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2]
- When to start braking (di) to reach a specified destionation speed (s2) after accelerating
- from initial speed s1 without ever stopping at a plateau:
- Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di]
- di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance()
- IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a)
- */
-
-
-// The number of linear motions that can be in the plan at any give time
-#define BLOCK_BUFFER_SIZE 16
-#define BLOCK_BUFFER_MASK 0x0f
-
-static block_t block_buffer[BLOCK_BUFFER_SIZE];            // A ring buffer for motion instructions
-static volatile unsigned char block_buffer_head;           // Index of the next block to be pushed
-static volatile unsigned char block_buffer_tail;           // Index of the block to process now
-
-// The current position of the tool in absolute steps
-static long position[4];   
-
-#define ONE_MINUTE_OF_MICROSECONDS 60000000.0
-
-// Calculates the distance (not time) it takes to accelerate from initial_rate to target_rate using the 
-// given acceleration:
-inline long estimate_acceleration_distance(long initial_rate, long target_rate, long acceleration) {
-  return(
-  (target_rate*target_rate-initial_rate*initial_rate)/
-    (2L*acceleration)
-    );
-}
-
-// This function gives you the point at which you must start braking (at the rate of -acceleration) if 
-// you started at speed initial_rate and accelerated until this point and want to end at the final_rate after
-// a total travel of distance. This can be used to compute the intersection point between acceleration and
-// deceleration in the cases where the trapezoid has no plateau (i.e. never reaches maximum speed)
-
-inline long intersection_distance(long initial_rate, long final_rate, long acceleration, long distance) {
-  return(
-  (2*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/
-    (4*acceleration)
-    );
-}
-
-// Calculates trapezoid parameters so that the entry- and exit-speed is compensated by the provided factors.
-
-void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit_speed) {
-  if(block->busy == true) return; // If block is busy then bail out.
-  float entry_factor = entry_speed / block->nominal_speed;
-  float exit_factor = exit_speed / block->nominal_speed;
-  long initial_rate = ceil(block->nominal_rate*entry_factor);
-  long final_rate = ceil(block->nominal_rate*exit_factor);
-  
-#ifdef ADVANCE
-  long initial_advance = block->advance*entry_factor*entry_factor;
-  long final_advance = block->advance*exit_factor*exit_factor;
-#endif // ADVANCE
-
-  // Limit minimal step rate (Otherwise the timer will overflow.)
-  if(initial_rate <120) initial_rate=120;
-  if(final_rate < 120) final_rate=120;
-  
-  // Calculate the acceleration steps
-  long acceleration = block->acceleration_st;
-  long accelerate_steps = estimate_acceleration_distance(initial_rate, block->nominal_rate, acceleration);
-  long decelerate_steps = estimate_acceleration_distance(final_rate, block->nominal_rate, acceleration);
-  // Calculate the size of Plateau of Nominal Rate. 
-  long plateau_steps = block->step_event_count-accelerate_steps-decelerate_steps;
-
-  // Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will
-  // have to use intersection_distance() to calculate when to abort acceleration and start braking 
-  // in order to reach the final_rate exactly at the end of this block.
-  if (plateau_steps < 0) {  
-    accelerate_steps = intersection_distance(initial_rate, final_rate, acceleration, block->step_event_count);
-    plateau_steps = 0;
-  }  
-
-  long decelerate_after = accelerate_steps+plateau_steps;
-  long acceleration_rate = (long)((float)acceleration * 8.388608);
-
-  CRITICAL_SECTION_START;  // Fill variables used by the stepper in a critical section
-  if(block->busy == false) { // Don't update variables if block is busy.
-    block->accelerate_until = accelerate_steps;
-    block->decelerate_after = decelerate_after;
-    block->acceleration_rate = acceleration_rate;
-    block->initial_rate = initial_rate;
-    block->final_rate = final_rate;
-#ifdef ADVANCE
-    block->initial_advance = initial_advance;
-    block->final_advance = final_advance;
-#endif ADVANCE
-  }
-  CRITICAL_SECTION_END;
-}                    
-
-// Calculates the maximum allowable speed at this point when you must be able to reach target_velocity using the 
-// acceleration within the allotted distance.
-inline float max_allowable_speed(float acceleration, float target_velocity, float distance) {
-  return(
-  sqrt(target_velocity*target_velocity-2*acceleration*60*60*distance)
-    );
-}
-
-// "Junction jerk" in this context is the immediate change in speed at the junction of two blocks.
-// This method will calculate the junction jerk as the euclidean distance between the nominal 
-// velocities of the respective blocks.
-inline float junction_jerk(block_t *before, block_t *after) {
-  return(sqrt(
-    pow((before->speed_x-after->speed_x), 2)+
-    pow((before->speed_y-after->speed_y), 2)));
-}
-
-// Return the safe speed which is max_jerk/2, e.g. the 
-// speed under which you cannot exceed max_jerk no matter what you do.
-float safe_speed(block_t *block) {
-  float safe_speed;
-  safe_speed = max_xy_jerk/2;  
-  if(abs(block->speed_z) > max_z_jerk/2) safe_speed = max_z_jerk/2;
-  if (safe_speed > block->nominal_speed) safe_speed = block->nominal_speed;
-  return safe_speed;  
-}
-
-// The kernel called by planner_recalculate() when scanning the plan from last to first entry.
-void planner_reverse_pass_kernel(block_t *previous, block_t *current, block_t *next) {
-  if(!current) { 
-    return; 
-  }
-
-  float entry_speed = current->nominal_speed;
-  float exit_factor;
-  float exit_speed;
-  if (next) {
-    exit_speed = next->entry_speed;
-  } 
-  else {
-    exit_speed = safe_speed(current);
-  }
-
-  // Calculate the entry_factor for the current block. 
-  if (previous) {
-    // Reduce speed so that junction_jerk is within the maximum allowed
-    float jerk = junction_jerk(previous, current);
-    if((previous->steps_x == 0) && (previous->steps_y == 0)) {
-      entry_speed = safe_speed(current);
-    }
-    else if (jerk > max_xy_jerk) {
-      entry_speed = (max_xy_jerk/jerk) * entry_speed;
-    } 
-    if(abs(previous->speed_z - current->speed_z) > max_z_jerk) {
-      entry_speed = (max_z_jerk/abs(previous->speed_z - current->speed_z)) * entry_speed;
-    }
-    // If the required deceleration across the block is too rapid, reduce the entry_factor accordingly.
-    if (entry_speed > exit_speed) {
-      float max_entry_speed = max_allowable_speed(-current->acceleration,exit_speed, current->millimeters);
-      if (max_entry_speed < entry_speed) {
-        entry_speed = max_entry_speed;
-      }
-    }    
-  } 
-  else {
-    entry_speed = safe_speed(current);
-  }
-  // Store result
-  current->entry_speed = entry_speed;
-}
-
-// planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This 
-// implements the reverse pass.
-void planner_reverse_pass() {
-  char block_index = block_buffer_head;
-  block_index--;
-  block_t *block[3] = { NULL, NULL, NULL };
-  while(block_index != block_buffer_tail) {  
-    block_index--;
-    if(block_index < 0) block_index = BLOCK_BUFFER_SIZE-1;  
-    block[2]= block[1];
-    block[1]= block[0];
-    block[0] = &block_buffer[block_index];
-    planner_reverse_pass_kernel(block[0], block[1], block[2]);
-  }
-  planner_reverse_pass_kernel(NULL, block[0], block[1]);
-}
-
-// The kernel called by planner_recalculate() when scanning the plan from first to last entry.
-void planner_forward_pass_kernel(block_t *previous, block_t *current, block_t *next) {
-  if(!current) { 
-    return; 
-  }
-  if(previous) {
-    // If the previous block is an acceleration block, but it is not long enough to 
-    // complete the full speed change within the block, we need to adjust out entry
-    // speed accordingly. Remember current->entry_factor equals the exit factor of 
-    // the previous block.
-    if(previous->entry_speed < current->entry_speed) {
-      float max_entry_speed = max_allowable_speed(-previous->acceleration, previous->entry_speed, previous->millimeters);
-      if (max_entry_speed < current->entry_speed) {
-        current->entry_speed = max_entry_speed;
-      }
-    }
-  }
-}
-
-// planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This 
-// implements the forward pass.
-void planner_forward_pass() {
-  char block_index = block_buffer_tail;
-  block_t *block[3] = {
-    NULL, NULL, NULL  };
-
-  while(block_index != block_buffer_head) {
-    block[0] = block[1];
-    block[1] = block[2];
-    block[2] = &block_buffer[block_index];
-    planner_forward_pass_kernel(block[0],block[1],block[2]);
-    block_index = (block_index+1) & BLOCK_BUFFER_MASK;
-  }
-  planner_forward_pass_kernel(block[1], block[2], NULL);
-}
-
-// Recalculates the trapezoid speed profiles for all blocks in the plan according to the 
-// entry_factor for each junction. Must be called by planner_recalculate() after 
-// updating the blocks.
-void planner_recalculate_trapezoids() {
-  char block_index = block_buffer_tail;
-  block_t *current;
-  block_t *next = NULL;
-  while(block_index != block_buffer_head) {
-    current = next;
-    next = &block_buffer[block_index];
-    if (current) {
-      calculate_trapezoid_for_block(current, current->entry_speed, next->entry_speed);      
-    }
-    block_index = (block_index+1) & BLOCK_BUFFER_MASK;
-  }
-  calculate_trapezoid_for_block(next, next->entry_speed, safe_speed(next));
-}
-
-// Recalculates the motion plan according to the following algorithm:
-//
-//   1. Go over every block in reverse order and calculate a junction speed reduction (i.e. block_t.entry_factor) 
-//      so that:
-//     a. The junction jerk is within the set limit
-//     b. No speed reduction within one block requires faster deceleration than the one, true constant 
-//        acceleration.
-//   2. Go over every block in chronological order and dial down junction speed reduction values if 
-//     a. The speed increase within one block would require faster accelleration than the one, true 
-//        constant acceleration.
-//
-// When these stages are complete all blocks have an entry_factor that will allow all speed changes to 
-// be performed using only the one, true constant acceleration, and where no junction jerk is jerkier than 
-// the set limit. Finally it will:
-//
-//   3. Recalculate trapezoids for all blocks.
-
-void planner_recalculate() {   
-  planner_reverse_pass();
-  planner_forward_pass();
-  planner_recalculate_trapezoids();
-}
-
-void plan_init() {
-  block_buffer_head = 0;
-  block_buffer_tail = 0;
-  memset(position, 0, sizeof(position)); // clear position
-}
-
-
-inline void plan_discard_current_block() {
-  if (block_buffer_head != block_buffer_tail) {
-    block_buffer_tail = (block_buffer_tail + 1) & BLOCK_BUFFER_MASK;  
-  }
-}
-
-inline block_t *plan_get_current_block() {
-  if (block_buffer_head == block_buffer_tail) { 
-    return(NULL); 
-  }
-  block_t *block = &block_buffer[block_buffer_tail];
-  block->busy = true;
-  return(block);
-}
-
-void check_axes_activity() {
-  unsigned char x_active = 0;
-  unsigned char y_active = 0;  
-  unsigned char z_active = 0;
-  unsigned char e_active = 0;
-  block_t *block;
-
-  if(block_buffer_tail != block_buffer_head) {
-    char block_index = block_buffer_tail;
-    while(block_index != block_buffer_head) {
-      block = &block_buffer[block_index];
-      if(block->steps_x != 0) x_active++;
-      if(block->steps_y != 0) y_active++;
-      if(block->steps_z != 0) z_active++;
-      if(block->steps_e != 0) e_active++;
-      block_index = (block_index+1) & BLOCK_BUFFER_MASK;
-    }
-  }
-  if((DISABLE_X) && (x_active == 0)) disable_x();
-  if((DISABLE_Y) && (y_active == 0)) disable_y();
-  if((DISABLE_Z) && (z_active == 0)) disable_z();
-  if((DISABLE_E) && (e_active == 0)) disable_e();
-}
-
-// Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in 
-// mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
-// calculation the caller must also provide the physical length of the line in millimeters.
-void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
-  // The target position of the tool in absolute steps
-  // Calculate target position in absolute steps
-  long target[4];
-  target[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
-  target[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
-  target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);     
-  target[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);     
-  
-  // Calculate the buffer head after we push this byte
-  int next_buffer_head = (block_buffer_head + 1) & BLOCK_BUFFER_MASK;  
-
-  // If the buffer is full: good! That means we are well ahead of the robot. 
-  // Rest here until there is room in the buffer.
-  while(block_buffer_tail == next_buffer_head) { 
-    manage_heater(); 
-    manage_inactivity(1); 
-  }
-
-  // Prepare to set up new block
-  block_t *block = &block_buffer[block_buffer_head];
-  
-  // Mark block as not busy (Not executed by the stepper interrupt)
-  block->busy = false;
-
-  // Number of steps for each axis
-  block->steps_x = labs(target[X_AXIS]-position[X_AXIS]);
-  block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
-  block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
-  block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
-  block->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, block->steps_e)));
-
-  // Bail if this is a zero-length block
-  if (block->step_event_count == 0) { 
-    return; 
-  };
-  
-  //enable active axes
-  if(block->steps_x != 0) enable_x();
-  if(block->steps_y != 0) enable_y();
-  if(block->steps_z != 0) enable_z();
-  if(block->steps_e != 0) enable_e();
-
-  float delta_x_mm = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
-  float delta_y_mm = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
-  float delta_z_mm = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
-  float delta_e_mm = (target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS];
-  block->millimeters = sqrt(square(delta_x_mm) + square(delta_y_mm) + square(delta_z_mm) + square(delta_e_mm));
-
-  unsigned long microseconds;
-  microseconds = lround((block->millimeters/feed_rate)*1000000);
-  
-  // Calculate speed in mm/minute for each axis
-  float multiplier = 60.0*1000000.0/microseconds;
-  block->speed_z = delta_z_mm * multiplier; 
-  block->speed_x = delta_x_mm * multiplier;
-  block->speed_y = delta_y_mm * multiplier;
-  block->speed_e = delta_e_mm * multiplier; 
-
-  // Limit speed per axis
-  float speed_factor = 1;
-  float tmp_speed_factor;
-  if(abs(block->speed_x) > max_feedrate[X_AXIS]) {
-    speed_factor = max_feedrate[X_AXIS] / abs(block->speed_x);
-  }
-  if(abs(block->speed_y) > max_feedrate[Y_AXIS]){
-    tmp_speed_factor = max_feedrate[Y_AXIS] / abs(block->speed_y);
-    if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
-  }
-  if(abs(block->speed_z) > max_feedrate[Z_AXIS]){
-    tmp_speed_factor = max_feedrate[Z_AXIS] / abs(block->speed_z);
-    if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
-  }
-  if(abs(block->speed_e) > max_feedrate[E_AXIS]){
-    tmp_speed_factor = max_feedrate[E_AXIS] / abs(block->speed_e);
-    if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
-  }
-  multiplier = multiplier * speed_factor;
-  block->speed_z = delta_z_mm * multiplier; 
-  block->speed_x = delta_x_mm * multiplier;
-  block->speed_y = delta_y_mm * multiplier;
-  block->speed_e = delta_e_mm * multiplier; 
-  block->nominal_speed = block->millimeters * multiplier;
-  block->nominal_rate = ceil(block->step_event_count * multiplier / 60);  
-  
-  if(block->nominal_rate < 120) block->nominal_rate = 120;
-  block->entry_speed = safe_speed(block);
-
-  // Compute the acceleration rate for the trapezoid generator. 
-  float travel_per_step = block->millimeters/block->step_event_count;
-  if(block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0) {
-    block->acceleration_st = ceil( (retract_acceleration)/travel_per_step); // convert to: acceleration steps/sec^2
-  }
-  else {
-    block->acceleration_st = ceil( (acceleration)/travel_per_step);      // convert to: acceleration steps/sec^2
-    // Limit acceleration per axis
-    if((block->acceleration_st * block->steps_x / block->step_event_count) > axis_steps_per_sqr_second[X_AXIS])
-      block->acceleration_st = axis_steps_per_sqr_second[X_AXIS];
-    if((block->acceleration_st * block->steps_y / block->step_event_count) > axis_steps_per_sqr_second[Y_AXIS])
-      block->acceleration_st = axis_steps_per_sqr_second[Y_AXIS];
-    if((block->acceleration_st * block->steps_e / block->step_event_count) > axis_steps_per_sqr_second[E_AXIS])
-      block->acceleration_st = axis_steps_per_sqr_second[E_AXIS];
-    if(((block->acceleration_st / block->step_event_count) * block->steps_z ) > axis_steps_per_sqr_second[Z_AXIS])
-      block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
-  }
-  block->acceleration = block->acceleration_st * travel_per_step;
-  
-#ifdef ADVANCE
-  // Calculate advance rate
-  if((block->steps_e == 0) || (block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0)) {
-    block->advance_rate = 0;
-    block->advance = 0;
-  }
-  else {
-    long acc_dist = estimate_acceleration_distance(0, block->nominal_rate, block->acceleration_st);
-    float advance = (STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K) * 
-      (block->speed_e * block->speed_e * EXTRUTION_AREA * EXTRUTION_AREA / 3600.0)*65536;
-    block->advance = advance;
-    if(acc_dist == 0) {
-      block->advance_rate = 0;
-    } 
-    else {
-      block->advance_rate = advance / (float)acc_dist;
-    }
-  }
-
-#endif // ADVANCE
-
-  // compute a preliminary conservative acceleration trapezoid
-  float safespeed = safe_speed(block);
-  calculate_trapezoid_for_block(block, safespeed, safespeed); 
-
-  // Compute direction bits for this block
-  block->direction_bits = 0;
-  if (target[X_AXIS] < position[X_AXIS]) { 
-    block->direction_bits |= (1<<X_AXIS); 
-  }
-  if (target[Y_AXIS] < position[Y_AXIS]) { 
-    block->direction_bits |= (1<<Y_AXIS); 
-  }
-  if (target[Z_AXIS] < position[Z_AXIS]) { 
-    block->direction_bits |= (1<<Z_AXIS); 
-  }
-  if (target[E_AXIS] < position[E_AXIS]) { 
-    block->direction_bits |= (1<<E_AXIS); 
-  }
-
-  // Move buffer head
-  block_buffer_head = next_buffer_head;     
-
-  // Update position 
-  memcpy(position, target, sizeof(target)); // position[] = target[]
-
-  planner_recalculate();
-  st_wake_up();
-}
-
-void plan_set_position(float x, float y, float z, float e)
-{
-  position[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
-  position[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
-  position[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);     
-  position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);     
-}
-
-// Stepper
-
-// intRes = intIn1 * intIn2 >> 16
-// uses:
-// r26 to store 0
-// r27 to store the byte 1 of the 24 bit result
-#define MultiU16X8toH16(intRes, charIn1, intIn2) \
-asm volatile ( \
-"clr r26 \n\t" \
-"mul %A1, %B2 \n\t" \
-"movw %A0, r0 \n\t" \
-"mul %A1, %A2 \n\t" \
-"add %A0, r1 \n\t" \
-"adc %B0, r26 \n\t" \
-"lsr r0 \n\t" \
-"adc %A0, r26 \n\t" \
-"adc %B0, r26 \n\t" \
-"clr r1 \n\t" \
-: \
-"=&r" (intRes) \
-: \
-"d" (charIn1), \
-"d" (intIn2) \
-: \
-"r26" \
-)
-
-// intRes = longIn1 * longIn2 >> 24
-// uses:
-// r26 to store 0
-// r27 to store the byte 1 of the 48bit result
-#define MultiU24X24toH16(intRes, longIn1, longIn2) \
-asm volatile ( \
-"clr r26 \n\t" \
-"mul %A1, %B2 \n\t" \
-"mov r27, r1 \n\t" \
-"mul %B1, %C2 \n\t" \
-"movw %A0, r0 \n\t" \
-"mul %C1, %C2 \n\t" \
-"add %B0, r0 \n\t" \
-"mul %C1, %B2 \n\t" \
-"add %A0, r0 \n\t" \
-"adc %B0, r1 \n\t" \
-"mul %A1, %C2 \n\t" \
-"add r27, r0 \n\t" \
-"adc %A0, r1 \n\t" \
-"adc %B0, r26 \n\t" \
-"mul %B1, %B2 \n\t" \
-"add r27, r0 \n\t" \
-"adc %A0, r1 \n\t" \
-"adc %B0, r26 \n\t" \
-"mul %C1, %A2 \n\t" \
-"add r27, r0 \n\t" \
-"adc %A0, r1 \n\t" \
-"adc %B0, r26 \n\t" \
-"mul %B1, %A2 \n\t" \
-"add r27, r1 \n\t" \
-"adc %A0, r26 \n\t" \
-"adc %B0, r26 \n\t" \
-"lsr r27 \n\t" \
-"adc %A0, r26 \n\t" \
-"adc %B0, r26 \n\t" \
-"clr r1 \n\t" \
-: \
-"=&r" (intRes) \
-: \
-"d" (longIn1), \
-"d" (longIn2) \
-: \
-"r26" , "r27" \
-)
-
-// Some useful constants
-
-#define ENABLE_STEPPER_DRIVER_INTERRUPT()  TIMSK1 |= (1<<OCIE1A)
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A)
-
-static block_t *current_block;  // A pointer to the block currently being traced
-
-// Variables used by The Stepper Driver Interrupt
-static unsigned char out_bits;        // The next stepping-bits to be output
-static long counter_x,       // Counter variables for the bresenham line tracer
-            counter_y, 
-            counter_z,       
-            counter_e;
-static unsigned long step_events_completed; // The number of step events executed in the current block
-static long advance_rate, advance, final_advance = 0;
-static short old_advance = 0;
-static short e_steps;
-static unsigned char busy = false; // TRUE when SIG_OUTPUT_COMPARE1A is being serviced. Used to avoid retriggering that handler.
-static long acceleration_time, deceleration_time;
-static long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
-static unsigned short acc_step_rate; // needed for deccelaration start point
-
-
-
-//         __________________________
-//        /|                        |\     _________________         ^
-//       / |                        | \   /|               |\        |
-//      /  |                        |  \ / |               | \       s
-//     /   |                        |   |  |               |  \      p
-//    /    |                        |   |  |               |   \     e
-//   +-----+------------------------+---+--+---------------+----+    e
-//   |               BLOCK 1            |      BLOCK 2          |    d
-//
-//                           time ----->
-// 
-//  The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates 
-//  first block->accelerate_until step_events_completed, then keeps going at constant speed until 
-//  step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
-//  The slope of acceleration is calculated with the leib ramp alghorithm.
-
-void st_wake_up() {
-  //  TCNT1 = 0;
-  ENABLE_STEPPER_DRIVER_INTERRUPT();  
-}
-
-inline unsigned short calc_timer(unsigned short step_rate) {
-  unsigned short timer;
-  if(step_rate < 32) step_rate = 32;
-  step_rate -= 32; // Correct for minimal speed
-  if(step_rate >= (8*256)){ // higher step rate 
-    unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
-    unsigned char tmp_step_rate = (step_rate & 0x00ff);
-    unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
-    MultiU16X8toH16(timer, tmp_step_rate, gain);
-    timer = (unsigned short)pgm_read_word_near(table_address) - timer;
-  }
-  else { // lower step rates
-    unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
-    table_address += ((step_rate)>>1) & 0xfffc;
-    timer = (unsigned short)pgm_read_word_near(table_address);
-    timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
-  }
-  if(timer < 100) timer = 100;
-  return timer;
-}
-
-// Initializes the trapezoid generator from the current block. Called whenever a new 
-// block begins.
-inline void trapezoid_generator_reset() {
-  accelerate_until = current_block->accelerate_until;
-  decelerate_after = current_block->decelerate_after;
-  acceleration_rate = current_block->acceleration_rate;
-  initial_rate = current_block->initial_rate;
-  final_rate = current_block->final_rate;
-  nominal_rate = current_block->nominal_rate;
-  advance = current_block->initial_advance;
-  final_advance = current_block->final_advance;
-  deceleration_time = 0;
-  advance_rate = current_block->advance_rate;
-  
-  // step_rate to timer interval
-  acc_step_rate = initial_rate;
-  acceleration_time = calc_timer(acc_step_rate);
-  OCR1A = acceleration_time;
-}
-
-// "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.  
-// It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. 
-ISR(TIMER1_COMPA_vect)
-{        
-  if(busy){ /*Serial.println("BUSY")*/; 
-    return; 
-  } // The busy-flag is used to avoid reentering this interrupt
-
-  busy = true;
-  sei(); // Re enable interrupts (normally disabled while inside an interrupt handler)
-
-  // If there is no current block, attempt to pop one from the buffer
-  if (current_block == NULL) {
-    // Anything in the buffer?
-    current_block = plan_get_current_block();
-    if (current_block != NULL) {
-      trapezoid_generator_reset();
-      counter_x = -(current_block->step_event_count >> 1);
-      counter_y = counter_x;
-      counter_z = counter_x;
-      counter_e = counter_x;
-      step_events_completed = 0;
-      e_steps = 0;
-    } 
-    else {
-      DISABLE_STEPPER_DRIVER_INTERRUPT();
-    }    
-  } 
-
-  if (current_block != NULL) {
-    // Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
-    out_bits = current_block->direction_bits;
-
-#ifdef ADVANCE
-    // Calculate E early.
-    counter_e += current_block->steps_e;
-    if (counter_e > 0) {
-      counter_e -= current_block->step_event_count;
-      if ((out_bits & (1<<E_AXIS)) != 0) { // - direction
-        CRITICAL_SECTION_START;
-        e_steps--;
-        CRITICAL_SECTION_END;
-      }
-      else {
-        CRITICAL_SECTION_START;
-        e_steps++;
-        CRITICAL_SECTION_END;
-      }
-    }    
-    // Do E steps + advance steps
-    CRITICAL_SECTION_START;
-    e_steps += ((advance >> 16) - old_advance);
-    CRITICAL_SECTION_END;
-    old_advance = advance >> 16;  
-#endif //ADVANCE
-
-    // Set direction en check limit switches
-    if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
-      WRITE(X_DIR_PIN, INVERT_X_DIR);
-      if(READ(X_MIN_PIN) != ENDSTOPS_INVERTING) {
-        step_events_completed = current_block->step_event_count;
-      }
-    }
-    else // +direction
-    WRITE(X_DIR_PIN,!INVERT_X_DIR);
-
-    if ((out_bits & (1<<Y_AXIS)) != 0) {   // -direction
-      WRITE(Y_DIR_PIN,INVERT_Y_DIR);
-      if(READ(Y_MIN_PIN) != ENDSTOPS_INVERTING) {
-        step_events_completed = current_block->step_event_count;
-      }
-    }
-    else // +direction
-    WRITE(Y_DIR_PIN,!INVERT_Y_DIR);
-
-    if ((out_bits & (1<<Z_AXIS)) != 0) {   // -direction
-      WRITE(Z_DIR_PIN,INVERT_Z_DIR);
-      if(READ(Z_MIN_PIN) != ENDSTOPS_INVERTING) {
-        step_events_completed = current_block->step_event_count;
-      }
-    }
-    else // +direction
-    WRITE(Z_DIR_PIN,!INVERT_Z_DIR);
-
-#ifndef ADVANCE
-    if ((out_bits & (1<<E_AXIS)) != 0)   // -direction
-      WRITE(E_DIR_PIN,INVERT_E_DIR);
-    else // +direction
-      WRITE(E_DIR_PIN,!INVERT_E_DIR);
-#endif //!ADVANCE
-
-    counter_x += current_block->steps_x;
-    if (counter_x > 0) {
-      WRITE(X_STEP_PIN, HIGH);
-      counter_x -= current_block->step_event_count;
-      WRITE(X_STEP_PIN, LOW);
-    }
-
-    counter_y += current_block->steps_y;
-    if (counter_y > 0) {
-      WRITE(Y_STEP_PIN, HIGH);
-      counter_y -= current_block->step_event_count;
-      WRITE(Y_STEP_PIN, LOW);
-    }
-
-    counter_z += current_block->steps_z;
-    if (counter_z > 0) {
-      WRITE(Z_STEP_PIN, HIGH);
-      counter_z -= current_block->step_event_count;
-      WRITE(Z_STEP_PIN, LOW);
-    }
-
-#ifndef ADVANCE
-    counter_e += current_block->steps_e;
-    if (counter_e > 0) {
-      WRITE(E_STEP_PIN, HIGH);
-      counter_e -= current_block->step_event_count;
-      WRITE(E_STEP_PIN, LOW);
-    }
-#endif //!ADVANCE
-
-    // Calculare new timer value
-    unsigned short timer;
-    unsigned short step_rate;
-    if (step_events_completed < accelerate_until) {
-      MultiU24X24toH16(acc_step_rate, acceleration_time, acceleration_rate);
-      acc_step_rate += initial_rate;
-      
-      // upper limit
-      if(acc_step_rate > nominal_rate)
-        acc_step_rate = nominal_rate;
-
-      // step_rate to timer interval
-      timer = calc_timer(acc_step_rate);
-      advance += advance_rate;
-      acceleration_time += timer;
-      OCR1A = timer;
-    } 
-    else if (step_events_completed >= decelerate_after) {   
-      MultiU24X24toH16(step_rate, deceleration_time, acceleration_rate);
-      
-      if(step_rate > acc_step_rate) { // Check step_rate stays positive
-        step_rate = final_rate;
-      }
-      else {
-        step_rate = acc_step_rate - step_rate; // Decelerate from aceleration end point.
-      }
-
-      // lower limit
-      if(step_rate < final_rate)
-        step_rate = final_rate;
-
-      // step_rate to timer interval
-      timer = calc_timer(step_rate);
-#ifdef ADVANCE
-      advance -= advance_rate;
-      if(advance < final_advance)
-        advance = final_advance;
-#endif //ADVANCE
-      deceleration_time += timer;
-      OCR1A = timer;
-    }       
-    // If current block is finished, reset pointer 
-    step_events_completed += 1;  
-    if (step_events_completed >= current_block->step_event_count) {
-      current_block = NULL;
-      plan_discard_current_block();
-    }   
-  } 
-  busy=false;
-}
-
-#ifdef ADVANCE
-
-unsigned char old_OCR0A;
-// Timer interrupt for E. e_steps is set in the main routine;
-// Timer 0 is shared with millies
-ISR(TIMER0_COMPA_vect)
-{
-  // Critical section needed because Timer 1 interrupt has higher priority. 
-  // The pin set functions are placed on trategic position to comply with the stepper driver timing.
-  WRITE(E_STEP_PIN, LOW);
-  // Set E direction (Depends on E direction + advance)
-  if (e_steps < 0) {
-    WRITE(E_DIR_PIN,INVERT_E_DIR);    
-    e_steps++;
-    WRITE(E_STEP_PIN, HIGH);
-  } 
-  if (e_steps > 0) {
-    WRITE(E_DIR_PIN,!INVERT_E_DIR);
-    e_steps--;
-    WRITE(E_STEP_PIN, HIGH);
-  }
-  old_OCR0A += 25; // 10kHz interrupt
-  OCR0A = old_OCR0A;
-}
-#endif // ADVANCE
-
-void st_init()
-{
-  // waveform generation = 0100 = CTC
-  TCCR1B &= ~(1<<WGM13);
-  TCCR1B |=  (1<<WGM12);
-  TCCR1A &= ~(1<<WGM11); 
-  TCCR1A &= ~(1<<WGM10);
-
-  // output mode = 00 (disconnected)
-  TCCR1A &= ~(3<<COM1A0); 
-  TCCR1A &= ~(3<<COM1B0); 
-  TCCR1B = (TCCR1B & ~(0x07<<CS10)) | (2<<CS10); // 2MHz timer
-
-  OCR1A = 0x4000;
-  DISABLE_STEPPER_DRIVER_INTERRUPT();  
-
-#ifdef ADVANCE
-  e_steps = 0;
-  TIMSK0 |= (1<<OCIE0A);
-#endif //ADVANCE
-  sei();
-}
-
-// Block until all buffered steps are executed
-void st_synchronize()
-{
-  while(plan_get_current_block()) {
-    manage_heater();
-    manage_inactivity(1);
-  }   
-}
-
-// Temperature loop
-
-void tp_init()
-{
-  DIDR0 = 1<<5; // TEMP_0_PIN for GEN6
-  ADMUX = ((1 << REFS0) | (5 & 0x07));
-  ADCSRA = 1<<ADEN | 1<<ADSC | 1<<ADIF | 0x07; // ADC enable, Clear interrupt, 1/128 prescaler.
-  TCCR2B = 0;     //Stop timer in case of running
-
-#ifdef PIDTEMP
-  TCCR2A = 0x23;  //OC2A disable; FastPWM noninverting; FastPWM mode 7
-#else
-  TCCR2A = 0x03;  //OC2A disable; FastPWM noninverting; FastPWM mode 7
-#endif //PIDTEMP
-  OCR2A = 156;    //Period is ~10ms
-  OCR2B = 0;      //Duty Cycle for heater pin is 0 (startup)
-  TIMSK2 = 0x01;  //Enable overflow interrupt
-  TCCR2B = 0x0F;  //1/1024 prescaler, start
-}
-
-static unsigned char temp_count = 0;
-static unsigned long raw_temp_value = 0;
-
-ISR(TIMER2_OVF_vect)
-{
-  //  uint8_t low, high;
-
-  //  low = ADCL;
-  //  high = ADCH;
-  raw_temp_value += ADC;
-  //  raw_temp_value = (ADCH <<8) | ADCL;
-  ADCSRA = 1<<ADEN | 1<<ADSC | 1<<ADIF | 0x07; // ADC enable, Clear interrupt, Enable Interrupt, 1/128 prescaler.
-  //  raw_temp_value += (high <<8) | low;
-  temp_count++;
-
-  if(temp_count >= 16)
-  {
-    current_raw = 16383 - raw_temp_value;
-    temp_meas_ready = true;
-    temp_count = 0;
-    raw_temp_value = 0;
-#ifdef MAXTEMP
-    if(current_raw >= maxttemp) {
-      target_raw = 0;
-#ifdef PIDTEMP
-      OCR2B = 0;
-#else
-      WRITE(HEATER_0_PIN,LOW);
-#endif //PIDTEMP
-    }
-#endif //MAXTEMP
-#ifdef MINTEMP
-    if(current_raw <= minttemp) {
-      target_raw = 0;
-#ifdef PIDTEMP
-      OCR2B = 0;
-#else
-      WRITE(HEATER_0_PIN,LOW);
-#endif //PIDTEMP
-    }
-#endif //MAXTEMP
-#ifndef PIDTEMP
-    if(current_raw >= target_raw)
-    {
-      WRITE(HEATER_0_PIN,LOW);
-    }
-    else 
-    {
-      WRITE(HEATER_0_PIN,HIGH);
-    }
-#endif //PIDTEMP
-  }
-}
-
-
index 1d28d0582f03d72753c4d8345fc94432024587b2..c1671ddef93284a5527157cbd6ae51e2b821fe1d 100644 (file)
@@ -27,6 +27,7 @@
 #define                _READ(IO)                                       ((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN)))
 /// write to a pin
 #define                _WRITE(IO, v)                   do { if (v) {DIO ##  IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ##  IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }; } while (0)
+//#define              _WRITE(IO, v)   do { #if (DIO ##  IO ## _WPORT >= 0x100) CRITICAL_SECTION_START; if (v) {DIO ##  IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ##  IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); };#if (DIO ##  IO ## _WPORT >= 0x100) CRITICAL_SECTION_END; } while (0)
 /// toggle a pin
 #define                _TOGGLE(IO)                             do {DIO ##  IO ## _RPORT = MASK(DIO ## IO ## _PIN); } while (0)
 
diff --git a/Marlin/lcd.h b/Marlin/lcd.h
new file mode 100644 (file)
index 0000000..74057dd
--- /dev/null
@@ -0,0 +1,10 @@
+#ifndef __LCDH
+#define __LCDH
+
+
+
+
+
+
+
+#endif
diff --git a/Marlin/lcd.pde b/Marlin/lcd.pde
new file mode 100644 (file)
index 0000000..8b13789
--- /dev/null
@@ -0,0 +1 @@
+
index 1bd670266cab47bc98ce0c4e2c4ae3e94e00f438..795d8bdbb5df6f21e06e8bb8f029f323741750c6 100644 (file)
@@ -60,8 +60,8 @@
 
 #define HEATER_0_PIN        6
 #define TEMP_0_PIN          0    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
-
-
+#define HEATER_1_PIN        -1
+#define HEATER_2_PIN        -1
 #endif
 
 
 
 #define HEATER_0_PIN       14
 #define TEMP_0_PIN          4 //D27   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
-
+#define HEATER_1_PIN        -1
+#define HEATER_2_PIN        -1
 /*  Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31)  */
 
 
 
 #define HEATER_0_PIN    -1
 #define TEMP_0_PIN      -1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
-
+#define HEATER_1_PIN        -1
+#define HEATER_2_PIN        -1
 
 
 
 
 #define HEATER_0_PIN       10
 #define HEATER_1_PIN       8
+#define HEATER_2_PIN        -1
 #define TEMP_0_PIN         13   // ANALOG NUMBERING
 #define TEMP_1_PIN         14   // ANALOG NUMBERING
+#define TEMP_2_PIN         -1   // ANALOG NUMBERING
 
 
 #else // RAMPS_V_1_1 or RAMPS_V_1_2 as default
   #define HEATER_1_PIN      8    // RAMPS 1.1
   #define FAN_PIN           9    // RAMPS 1.1
 #endif
-
+#define HEATER_2_PIN        -1
 #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!!!!!!!!!
+#define TEMP_2_PIN          -1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
 #endif
 
 // SPI for Max6675 Thermocouple 
 
 #define HEATER_0_PIN        6
 #define TEMP_0_PIN          0    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
-
+#define HEATER_1_PIN        -1
+#define HEATER_2_PIN        -1
 
 #endif
 
     #define TEMP_0_PIN      5     //changed @ rkoeppl 20110410
     #define HEATER_0_PIN    14    //changed @ rkoeppl 20110410
     #define HEATER_1_PIN    -1    //changed @ rkoeppl 20110410
-    
+    #define HEATER_2_PIN        -1
     
     #define SDPOWER          -1
     #define SDSS          17
     #define LED_PIN         -1    //changed @ rkoeppl 20110410
     #define TEMP_1_PIN      -1    //changed @ rkoeppl 20110410
+    #define TEMP_2_PIN      -1
     #define FAN_PIN         -1    //changed @ rkoeppl 20110410
     #define PS_ON_PIN       -1    //changed @ rkoeppl 20110410
     //our pin for debugging.
     #define RX_ENABLE_PIN      13
 
 #endif
+
 /****************************************************************************************
 * Sanguinololu pin assignment
 *
 
 #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)
-#define SDPOWER          -1
-#define SDSS          31
+#define TEMP_2_PIN         -1
+#define SDPOWER            -1
+#define SDSS               31
+#define HEATER_2_PIN       -1
 
-#ifndef KNOWN_BOARD
-#error Unknown MOTHERBOARD value in configuration.h
 #endif
 
+
+#if MOTHERBOARD == 7
+#define KNOWN_BOARD
+/*****************************************************************
+* Ultimaker pin assignment
+******************************************************************/
+
+#ifndef __AVR_ATmega1280__
+ #ifndef __AVR_ATmega2560__
+ #error Oops!  Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
+ #endif
+#endif
+
+#define X_STEP_PIN 25
+#define X_DIR_PIN 23
+#define X_MIN_PIN 22
+#define X_MAX_PIN 24
+#define X_ENABLE_PIN 27
+
+#define Y_STEP_PIN 31
+#define Y_DIR_PIN 33
+#define Y_MIN_PIN 26
+#define Y_MAX_PIN 28
+#define Y_ENABLE_PIN 29
+
+#define Z_STEP_PIN 37 
+#define Z_DIR_PIN 39
+#define Z_MIN_PIN 30
+#define Z_MAX_PIN 32
+#define Z_ENABLE_PIN 35
+
+#define HEATER_1_PIN 4 
+#define TEMP_1_PIN 11  
+
+#define EXTRUDER_0_STEP_PIN 43 
+#define EXTRUDER_0_DIR_PIN 45
+#define EXTRUDER_0_ENABLE_PIN 41
+#define HEATER_0_PIN  2
+#define TEMP_0_PIN 8   
+
+#define EXTRUDER_1_STEP_PIN 49 
+#define EXTRUDER_1_DIR_PIN 47
+#define EXTRUDER_1_ENABLE_PIN 51
+#define EXTRUDER_1_HEATER_PIN 3
+#define EXTRUDER_1_TEMPERATURE_PIN 10 
+#define HEATER_2_PIN 51
+#define TEMP_2_PIN 3
+
+
+
+#define E_STEP_PIN         EXTRUDER_0_STEP_PIN
+#define E_DIR_PIN          EXTRUDER_0_DIR_PIN
+#define E_ENABLE_PIN       EXTRUDER_0_ENABLE_PIN
+
+#define SDPOWER            -1
+#define SDSS               53
+#define LED_PIN            13
+#define FAN_PIN            7
+#define PS_ON_PIN          12
+#define KILL_PIN           -1
 #endif
 
+
+#ifndef KNOWN_BOARD
+#error Unknown MOTHERBOARD value in configuration.h
+#endif
 #endif
diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp
new file mode 100644 (file)
index 0000000..645384e
--- /dev/null
@@ -0,0 +1,584 @@
+/*
+  planner.c - buffers movement commands and manages the acceleration profile plan
+  Part of Grbl
+
+  Copyright (c) 2009-2011 Simen Svale Skogsrud
+
+  Grbl 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.
+
+  Grbl 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 Grbl.  If not, see <http://www.gnu.org/licenses/>.
+*/
+
+/* The ring buffer implementation gleaned from the wiring_serial library by David A. Mellis. */
+
+/*  
+  Reasoning behind the mathematics in this module (in the key of 'Mathematica'):
+  
+  s == speed, a == acceleration, t == time, d == distance
+
+  Basic definitions:
+
+    Speed[s_, a_, t_] := s + (a*t) 
+    Travel[s_, a_, t_] := Integrate[Speed[s, a, t], t]
+
+  Distance to reach a specific speed with a constant acceleration:
+
+    Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t]
+      d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance()
+
+  Speed after a given distance of travel with constant acceleration:
+
+    Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t]
+      m -> Sqrt[2 a d + s^2]    
+
+    DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2]
+
+  When to start braking (di) to reach a specified destionation speed (s2) after accelerating
+  from initial speed s1 without ever stopping at a plateau:
+
+    Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di]
+      di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance()
+
+    IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a)
+*/
+                                                                                                            
+
+//#include <inttypes.h>
+//#include <math.h>       
+//#include <stdlib.h>
+
+#include "Marlin.h"
+#include "Configuration.h"
+#include "pins.h"
+#include "fastio.h"
+#include "planner.h"
+#include "stepper.h"
+#include "temperature.h"
+#include "ultralcd.h"
+
+unsigned long minsegmenttime;
+float max_feedrate[4]; // set the max speeds
+float axis_steps_per_unit[4];
+long max_acceleration_units_per_sq_second[4]; // Use M201 to override by software
+float minimumfeedrate;
+float acceleration;         // Normal acceleration mm/s^2  THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
+float retract_acceleration; //  mm/s^2   filament pull-pack and push-forward  while standing still in the other axis M204 TXXXX
+float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
+float max_z_jerk;
+float mintravelfeedrate;
+unsigned long axis_steps_per_sqr_second[NUM_AXIS];
+// Manage heater variables.
+
+static block_t block_buffer[BLOCK_BUFFER_SIZE];            // A ring buffer for motion instfructions
+static volatile unsigned char block_buffer_head;           // Index of the next block to be pushed
+static volatile unsigned char block_buffer_tail;           // Index of the block to process now
+
+// The current position of the tool in absolute steps
+ long position[4];   
+
+#define ONE_MINUTE_OF_MICROSECONDS 60000000.0
+
+// Calculates the distance (not time) it takes to accelerate from initial_rate to target_rate using the 
+// given acceleration:
+inline float estimate_acceleration_distance(float initial_rate, float target_rate, float acceleration) {
+  if (acceleration!=0) {
+  return((target_rate*target_rate-initial_rate*initial_rate)/
+         (2.0*acceleration));
+  }
+  else {
+    return 0.0;  // acceleration was 0, set acceleration distance to 0
+  }
+}
+
+// This function gives you the point at which you must start braking (at the rate of -acceleration) if 
+// you started at speed initial_rate and accelerated until this point and want to end at the final_rate after
+// a total travel of distance. This can be used to compute the intersection point between acceleration and
+// deceleration in the cases where the trapezoid has no plateau (i.e. never reaches maximum speed)
+
+inline float intersection_distance(float initial_rate, float final_rate, float acceleration, float distance) {
+ if (acceleration!=0) {
+  return((2.0*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/
+         (4.0*acceleration) );
+  }
+  else {
+    return 0.0;  // acceleration was 0, set intersection distance to 0
+  }
+}
+
+// Calculates trapezoid parameters so that the entry- and exit-speed is compensated by the provided factors.
+
+void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit_speed) {
+  if(block->busy == true) return; // If block is busy then bail out.
+  float entry_factor = entry_speed / block->nominal_speed;
+  float exit_factor = exit_speed / block->nominal_speed;
+  long initial_rate = ceil(block->nominal_rate*entry_factor);
+  long final_rate = ceil(block->nominal_rate*exit_factor);
+  
+#ifdef ADVANCE
+  long initial_advance = block->advance*entry_factor*entry_factor;
+  long final_advance = block->advance*exit_factor*exit_factor;
+#endif // ADVANCE
+
+  // Limit minimal step rate (Otherwise the timer will overflow.)
+  if(initial_rate <120) initial_rate=120;
+  if(final_rate < 120) final_rate=120;
+  
+  // Calculate the acceleration steps
+  long acceleration = block->acceleration_st;
+  long accelerate_steps = estimate_acceleration_distance(initial_rate, block->nominal_rate, acceleration);
+  long decelerate_steps = estimate_acceleration_distance(final_rate, block->nominal_rate, acceleration);
+  // Calculate the size of Plateau of Nominal Rate. 
+  long plateau_steps = block->step_event_count-accelerate_steps-decelerate_steps;
+
+  // Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will
+  // have to use intersection_distance() to calculate when to abort acceleration and start braking 
+  // in order to reach the final_rate exactly at the end of this block.
+  if (plateau_steps < 0) {  
+    accelerate_steps = intersection_distance(initial_rate, final_rate, acceleration, block->step_event_count);
+    plateau_steps = 0;
+  }  
+
+  long decelerate_after = accelerate_steps+plateau_steps;
+
+  CRITICAL_SECTION_START;  // Fill variables used by the stepper in a critical section
+  if(block->busy == false) { // Don't update variables if block is busy.
+    block->accelerate_until = accelerate_steps;
+    block->decelerate_after = decelerate_after;
+    block->initial_rate = initial_rate;
+    block->final_rate = final_rate;
+#ifdef ADVANCE
+    block->initial_advance = initial_advance;
+    block->final_advance = final_advance;
+#endif //ADVANCE
+  }
+  CRITICAL_SECTION_END;
+}                    
+
+// Calculates the maximum allowable speed at this point when you must be able to reach target_velocity using the 
+// acceleration within the allotted distance.
+inline float max_allowable_speed(float acceleration, float target_velocity, float distance) {
+  return(
+  sqrt(target_velocity*target_velocity-2*acceleration*60*60*distance)
+    );
+}
+
+// "Junction jerk" in this context is the immediate change in speed at the junction of two blocks.
+// This method will calculate the junction jerk as the euclidean distance between the nominal 
+// velocities of the respective blocks.
+inline float junction_jerk(block_t *before, block_t *after) {
+  return(sqrt(
+    pow((before->speed_x-after->speed_x), 2)+
+    pow((before->speed_y-after->speed_y), 2)));
+}
+
+// Return the safe speed which is max_jerk/2, e.g. the 
+// speed under which you cannot exceed max_jerk no matter what you do.
+float safe_speed(block_t *block) {
+  float safe_speed;
+  safe_speed = max_xy_jerk/2;  
+  if(abs(block->speed_z) > max_z_jerk/2) safe_speed = max_z_jerk/2;
+  if (safe_speed > block->nominal_speed) safe_speed = block->nominal_speed;
+  return safe_speed;  
+}
+
+// The kernel called by planner_recalculate() when scanning the plan from last to first entry.
+void planner_reverse_pass_kernel(block_t *previous, block_t *current, block_t *next) {
+  if(!current) { 
+    return; 
+  }
+
+  float entry_speed = current->nominal_speed;
+  float exit_factor;
+  float exit_speed;
+  if (next) {
+    exit_speed = next->entry_speed;
+  } 
+  else {
+    exit_speed = safe_speed(current);
+  }
+
+  // Calculate the entry_factor for the current block. 
+  if (previous) {
+    // Reduce speed so that junction_jerk is within the maximum allowed
+    float jerk = junction_jerk(previous, current);
+    if((previous->steps_x == 0) && (previous->steps_y == 0)) {
+      entry_speed = safe_speed(current);
+    }
+    else if (jerk > max_xy_jerk) {
+      entry_speed = (max_xy_jerk/jerk) * entry_speed;
+    } 
+    if(abs(previous->speed_z - current->speed_z) > max_z_jerk) {
+      entry_speed = (max_z_jerk/abs(previous->speed_z - current->speed_z)) * entry_speed;
+    } 
+    // If the required deceleration across the block is too rapid, reduce the entry_factor accordingly.
+    if (entry_speed > exit_speed) {
+      float max_entry_speed = max_allowable_speed(-current->acceleration,exit_speed, current->millimeters);
+      if (max_entry_speed < entry_speed) {
+        entry_speed = max_entry_speed;
+      }
+    }    
+  } 
+  else {
+    entry_speed = safe_speed(current);
+  }
+  // Store result
+  current->entry_speed = entry_speed;
+}
+
+// planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This 
+// implements the reverse pass.
+void planner_reverse_pass() {
+  char block_index = block_buffer_head;
+  if(((block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1)) > 3) {
+    block_index = (block_buffer_head - 3) & (BLOCK_BUFFER_SIZE - 1);
+    block_t *block[5] = {
+      NULL, NULL, NULL, NULL, NULL  };
+    while(block_index != block_buffer_tail) { 
+      block_index = (block_index-1) & (BLOCK_BUFFER_SIZE -1); 
+      block[2]= block[1];
+      block[1]= block[0];
+      block[0] = &block_buffer[block_index];
+      planner_reverse_pass_kernel(block[0], block[1], block[2]);
+    }
+    planner_reverse_pass_kernel(NULL, block[0], block[1]);
+  }
+}
+
+// The kernel called by planner_recalculate() when scanning the plan from first to last entry.
+void planner_forward_pass_kernel(block_t *previous, block_t *current, block_t *next) {
+  if(!current) { 
+    return; 
+  }
+  if(previous) {
+    // If the previous block is an acceleration block, but it is not long enough to 
+    // complete the full speed change within the block, we need to adjust out entry
+    // speed accordingly. Remember current->entry_factor equals the exit factor of 
+    // the previous block.
+    if(previous->entry_speed < current->entry_speed) {
+      float max_entry_speed = max_allowable_speed(-previous->acceleration, previous->entry_speed, previous->millimeters);
+      if (max_entry_speed < current->entry_speed) {
+        current->entry_speed = max_entry_speed;
+      }
+    }
+  }
+}
+
+// planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This 
+// implements the forward pass.
+void planner_forward_pass() {
+  char block_index = block_buffer_tail;
+  block_t *block[3] = {
+    NULL, NULL, NULL  };
+
+  while(block_index != block_buffer_head) {
+    block[0] = block[1];
+    block[1] = block[2];
+    block[2] = &block_buffer[block_index];
+    planner_forward_pass_kernel(block[0],block[1],block[2]);
+    block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1);
+  }
+  planner_forward_pass_kernel(block[1], block[2], NULL);
+}
+
+// Recalculates the trapezoid speed profiles for all blocks in the plan according to the 
+// entry_factor for each junction. Must be called by planner_recalculate() after 
+// updating the blocks.
+void planner_recalculate_trapezoids() {
+  char block_index = block_buffer_tail;
+  block_t *current;
+  block_t *next = NULL;
+  while(block_index != block_buffer_head) {
+    current = next;
+    next = &block_buffer[block_index];
+    if (current) {
+      calculate_trapezoid_for_block(current, current->entry_speed, next->entry_speed);      
+    }
+    block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1);
+  }
+  calculate_trapezoid_for_block(next, next->entry_speed, safe_speed(next));
+}
+
+// Recalculates the motion plan according to the following algorithm:
+//
+//   1. Go over every block in reverse order and calculate a junction speed reduction (i.e. block_t.entry_factor) 
+//      so that:
+//     a. The junction jerk is within the set limit
+//     b. No speed reduction within one block requires faster deceleration than the one, true constant 
+//        acceleration.
+//   2. Go over every block in chronological order and dial down junction speed reduction values if 
+//     a. The speed increase within one block would require faster accelleration than the one, true 
+//        constant acceleration.
+//
+// When these stages are complete all blocks have an entry_factor that will allow all speed changes to 
+// be performed using only the one, true constant acceleration, and where no junction jerk is jerkier than 
+// the set limit. Finally it will:
+//
+//   3. Recalculate trapezoids for all blocks.
+
+void planner_recalculate() {   
+  planner_reverse_pass();
+  planner_forward_pass();
+  planner_recalculate_trapezoids();
+}
+
+void plan_init() {
+  block_buffer_head = 0;
+  block_buffer_tail = 0;
+  memset(position, 0, sizeof(position)); // clear position
+}
+
+
+void plan_discard_current_block() {
+  if (block_buffer_head != block_buffer_tail) {
+    block_buffer_tail = (block_buffer_tail + 1) & (BLOCK_BUFFER_SIZE - 1);  
+  }
+}
+
+block_t *plan_get_current_block() {
+  if (block_buffer_head == block_buffer_tail) { 
+    return(NULL); 
+  }
+  block_t *block = &block_buffer[block_buffer_tail];
+  block->busy = true;
+  return(block);
+}
+
+void check_axes_activity() {
+  unsigned char x_active = 0;
+  unsigned char y_active = 0;  
+  unsigned char z_active = 0;
+  unsigned char e_active = 0;
+  block_t *block;
+
+  if(block_buffer_tail != block_buffer_head) {
+    char block_index = block_buffer_tail;
+    while(block_index != block_buffer_head) {
+      block = &block_buffer[block_index];
+      if(block->steps_x != 0) x_active++;
+      if(block->steps_y != 0) y_active++;
+      if(block->steps_z != 0) z_active++;
+      if(block->steps_e != 0) e_active++;
+      block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1);
+    }
+  }
+  if((DISABLE_X) && (x_active == 0)) disable_x();
+  if((DISABLE_Y) && (y_active == 0)) disable_y();
+  if((DISABLE_Z) && (z_active == 0)) disable_z();
+  if((DISABLE_E) && (e_active == 0)) disable_e();
+}
+
+// Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in 
+// mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
+// calculation the caller must also provide the physical length of the line in millimeters.
+void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
+
+  // The target position of the tool in absolute steps
+  // Calculate target position in absolute steps
+  long target[4];
+  target[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
+  target[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
+  target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);     
+  target[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);     
+
+  // Calculate the buffer head after we push this byte
+  int next_buffer_head = (block_buffer_head + 1) & (BLOCK_BUFFER_SIZE - 1);
+
+  // If the buffer is full: good! That means we are well ahead of the robot. 
+  // Rest here until there is room in the buffer.
+  while(block_buffer_tail == next_buffer_head) { 
+    manage_heater(); 
+    manage_inactivity(1); 
+    LCD_STATUS;
+  }
+
+  // Prepare to set up new block
+  block_t *block = &block_buffer[block_buffer_head];
+  
+  // Mark block as not busy (Not executed by the stepper interrupt)
+  block->busy = false;
+
+  // Number of steps for each axis
+  block->steps_x = labs(target[X_AXIS]-position[X_AXIS]);
+  block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
+  block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
+  block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
+  block->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, block->steps_e)));
+
+  // Bail if this is a zero-length block
+  if (block->step_event_count <=dropsegments) { 
+    return; 
+  };
+
+  //enable active axes
+  if(block->steps_x != 0) enable_x();
+  if(block->steps_y != 0) enable_y();
+  if(block->steps_z != 0) enable_z();
+  if(block->steps_e != 0) enable_e();
+
+  float delta_x_mm = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
+  float delta_y_mm = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
+  float delta_z_mm = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
+  float delta_e_mm = (target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS];
+  block->millimeters = sqrt(square(delta_x_mm) + square(delta_y_mm) + square(delta_z_mm) + square(delta_e_mm));
+
+  unsigned long microseconds;
+
+  if (block->steps_e == 0) {
+       if(feed_rate<mintravelfeedrate) feed_rate=mintravelfeedrate;
+  }
+  else {
+       if(feed_rate<minimumfeedrate) feed_rate=minimumfeedrate;
+  } 
+
+  microseconds = lround((block->millimeters/feed_rate)*1000000);
+
+  // slow down when de buffer starts to empty, rather than wait at the corner for a buffer refill
+  // reduces/removes corner blobs as the machine won't come to a full stop.
+  int blockcount=(block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
+  
+  if ((blockcount>0) && (blockcount < (BLOCK_BUFFER_SIZE - 4))) {
+    if (microseconds<minsegmenttime)  { // buffer is draining, add extra time.  The amount of time added increases if the buffer is still emptied more.
+        microseconds=microseconds+lround(2*(minsegmenttime-microseconds)/blockcount);
+    }
+  }
+  else {
+    if (microseconds<minsegmenttime) microseconds=minsegmenttime;
+  }
+  //  END OF SLOW DOWN SECTION  
+  
+  
+  // Calculate speed in mm/minute for each axis
+  float multiplier = 60.0*1000000.0/microseconds;
+  block->speed_z = delta_z_mm * multiplier; 
+  block->speed_x = delta_x_mm * multiplier;
+  block->speed_y = delta_y_mm * multiplier;
+  block->speed_e = delta_e_mm * multiplier; 
+
+
+  // Limit speed per axis
+  float speed_factor = 1; //factor <=1 do decrease speed
+  if(abs(block->speed_x) > max_feedrate[X_AXIS]) {
+    //// [ErikDeBruijn] IS THIS THE BUG WE'RE LOOING FOR????
+    //// [bernhard] No its not, according to Zalm.
+               //// the if would always be true, since tmp_speedfactor <=0 due the inial if, so its safe to set. the next lines actually compare.
+    speed_factor = max_feedrate[X_AXIS] / abs(block->speed_x);
+    //if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
+  }
+  if(abs(block->speed_y) > max_feedrate[Y_AXIS]){
+    float tmp_speed_factor = max_feedrate[Y_AXIS] / abs(block->speed_y);
+    if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
+  }
+  if(abs(block->speed_z) > max_feedrate[Z_AXIS]){
+    float tmp_speed_factor = max_feedrate[Z_AXIS] / abs(block->speed_z);
+    if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
+  }
+  if(abs(block->speed_e) > max_feedrate[E_AXIS]){
+    float tmp_speed_factor = max_feedrate[E_AXIS] / abs(block->speed_e);
+    if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
+  }
+  multiplier = multiplier * speed_factor;
+  block->speed_z = delta_z_mm * multiplier; 
+  block->speed_x = delta_x_mm * multiplier;
+  block->speed_y = delta_y_mm * multiplier;
+  block->speed_e = delta_e_mm * multiplier; 
+  block->nominal_speed = block->millimeters * multiplier;
+  block->nominal_rate = ceil(block->step_event_count * multiplier / 60);  
+
+  if(block->nominal_rate < 120) block->nominal_rate = 120;
+  block->entry_speed = safe_speed(block);
+
+  // Compute the acceleration rate for the trapezoid generator. 
+  float travel_per_step = block->millimeters/block->step_event_count;
+  if(block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0) {
+    block->acceleration_st = ceil( (retract_acceleration)/travel_per_step); // convert to: acceleration steps/sec^2
+  }
+  else {
+    block->acceleration_st = ceil( (acceleration)/travel_per_step);      // convert to: acceleration steps/sec^2
+    float tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
+    // Limit acceleration per axis
+    if((tmp_acceleration * block->steps_x) > axis_steps_per_sqr_second[X_AXIS]) {
+      block->acceleration_st = axis_steps_per_sqr_second[X_AXIS];
+      tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
+    }
+    if((tmp_acceleration * block->steps_y) > axis_steps_per_sqr_second[Y_AXIS]) {
+      block->acceleration_st = axis_steps_per_sqr_second[Y_AXIS];
+      tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
+    }
+    if((tmp_acceleration * block->steps_e) > axis_steps_per_sqr_second[E_AXIS]) {
+      block->acceleration_st = axis_steps_per_sqr_second[E_AXIS];
+      tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
+    }
+    if((tmp_acceleration * block->steps_z) > axis_steps_per_sqr_second[Z_AXIS]) {
+      block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
+      tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
+    }
+  }
+  block->acceleration = block->acceleration_st * travel_per_step;
+  block->acceleration_rate = (long)((float)block->acceleration_st * 8.388608);
+
+#ifdef ADVANCE
+  // Calculate advance rate
+  if((block->steps_e == 0) || (block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0)) {
+    block->advance_rate = 0;
+    block->advance = 0;
+  }
+  else {
+    long acc_dist = estimate_acceleration_distance(0, block->nominal_rate, block->acceleration_st);
+    float advance = (STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K) * 
+      (block->speed_e * block->speed_e * EXTRUTION_AREA * EXTRUTION_AREA / 3600.0)*65536;
+    block->advance = advance;
+    if(acc_dist == 0) {
+      block->advance_rate = 0;
+    } 
+    else {
+      block->advance_rate = advance / (float)acc_dist;
+    }
+  }
+#endif // ADVANCE
+
+  // compute a preliminary conservative acceleration trapezoid
+  float safespeed = safe_speed(block);
+  calculate_trapezoid_for_block(block, safespeed, safespeed); 
+
+  // Compute direction bits for this block
+  block->direction_bits = 0;
+  if (target[X_AXIS] < position[X_AXIS]) { 
+    block->direction_bits |= (1<<X_AXIS); 
+  }
+  if (target[Y_AXIS] < position[Y_AXIS]) { 
+    block->direction_bits |= (1<<Y_AXIS); 
+  }
+  if (target[Z_AXIS] < position[Z_AXIS]) { 
+    block->direction_bits |= (1<<Z_AXIS); 
+  }
+  if (target[E_AXIS] < position[E_AXIS]) { 
+    block->direction_bits |= (1<<E_AXIS); 
+  }
+
+  // Move buffer head
+  block_buffer_head = next_buffer_head;     
+
+  // Update position 
+  memcpy(position, target, sizeof(target)); // position[] = target[]
+
+  planner_recalculate();
+  st_wake_up();
+}
+
+void plan_set_position(float x, float y, float z, float e)
+{
+  position[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
+  position[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
+  position[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);     
+  position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);     
+}
+
diff --git a/Marlin/planner.h b/Marlin/planner.h
new file mode 100644 (file)
index 0000000..7880e6e
--- /dev/null
@@ -0,0 +1,90 @@
+/*
+  planner.h - buffers movement commands and manages the acceleration profile plan
+  Part of Grbl
+
+  Copyright (c) 2009-2011 Simen Svale Skogsrud
+
+  Grbl 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.
+
+  Grbl 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 Grbl.  If not, see <http://www.gnu.org/licenses/>.
+*/
+
+// This module is to be considered a sub-module of stepper.c. Please don't include 
+// this file from any other module.
+
+#ifndef planner_h
+#define planner_h
+
+// This struct is used when buffering the setup for each linear movement "nominal" values are as specified in 
+// the source g-code and may never actually be reached if acceleration management is active.
+typedef struct {
+  // Fields used by the bresenham algorithm for tracing the line
+  long steps_x, steps_y, steps_z, steps_e;  // Step count along each axis
+  long step_event_count;                    // The number of step events required to complete this block
+  volatile long accelerate_until;                    // The index of the step event on which to stop acceleration
+  volatile long decelerate_after;                    // The index of the step event on which to start decelerating
+  volatile long acceleration_rate;                   // The acceleration rate used for acceleration calculation
+  unsigned char direction_bits;             // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
+#ifdef ADVANCE
+  long advance_rate;
+  volatile long initial_advance;
+  volatile long final_advance;
+  float advance;
+#endif
+
+  // Fields used by the motion planner to manage acceleration
+  float speed_x, speed_y, speed_z, speed_e;          // Nominal mm/minute for each axis
+  float nominal_speed;                               // The nominal speed for this block in mm/min  
+  float millimeters;                                 // The total travel of this block in mm
+  float entry_speed;
+  float acceleration;                                // acceleration mm/sec^2
+
+  // Settings for the trapezoid generator
+  long nominal_rate;                                 // The nominal step rate for this block in step_events/sec 
+  volatile long initial_rate;                        // The jerk-adjusted step rate at start of block  
+  volatile long final_rate;                          // The minimal rate at exit
+  long acceleration_st;                              // acceleration steps/sec^2
+  volatile char busy;
+} block_t;
+      
+// Initialize the motion plan subsystem      
+void plan_init();
+
+// Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in 
+// millimaters. Feed rate specifies the speed of the motion.
+void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
+
+// Set position. Used for G92 instructions.
+void plan_set_position(float x, float y, float z, float e);
+
+// Called when the current block is no longer needed. Discards the block and makes the memory
+// availible for new blocks.
+void plan_discard_current_block();
+
+// Gets the current block. Returns NULL if buffer empty
+block_t *plan_get_current_block();
+
+void check_axes_activity();
+
+extern unsigned long minsegmenttime;
+extern float max_feedrate[4]; // set the max speeds
+extern float axis_steps_per_unit[4];
+extern long max_acceleration_units_per_sq_second[4]; // Use M201 to override by software
+extern float minimumfeedrate;
+extern float acceleration;         // Normal acceleration mm/s^2  THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
+extern float retract_acceleration; //  mm/s^2   filament pull-pack and push-forward  while standing still in the other axis M204 TXXXX
+extern float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
+extern float max_z_jerk;
+extern float mintravelfeedrate;
+extern unsigned long axis_steps_per_sqr_second[NUM_AXIS];
+
+#endif
index 5c54a08d1cd2cd92f9e0d909f0c251de2330f887..43ef89980d91029b403e9831a18a75a88352e1da 100644 (file)
@@ -3,7 +3,7 @@
 
 #include <avr/pgmspace.h>
 
-uint16_t speed_lookuptable_fast[256][2] PROGMEM = {
+uint16_t speed_lookuptable_fast[256][2] PROGMEM = {\
 { 62500, 55556}, { 6944, 3268}, { 3676, 1176}, { 2500, 607}, { 1893, 369}, { 1524, 249}, { 1275, 179}, { 1096, 135}, 
 { 961, 105}, { 856, 85}, { 771, 69}, { 702, 58}, { 644, 49}, { 595, 42}, { 553, 37}, { 516, 32}, 
 { 484, 28}, { 456, 25}, { 431, 23}, { 408, 20}, { 388, 19}, { 369, 16}, { 353, 16}, { 337, 14}, 
@@ -35,9 +35,9 @@ uint16_t speed_lookuptable_fast[256][2] PROGMEM = {
 { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 1}, { 33, 0}, { 33, 0}, 
 { 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 1}, { 32, 0}, { 32, 0}, { 32, 0}, 
 { 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0}, 
-{ 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
+{ 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
 };
-uint16_t speed_lookuptable_slow[256][2] PROGMEM = {
+uint16_t speed_lookuptable_slow[256][2] PROGMEM = {\
 { 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894}, 
 { 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657}, 
 { 12500, 596}, { 11904, 541}, { 11363, 494}, { 10869, 453}, { 10416, 416}, { 10000, 385}, { 9615, 356}, { 9259, 331}, 
@@ -69,7 +69,7 @@ uint16_t speed_lookuptable_slow[256][2] PROGMEM = {
 { 1096, 5}, { 1091, 5}, { 1086, 4}, { 1082, 5}, { 1077, 5}, { 1072, 4}, { 1068, 5}, { 1063, 4}, 
 { 1059, 5}, { 1054, 4}, { 1050, 4}, { 1046, 5}, { 1041, 4}, { 1037, 4}, { 1033, 5}, { 1028, 4}, 
 { 1024, 4}, { 1020, 4}, { 1016, 4}, { 1012, 4}, { 1008, 4}, { 1004, 4}, { 1000, 4}, { 996, 4}, 
-{ 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}
+{ 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}
 };
 
 #endif
diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp
new file mode 100644 (file)
index 0000000..cd68bae
--- /dev/null
@@ -0,0 +1,592 @@
+/*
+  stepper.c - stepper motor driver: executes motion plans using stepper motors
+  Part of Grbl
+
+  Copyright (c) 2009-2011 Simen Svale Skogsrud
+
+  Grbl 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.
+
+  Grbl 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 Grbl.  If not, see <http://www.gnu.org/licenses/>.
+*/
+
+/* The timer calculations of this module informed by the 'RepRap cartesian firmware' by Zack Smith
+   and Philipp Tiefenbacher. */
+
+#include "stepper.h"
+#include "Configuration.h"
+#include "Marlin.h"
+#include "planner.h"
+#include "pins.h"
+#include "fastio.h"
+#include "temperature.h"
+#include "ultralcd.h"
+
+#include "speed_lookuptable.h"
+
+// if DEBUG_STEPS is enabled, M114 can be used to compare two methods of determining the X,Y,Z position of the printer.
+// for debugging purposes only, should be disabled by default
+#ifdef DEBUG_STEPS
+volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
+volatile int count_direction[NUM_AXIS] = { 1, 1, 1, 1};
+#endif
+
+
+// intRes = intIn1 * intIn2 >> 16
+// uses:
+// r26 to store 0
+// r27 to store the byte 1 of the 24 bit result
+#define MultiU16X8toH16(intRes, charIn1, intIn2) \
+asm volatile ( \
+"clr r26 \n\t" \
+"mul %A1, %B2 \n\t" \
+"movw %A0, r0 \n\t" \
+"mul %A1, %A2 \n\t" \
+"add %A0, r1 \n\t" \
+"adc %B0, r26 \n\t" \
+"lsr r0 \n\t" \
+"adc %A0, r26 \n\t" \
+"adc %B0, r26 \n\t" \
+"clr r1 \n\t" \
+: \
+"=&r" (intRes) \
+: \
+"d" (charIn1), \
+"d" (intIn2) \
+: \
+"r26" \
+)
+
+// intRes = longIn1 * longIn2 >> 24
+// uses:
+// r26 to store 0
+// r27 to store the byte 1 of the 48bit result
+#define MultiU24X24toH16(intRes, longIn1, longIn2) \
+asm volatile ( \
+"clr r26 \n\t" \
+"mul %A1, %B2 \n\t" \
+"mov r27, r1 \n\t" \
+"mul %B1, %C2 \n\t" \
+"movw %A0, r0 \n\t" \
+"mul %C1, %C2 \n\t" \
+"add %B0, r0 \n\t" \
+"mul %C1, %B2 \n\t" \
+"add %A0, r0 \n\t" \
+"adc %B0, r1 \n\t" \
+"mul %A1, %C2 \n\t" \
+"add r27, r0 \n\t" \
+"adc %A0, r1 \n\t" \
+"adc %B0, r26 \n\t" \
+"mul %B1, %B2 \n\t" \
+"add r27, r0 \n\t" \
+"adc %A0, r1 \n\t" \
+"adc %B0, r26 \n\t" \
+"mul %C1, %A2 \n\t" \
+"add r27, r0 \n\t" \
+"adc %A0, r1 \n\t" \
+"adc %B0, r26 \n\t" \
+"mul %B1, %A2 \n\t" \
+"add r27, r1 \n\t" \
+"adc %A0, r26 \n\t" \
+"adc %B0, r26 \n\t" \
+"lsr r27 \n\t" \
+"adc %A0, r26 \n\t" \
+"adc %B0, r26 \n\t" \
+"clr r1 \n\t" \
+: \
+"=&r" (intRes) \
+: \
+"d" (longIn1), \
+"d" (longIn2) \
+: \
+"r26" , "r27" \
+)
+
+// Some useful constants
+
+#define ENABLE_STEPPER_DRIVER_INTERRUPT()  TIMSK1 |= (1<<OCIE1A)
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A)
+
+static block_t *current_block;  // A pointer to the block currently being traced
+
+// Variables used by The Stepper Driver Interrupt
+static unsigned char out_bits;        // The next stepping-bits to be output
+static long counter_x,       // Counter variables for the bresenham line tracer
+            counter_y, 
+            counter_z,       
+            counter_e;
+static unsigned long step_events_completed; // The number of step events executed in the current block
+#ifdef ADVANCE
+static long advance_rate, advance, final_advance = 0;
+static short old_advance = 0;
+static short e_steps;
+#endif
+static unsigned char busy = false; // TRUE when SIG_OUTPUT_COMPARE1A is being serviced. Used to avoid retriggering that handler.
+static long acceleration_time, deceleration_time;
+//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
+static unsigned short acc_step_rate; // needed for deccelaration start point
+static char step_loops;
+
+
+//         __________________________
+//        /|                        |\     _________________         ^
+//       / |                        | \   /|               |\        |
+//      /  |                        |  \ / |               | \       s
+//     /   |                        |   |  |               |  \      p
+//    /    |                        |   |  |               |   \     e
+//   +-----+------------------------+---+--+---------------+----+    e
+//   |               BLOCK 1            |      BLOCK 2          |    d
+//
+//                           time ----->
+// 
+//  The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates 
+//  first block->accelerate_until step_events_completed, then keeps going at constant speed until 
+//  step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
+//  The slope of acceleration is calculated with the leib ramp alghorithm.
+
+void st_wake_up() {
+  //  TCNT1 = 0;
+  ENABLE_STEPPER_DRIVER_INTERRUPT();  
+}
+
+inline unsigned short calc_timer(unsigned short step_rate) {
+  unsigned short timer;
+  if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY;
+  
+  if(step_rate > 20000) { // If steprate > 20kHz >> step 4 times
+    step_rate = step_rate >> 2;
+    step_loops = 4;
+  }
+  else if(step_rate > 10000) { // If steprate > 10kHz >> step 2 times
+    step_rate = step_rate >> 1;
+    step_loops = 2;
+  }
+  else {
+    step_loops = 1;
+  } 
+  
+  if(step_rate < 32) step_rate = 32;
+  step_rate -= 32; // Correct for minimal speed
+  if(step_rate >= (8*256)){ // higher step rate 
+    unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
+    unsigned char tmp_step_rate = (step_rate & 0x00ff);
+    unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
+    MultiU16X8toH16(timer, tmp_step_rate, gain);
+    timer = (unsigned short)pgm_read_word_near(table_address) - timer;
+  }
+  else { // lower step rates
+    unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
+    table_address += ((step_rate)>>1) & 0xfffc;
+    timer = (unsigned short)pgm_read_word_near(table_address);
+    timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
+  }
+  if(timer < 100) timer = 100;
+  return timer;
+}
+
+// Initializes the trapezoid generator from the current block. Called whenever a new 
+// block begins.
+inline void trapezoid_generator_reset() {
+#ifdef ADVANCE
+  advance = current_block->initial_advance;
+  final_advance = current_block->final_advance;
+#endif
+  deceleration_time = 0;
+  // advance_rate = current_block->advance_rate;
+  // step_rate to timer interval
+  acc_step_rate = current_block->initial_rate;
+  acceleration_time = calc_timer(acc_step_rate);
+  OCR1A = acceleration_time;
+}
+
+// "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.  
+// It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. 
+ISR(TIMER1_COMPA_vect)
+{        
+  if(busy){ Serial.print(*(unsigned short *)OCR1A); Serial.println(" BUSY");
+    return; 
+  } // The busy-flag is used to avoid reentering this interrupt
+
+  busy = true;
+  sei(); // Re enable interrupts (normally disabled while inside an interrupt handler)
+
+  // If there is no current block, attempt to pop one from the buffer
+  if (current_block == NULL) {
+    // Anything in the buffer?
+    current_block = plan_get_current_block();
+    if (current_block != NULL) {
+      trapezoid_generator_reset();
+      counter_x = -(current_block->step_event_count >> 1);
+      counter_y = counter_x;
+      counter_z = counter_x;
+      counter_e = counter_x;
+      step_events_completed = 0;
+      #ifdef ADVANCE
+      e_steps = 0;
+      #endif
+    } 
+    else {
+//      DISABLE_STEPPER_DRIVER_INTERRUPT();
+    }    
+  } 
+
+  if (current_block != NULL) {
+    // Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
+    out_bits = current_block->direction_bits;
+
+#ifdef ADVANCE
+    // Calculate E early.
+    counter_e += current_block->steps_e;
+    if (counter_e > 0) {
+      counter_e -= current_block->step_event_count;
+      if ((out_bits & (1<<E_AXIS)) != 0) { // - direction
+        CRITICAL_SECTION_START;
+        e_steps--;
+        CRITICAL_SECTION_END;
+      }
+      else {
+        CRITICAL_SECTION_START;
+        e_steps++;
+        CRITICAL_SECTION_END;
+      }
+    }    
+    // Do E steps + advance steps
+    CRITICAL_SECTION_START;
+    e_steps += ((advance >> 16) - old_advance);
+    CRITICAL_SECTION_END;
+    old_advance = advance >> 16;  
+#endif //ADVANCE
+
+    // Set direction en check limit switches
+if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
+      WRITE(X_DIR_PIN, INVERT_X_DIR);
+      #ifdef DEBUG_STEPS
+      count_direction[X_AXIS]=-1;
+      #endif
+#if X_MIN_PIN > -1
+      if(READ(X_MIN_PIN) != ENDSTOPS_INVERTING) {
+        step_events_completed = current_block->step_event_count;
+      }
+#endif
+    }
+    else { // +direction 
+        WRITE(X_DIR_PIN,!INVERT_X_DIR);
+        #ifdef DEBUG_STEPS
+        count_direction[X_AXIS]=1;
+        #endif
+#if X_MAX_PIN > -1
+        if((READ(X_MAX_PIN) != ENDSTOPS_INVERTING)  && (current_block->steps_x >0)){
+          step_events_completed = current_block->step_event_count;
+        }
+#endif
+    }
+
+    if ((out_bits & (1<<Y_AXIS)) != 0) {   // -direction
+      WRITE(Y_DIR_PIN,INVERT_Y_DIR);
+      #ifdef DEBUG_STEPS
+      count_direction[Y_AXIS]=-1;
+      #endif
+#if Y_MIN_PIN > -1
+      if(READ(Y_MIN_PIN) != ENDSTOPS_INVERTING) {
+        step_events_completed = current_block->step_event_count;
+      }
+#endif
+    }
+    else { // +direction
+    WRITE(Y_DIR_PIN,!INVERT_Y_DIR);
+      #ifdef DEBUG_STEPS
+      count_direction[Y_AXIS]=1;
+      #endif
+#if Y_MAX_PIN > -1
+    if((READ(Y_MAX_PIN) != ENDSTOPS_INVERTING) && (current_block->steps_y >0)){
+        step_events_completed = current_block->step_event_count;
+      }
+#endif
+    }
+
+    if ((out_bits & (1<<Z_AXIS)) != 0) {   // -direction
+      WRITE(Z_DIR_PIN,INVERT_Z_DIR);
+      #ifdef DEBUG_STEPS
+      count_direction[Z_AXIS]=-1;
+      #endif
+#if Z_MIN_PIN > -1
+      if(READ(Z_MIN_PIN) != ENDSTOPS_INVERTING) {
+        step_events_completed = current_block->step_event_count;
+      }
+#endif
+    }
+    else { // +direction
+        WRITE(Z_DIR_PIN,!INVERT_Z_DIR);
+        #ifdef DEBUG_STEPS
+        count_direction[Z_AXIS]=1;
+        #endif
+#if Z_MAX_PIN > -1
+        if((READ(Z_MAX_PIN) != ENDSTOPS_INVERTING)  && (current_block->steps_z >0)){
+          step_events_completed = current_block->step_event_count;
+        }
+#endif
+    }
+
+#ifndef ADVANCE
+    if ((out_bits & (1<<E_AXIS)) != 0)   // -direction
+      WRITE(E_DIR_PIN,INVERT_E_DIR);
+    else // +direction
+      WRITE(E_DIR_PIN,!INVERT_E_DIR);
+#endif //!ADVANCE
+
+    for(char i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves) 
+      counter_x += current_block->steps_x;
+      if (counter_x > 0) {
+        WRITE(X_STEP_PIN, HIGH);
+        counter_x -= current_block->step_event_count;
+        WRITE(X_STEP_PIN, LOW);
+        #ifdef DEBUG_STEPS
+        count_position[X_AXIS]+=count_direction[X_AXIS];   
+        #endif
+      }
+
+      counter_y += current_block->steps_y;
+      if (counter_y > 0) {
+        WRITE(Y_STEP_PIN, HIGH);
+        counter_y -= current_block->step_event_count;
+        WRITE(Y_STEP_PIN, LOW);
+        #ifdef DEBUG_STEPS
+        count_position[Y_AXIS]+=count_direction[Y_AXIS];
+        #endif
+      }
+
+      counter_z += current_block->steps_z;
+      if (counter_z > 0) {
+        WRITE(Z_STEP_PIN, HIGH);
+        counter_z -= current_block->step_event_count;
+        WRITE(Z_STEP_PIN, LOW);
+        #ifdef DEBUG_STEPS
+        count_position[Z_AXIS]+=count_direction[Z_AXIS];
+        #endif
+      }
+
+#ifndef ADVANCE
+      counter_e += current_block->steps_e;
+      if (counter_e > 0) {
+        WRITE(E_STEP_PIN, HIGH);
+        counter_e -= current_block->step_event_count;
+        WRITE(E_STEP_PIN, LOW);
+      }
+#endif //!ADVANCE
+      step_events_completed += 1;  
+      if(step_events_completed >= current_block->step_event_count) break;
+    }
+    // Calculare new timer value
+    unsigned short timer;
+    unsigned short step_rate;
+    if (step_events_completed <= current_block->accelerate_until) {
+      MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
+      acc_step_rate += current_block->initial_rate;
+      
+      // upper limit
+      if(acc_step_rate > current_block->nominal_rate)
+        acc_step_rate = current_block->nominal_rate;
+
+      // step_rate to timer interval
+      timer = calc_timer(acc_step_rate);
+#ifdef ADVANCE
+      advance += advance_rate;
+#endif
+      acceleration_time += timer;
+      OCR1A = timer;
+    } 
+    else if (step_events_completed > current_block->decelerate_after) {   
+      MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
+      
+      if(step_rate > acc_step_rate) { // Check step_rate stays positive
+        step_rate = current_block->final_rate;
+      }
+      else {
+        step_rate = acc_step_rate - step_rate; // Decelerate from aceleration end point.
+      }
+
+      // lower limit
+      if(step_rate < current_block->final_rate)
+        step_rate = current_block->final_rate;
+
+      // step_rate to timer interval
+      timer = calc_timer(step_rate);
+#ifdef ADVANCE
+      advance -= advance_rate;
+      if(advance < final_advance)
+        advance = final_advance;
+#endif //ADVANCE
+      deceleration_time += timer;
+      OCR1A = timer;
+    }       
+    // If current block is finished, reset pointer 
+    if (step_events_completed >= current_block->step_event_count) {
+      current_block = NULL;
+      plan_discard_current_block();
+    }   
+  } 
+  cli(); // disable interrupts
+  busy=false;
+}
+
+#ifdef ADVANCE
+
+unsigned char old_OCR0A;
+// Timer interrupt for E. e_steps is set in the main routine;
+// Timer 0 is shared with millies
+ISR(TIMER0_COMPA_vect)
+{
+  // Critical section needed because Timer 1 interrupt has higher priority. 
+  // The pin set functions are placed on trategic position to comply with the stepper driver timing.
+  WRITE(E_STEP_PIN, LOW);
+  // Set E direction (Depends on E direction + advance)
+  if (e_steps < 0) {
+    WRITE(E_DIR_PIN,INVERT_E_DIR);    
+    e_steps++;
+    WRITE(E_STEP_PIN, HIGH);
+  } 
+  if (e_steps > 0) {
+    WRITE(E_DIR_PIN,!INVERT_E_DIR);
+    e_steps--;
+    WRITE(E_STEP_PIN, HIGH);
+  }
+  old_OCR0A += 25; // 10kHz interrupt
+  OCR0A = old_OCR0A;
+}
+#endif // ADVANCE
+
+void st_init()
+{
+    //Initialize Dir Pins
+#if X_DIR_PIN > -1
+  SET_OUTPUT(X_DIR_PIN);
+#endif
+#if Y_DIR_PIN > -1 
+  SET_OUTPUT(Y_DIR_PIN);
+#endif
+#if Z_DIR_PIN > -1 
+  SET_OUTPUT(Z_DIR_PIN);
+#endif
+#if E_DIR_PIN > -1 
+  SET_OUTPUT(E_DIR_PIN);
+#endif
+
+  //Initialize Enable Pins - steppers default to disabled.
+
+#if (X_ENABLE_PIN > -1)
+  SET_OUTPUT(X_ENABLE_PIN);
+  if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
+#endif
+#if (Y_ENABLE_PIN > -1)
+  SET_OUTPUT(Y_ENABLE_PIN);
+  if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
+#endif
+#if (Z_ENABLE_PIN > -1)
+  SET_OUTPUT(Z_ENABLE_PIN);
+  if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
+#endif
+#if (E_ENABLE_PIN > -1)
+  SET_OUTPUT(E_ENABLE_PIN);
+  if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH);
+#endif
+
+  //endstops and pullups
+#ifdef ENDSTOPPULLUPS
+#if X_MIN_PIN > -1
+  SET_INPUT(X_MIN_PIN); 
+  WRITE(X_MIN_PIN,HIGH);
+#endif
+#if X_MAX_PIN > -1
+  SET_INPUT(X_MAX_PIN); 
+  WRITE(X_MAX_PIN,HIGH);
+#endif
+#if Y_MIN_PIN > -1
+  SET_INPUT(Y_MIN_PIN); 
+  WRITE(Y_MIN_PIN,HIGH);
+#endif
+#if Y_MAX_PIN > -1
+  SET_INPUT(Y_MAX_PIN); 
+  WRITE(Y_MAX_PIN,HIGH);
+#endif
+#if Z_MIN_PIN > -1
+  SET_INPUT(Z_MIN_PIN); 
+  WRITE(Z_MIN_PIN,HIGH);
+#endif
+#if Z_MAX_PIN > -1
+  SET_INPUT(Z_MAX_PIN); 
+  WRITE(Z_MAX_PIN,HIGH);
+#endif
+#else //ENDSTOPPULLUPS
+#if X_MIN_PIN > -1
+  SET_INPUT(X_MIN_PIN); 
+#endif
+#if X_MAX_PIN > -1
+  SET_INPUT(X_MAX_PIN); 
+#endif
+#if Y_MIN_PIN > -1
+  SET_INPUT(Y_MIN_PIN); 
+#endif
+#if Y_MAX_PIN > -1
+  SET_INPUT(Y_MAX_PIN); 
+#endif
+#if Z_MIN_PIN > -1
+  SET_INPUT(Z_MIN_PIN); 
+#endif
+#if Z_MAX_PIN > -1
+  SET_INPUT(Z_MAX_PIN); 
+#endif
+#endif //ENDSTOPPULLUPS
+
+  //Initialize Step Pins
+#if (X_STEP_PIN > -1) 
+  SET_OUTPUT(X_STEP_PIN);
+#endif  
+#if (Y_STEP_PIN > -1) 
+  SET_OUTPUT(Y_STEP_PIN);
+#endif  
+#if (Z_STEP_PIN > -1) 
+  SET_OUTPUT(Z_STEP_PIN);
+#endif  
+#if (E_STEP_PIN > -1) 
+  SET_OUTPUT(E_STEP_PIN);
+#endif  
+
+  // waveform generation = 0100 = CTC
+  TCCR1B &= ~(1<<WGM13);
+  TCCR1B |=  (1<<WGM12);
+  TCCR1A &= ~(1<<WGM11); 
+  TCCR1A &= ~(1<<WGM10);
+
+  // output mode = 00 (disconnected)
+  TCCR1A &= ~(3<<COM1A0); 
+  TCCR1A &= ~(3<<COM1B0); 
+  TCCR1B = (TCCR1B & ~(0x07<<CS10)) | (2<<CS10); // 2MHz timer
+
+  OCR1A = 0x4000;
+  DISABLE_STEPPER_DRIVER_INTERRUPT();  
+
+#ifdef ADVANCE
+  e_steps = 0;
+  TIMSK0 |= (1<<OCIE0A);
+#endif //ADVANCE
+  sei();
+}
+
+// Block until all buffered steps are executed
+void st_synchronize()
+{
+  while(plan_get_current_block()) {
+    manage_heater();
+    manage_inactivity(1);
+    LCD_STATUS;
+  }   
+}
diff --git a/Marlin/stepper.h b/Marlin/stepper.h
new file mode 100644 (file)
index 0000000..1ed4a0e
--- /dev/null
@@ -0,0 +1,40 @@
+/*
+  stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
+  Part of Grbl
+
+  Copyright (c) 2009-2011 Simen Svale Skogsrud
+
+  Grbl 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.
+
+  Grbl 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 Grbl.  If not, see <http://www.gnu.org/licenses/>.
+*/
+
+#ifndef stepper_h
+#define stepper_h 
+// Initialize and start the stepper motor subsystem
+void st_init();
+
+// Block until all buffered steps are executed
+void st_synchronize();
+
+// The stepper subsystem goes to sleep when it runs out of things to execute. Call this
+// to notify the subsystem that it is time to go to work.
+void st_wake_up();
+
+// if DEBUG_STEPS is enabled, M114 can be used to compare two methods of determining the X,Y,Z position of the printer.
+// for debugging purposes only, should be disabled by default
+#ifdef DEBUG_STEPS
+extern volatile long count_position[NUM_AXIS];
+extern volatile int count_direction[NUM_AXIS];
+#endif
+
+#endif
diff --git a/Marlin/streaming.h b/Marlin/streaming.h
new file mode 100644 (file)
index 0000000..2abf64f
--- /dev/null
@@ -0,0 +1,84 @@
+/*
+Streaming.h - Arduino library for supporting the << streaming operator
+Copyright (c) 2010 Mikal Hart.  All rights 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
+*/
+
+#ifndef ARDUINO_STREAMING
+#define ARDUINO_STREAMING
+
+//#include <WProgram.h>
+
+#define STREAMING_LIBRARY_VERSION 4
+
+// Generic template
+template<class T> 
+inline Print &operator <<(Print &stream, T arg) 
+{ stream.print(arg); return stream; }
+
+struct _BASED 
+{ 
+  long val; 
+  int base;
+  _BASED(long v, int b): val(v), base(b) 
+  {}
+};
+
+#define _HEX(a)     _BASED(a, HEX)
+#define _DEC(a)     _BASED(a, DEC)
+#define _OCT(a)     _BASED(a, OCT)
+#define _BIN(a)     _BASED(a, BIN)
+#define _BYTE(a)    _BASED(a, BYTE)
+
+// Specialization for class _BASED
+// Thanks to Arduino forum user Ben Combee who suggested this 
+// clever technique to allow for expressions like
+//   Serial << _HEX(a);
+
+inline Print &operator <<(Print &obj, const _BASED &arg)
+{ obj.print(arg.val, arg.base); return obj; } 
+
+#if ARDUINO >= 18
+// Specialization for class _FLOAT
+// Thanks to Michael Margolis for suggesting a way
+// to accommodate Arduino 0018's floating point precision
+// feature like this:
+//   Serial << _FLOAT(gps_latitude, 6); // 6 digits of precision
+
+struct _FLOAT
+{
+  float val;
+  int digits;
+  _FLOAT(double v, int d): val(v), digits(d)
+  {}
+};
+
+inline Print &operator <<(Print &obj, const _FLOAT &arg)
+{ obj.print(arg.val, arg.digits); return obj; }
+#endif
+
+// Specialization for enum _EndLineCode
+// Thanks to Arduino forum user Paul V. who suggested this
+// clever technique to allow for expressions like
+//   Serial << "Hello!" << endl;
+
+enum _EndLineCode { endl };
+
+inline Print &operator <<(Print &obj, _EndLineCode arg) 
+{ obj.println(); return obj; }
+
+#endif
+
diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp
new file mode 100644 (file)
index 0000000..248b807
--- /dev/null
@@ -0,0 +1,476 @@
+/*
+  temperature.c - temperature control
+  Part of Marlin
+  
+ Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+ This program 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 this program.  If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/*
+ This firmware is a mashup between Sprinter and grbl.
+  (https://github.com/kliment/Sprinter)
+  (https://github.com/simen/grbl/tree)
+ It has preliminary support for Matthew Roberts advance algorithm 
+    http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
+
+ This firmware is optimized for gen6 electronics.
+ */
+
+#include "fastio.h"
+#include "Configuration.h"
+#include "pins.h"
+#include "Marlin.h"
+#include "ultralcd.h"
+#include "streaming.h"
+#include "temperature.h"
+
+int target_bed_raw = 0;
+int current_bed_raw = 0;
+
+int target_raw[3] = {0, 0, 0};
+int current_raw[3] = {0, 0, 0};
+unsigned char temp_meas_ready = false;
+
+unsigned long previous_millis_heater, previous_millis_bed_heater;
+
+#ifdef PIDTEMP
+  double temp_iState = 0;
+  double temp_dState = 0;
+  double pTerm;
+  double iTerm;
+  double dTerm;
+      //int output;
+  double pid_error;
+  double temp_iState_min;
+  double temp_iState_max;
+  double pid_setpoint = 0.0;
+  double pid_input;
+  double pid_output;
+  bool pid_reset;
+  float HeaterPower;
+  
+  float Kp=DEFAULT_Kp;
+  float Ki=DEFAULT_Ki;
+  float Kd=DEFAULT_Kd;
+  float Kc=DEFAULT_Kc;
+#endif //PIDTEMP
+
+#ifdef MINTEMP
+int minttemp = temp2analog(MINTEMP);
+#endif //MINTEMP
+#ifdef MAXTEMP
+int maxttemp = temp2analog(MAXTEMP);
+#endif //MAXTEMP
+
+#ifdef BED_MINTEMP
+int bed_minttemp = temp2analog(BED_MINTEMP);
+#endif //BED_MINTEMP
+#ifdef BED_MAXTEMP
+int bed_maxttemp = temp2analog(BED_MAXTEMP);
+#endif //BED_MAXTEMP
+
+void manage_heater()
+{
+#ifdef USE_WATCHDOG
+  wd_reset();
+#endif
+  
+  float pid_input;
+  float pid_output;
+  if(temp_meas_ready == true) {
+
+CRITICAL_SECTION_START;
+    temp_meas_ready = false;
+CRITICAL_SECTION_END;
+
+#ifdef PIDTEMP
+    pid_input = analog2temp(current_raw[0]);
+
+#ifndef PID_OPENLOOP
+    pid_error = pid_setpoint - pid_input;
+    if(pid_error > 10){
+      pid_output = PID_MAX;
+      pid_reset = true;
+    }
+    else if(pid_error < -10) {
+      pid_output = 0;
+      pid_reset = true;
+    }
+    else {
+      if(pid_reset == true) {
+        temp_iState = 0.0;
+        pid_reset = false;
+      }
+      pTerm = Kp * pid_error;
+      temp_iState += pid_error;
+      temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max);
+      iTerm = Ki * temp_iState;
+      #define K1 0.95
+      #define K2 (1.0-K1)
+      dTerm = (Kd * (pid_input - temp_dState))*K2 + (K1 * dTerm);
+      temp_dState = pid_input;
+      pid_output = constrain(pTerm + iTerm - dTerm, 0, PID_MAX);
+    }
+#endif //PID_OPENLOOP
+#ifdef PID_DEBUG
+     Serial.print(" Input ");
+     Serial.print(pid_input);
+     Serial.print(" Output ");
+     Serial.print(pid_output);    
+     Serial.print(" pTerm ");
+     Serial.print(pTerm); 
+     Serial.print(" iTerm ");
+     Serial.print(iTerm); 
+     Serial.print(" dTerm ");
+     Serial.print(dTerm); 
+     Serial.println();
+#endif //PID_DEBUG
+    analogWrite(HEATER_0_PIN, pid_output);
+#endif //PIDTEMP
+
+#ifndef PIDTEMP
+    if(current_raw[0] >= target_raw[0])
+    {
+      WRITE(HEATER_0_PIN,LOW);
+    }
+    else 
+    {
+      WRITE(HEATER_0_PIN,HIGH);
+    }
+#endif
+    
+  if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
+    return;
+  previous_millis_bed_heater = millis();
+  
+  #if TEMP_1_PIN > -1
+    if(current_raw[1] >= target_raw[1])
+    {
+      WRITE(HEATER_1_PIN,LOW);
+    }
+    else 
+    {
+      WRITE(HEATER_1_PIN,HIGH);
+    }
+  #endif
+  }
+}
+
+// Takes hot end temperature value as input and returns corresponding raw value. 
+// For a thermistor, it uses the RepRap thermistor temp table.
+// This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
+// This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
+float temp2analog(int celsius) {
+  #ifdef HEATER_USES_THERMISTOR
+    int raw = 0;
+    byte i;
+    
+    for (i=1; i<NUMTEMPS; i++)
+    {
+      if (temptable[i][1] < celsius)
+      {
+        raw = temptable[i-1][0] + 
+          (celsius - temptable[i-1][1]) * 
+          (temptable[i][0] - temptable[i-1][0]) /
+          (temptable[i][1] - temptable[i-1][1]);
+      
+        break;
+      }
+    }
+
+    // Overflow: Set to last value in the table
+    if (i == NUMTEMPS) raw = temptable[i-1][0];
+
+    return (1023 * OVERSAMPLENR) - raw;
+  #elif defined HEATER_USES_AD595
+    return celsius * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
+  #endif
+}
+
+// Takes bed temperature value as input and returns corresponding raw value. 
+// For a thermistor, it uses the RepRap thermistor temp table.
+// This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
+// This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
+float temp2analogBed(int celsius) {
+  #ifdef BED_USES_THERMISTOR
+
+    int raw = 0;
+    byte i;
+    
+    for (i=1; i<BNUMTEMPS; i++)
+    {
+      if (bedtemptable[i][1] < celsius)
+      {
+        raw = bedtemptable[i-1][0] + 
+          (celsius - bedtemptable[i-1][1]) * 
+          (bedtemptable[i][0] - bedtemptable[i-1][0]) /
+          (bedtemptable[i][1] - bedtemptable[i-1][1]);
+      
+        break;
+      }
+    }
+
+    // Overflow: Set to last value in the table
+    if (i == BNUMTEMPS) raw = bedtemptable[i-1][0];
+
+    return (1023 * OVERSAMPLENR) - raw;
+  #elif defined BED_USES_AD595
+    return celsius * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
+  #endif
+}
+
+// Derived from RepRap FiveD extruder::getTemperature()
+// For hot end temperature measurement.
+float analog2temp(int raw) {
+  #ifdef HEATER_USES_THERMISTOR
+    int celsius = 0;
+    byte i;  
+    raw = (1023 * OVERSAMPLENR) - raw;
+    for (i=1; i<NUMTEMPS; i++)
+    {
+      if (temptable[i][0] > raw)
+      {
+        celsius  = temptable[i-1][1] + 
+          (raw - temptable[i-1][0]) * 
+          (temptable[i][1] - temptable[i-1][1]) /
+          (temptable[i][0] - temptable[i-1][0]);
+
+        break;
+      }
+    }
+
+    // Overflow: Set to last value in the table
+    if (i == NUMTEMPS) celsius = temptable[i-1][1];
+
+    return celsius;
+  #elif defined HEATER_USES_AD595
+    return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
+  #endif
+}
+
+// Derived from RepRap FiveD extruder::getTemperature()
+// For bed temperature measurement.
+float analog2tempBed(int raw) {
+  #ifdef BED_USES_THERMISTOR
+    int celsius = 0;
+    byte i;
+
+    raw = (1023 * OVERSAMPLENR) - raw;
+
+    for (i=1; i<NUMTEMPS; i++)
+    {
+      if (bedtemptable[i][0] > raw)
+      {
+        celsius  = bedtemptable[i-1][1] + 
+          (raw - bedtemptable[i-1][0]) * 
+          (bedtemptable[i][1] - bedtemptable[i-1][1]) /
+          (bedtemptable[i][0] - bedtemptable[i-1][0]);
+
+        break;
+      }
+    }
+
+    // Overflow: Set to last value in the table
+    if (i == NUMTEMPS) celsius = bedtemptable[i-1][1];
+
+    return celsius;
+    
+  #elif defined BED_USES_AD595
+    return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
+  #endif
+}
+
+void tp_init()
+{
+#if (HEATER_0_PIN > -1) 
+  SET_OUTPUT(HEATER_0_PIN);
+#endif  
+#if (HEATER_1_PIN > -1) 
+  SET_OUTPUT(HEATER_1_PIN);
+#endif  
+#if (HEATER_2_PIN > -1) 
+  SET_OUTPUT(HEATER_2_PIN);
+#endif  
+
+#ifdef PIDTEMP
+  temp_iState_min = 0.0;
+  temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
+#endif //PIDTEMP
+
+// Set analog inputs
+  ADCSRA = 1<<ADEN | 1<<ADSC | 1<<ADIF | 0x07;
+  
+// Use timer0 for temperature measurement
+// Interleave temperature interrupt with millies interrupt
+  OCR0B = 128;
+  TIMSK0 |= (1<<OCIE0B);  
+}
+
+static unsigned char temp_count = 0;
+static unsigned long raw_temp_0_value = 0;
+static unsigned long raw_temp_1_value = 0;
+static unsigned long raw_temp_2_value = 0;
+static unsigned char temp_state = 0;
+
+// Timer 0 is shared with millies
+ISR(TIMER0_COMPB_vect)
+{
+  switch(temp_state) {
+    case 0: // Prepare TEMP_0
+            #if (TEMP_0_PIN > -1)
+              #if TEMP_0_PIN < 8
+                DIDR0 = 1 << TEMP_0_PIN; 
+              #else
+                DIDR2 = 1<<(TEMP_0_PIN - 8); 
+                ADCSRB = 1<<MUX5;
+              #endif
+              ADMUX = ((1 << REFS0) | (TEMP_0_PIN & 0x07));
+              ADCSRA |= 1<<ADSC; // Start conversion
+            #endif
+            #ifdef ULTIPANEL
+              buttons_check();
+            #endif
+            temp_state = 1;
+            break;
+    case 1: // Measure TEMP_0
+            #if (TEMP_0_PIN > -1)
+              raw_temp_0_value += ADC;
+            #endif
+            temp_state = 2;
+            break;
+    case 2: // Prepare TEMP_1
+            #if (TEMP_1_PIN > -1)
+              #if TEMP_1_PIN < 7
+                DIDR0 = 1<<TEMP_1_PIN; 
+              #else
+                DIDR2 = 1<<(TEMP_1_PIN - 8); 
+                ADCSRB = 1<<MUX5;
+              #endif
+              ADMUX = ((1 << REFS0) | (TEMP_1_PIN & 0x07));
+              ADCSRA |= 1<<ADSC; // Start conversion
+            #endif
+            #ifdef ULTIPANEL
+              buttons_check();
+            #endif
+            temp_state = 3;
+            break;
+    case 3: // Measure TEMP_1
+            #if (TEMP_1_PIN > -1)
+              raw_temp_1_value += ADC;
+            #endif
+            temp_state = 4;
+            break;
+    case 4: // Prepare TEMP_2
+            #if (TEMP_2_PIN > -1)
+              #if TEMP_2_PIN < 7
+                DIDR0 = 1 << TEMP_2_PIN; 
+              #else
+                DIDR2 = 1<<(TEMP_2_PIN - 8); 
+                ADCSRB = 1<<MUX5;
+              #endif
+              ADMUX = ((1 << REFS0) | (TEMP_2_PIN & 0x07));
+              ADCSRA |= 1<<ADSC; // Start conversion
+            #endif
+            #ifdef ULTIPANEL
+              buttons_check();
+            #endif
+            temp_state = 5;
+            break;
+    case 5: // Measure TEMP_2
+            #if (TEMP_2_PIN > -1)
+              raw_temp_2_value += ADC;
+            #endif
+            temp_state = 0;
+            temp_count++;
+            break;
+    default:
+            Serial.println("!! Temp measurement error !!");
+            break;
+  }
+    
+  if(temp_count >= 16) // 6 ms * 16 = 96ms.
+  {
+    #ifdef HEATER_USES_AD595
+      current_raw[0] = raw_temp_0_value;
+      current_raw[2] = raw_temp_2_value;
+    #else
+      current_raw[0] = 16383 - raw_temp_0_value;
+      current_raw[2] = 16383 - raw_temp_2_value;
+    #endif
+    
+    #ifdef BED_USES_AD595
+      current_raw[1] = raw_temp_1_value;
+    #else
+      current_raw[1] = 16383 - raw_temp_1_value;
+    #endif
+    
+    temp_meas_ready = true;
+    temp_count = 0;
+    raw_temp_0_value = 0;
+    raw_temp_1_value = 0;
+    raw_temp_2_value = 0;
+#ifdef MAXTEMP
+  #if (HEATER_0_PIN > -1)
+    if(current_raw[0] >= maxttemp) {
+      target_raw[0] = 0;
+      analogWrite(HEATER_0_PIN, 0);
+      Serial.println("!! Temperature extruder 0 switched off. MAXTEMP triggered !!");
+    }
+  #endif
+  #if (HEATER_2_PIN > -1)
+    if(current_raw[2] >= maxttemp) {
+      target_raw[2] = 0;
+      analogWrite(HEATER_2_PIN, 0);
+      Serial.println("!! Temperature extruder 1 switched off. MAXTEMP triggered !!");
+    }
+  #endif
+#endif //MAXTEMP
+#ifdef MINTEMP
+  #if (HEATER_0_PIN > -1)
+    if(current_raw[0] <= minttemp) {
+      target_raw[0] = 0;
+      analogWrite(HEATER_0_PIN, 0);
+      Serial.println("!! Temperature extruder 0 switched off. MINTEMP triggered !!");
+    }
+  #endif
+  #if (HEATER_2_PIN > -1)
+    if(current_raw[2] <= minttemp) {
+      target_raw[2] = 0;
+      analogWrite(HEATER_2_PIN, 0);
+      Serial.println("!! Temperature extruder 1 switched off. MINTEMP triggered !!");
+    }
+  #endif
+#endif //MAXTEMP
+#ifdef BED_MINTEMP
+  #if (HEATER_1_PIN > -1)
+    if(current_raw[1] <= bed_minttemp) {
+      target_raw[1] = 0;
+      WRITE(HEATER_1_PIN, 0);
+      Serial.println("!! Temperatur heated bed switched off. MINTEMP triggered !!");
+    }
+  #endif
+#endif
+#ifdef BED_MAXTEMP
+  #if (HEATER_1_PIN > -1)
+    if(current_raw[1] >= bed_maxttemp) {
+      target_raw[1] = 0;
+      WRITE(HEATER_1_PIN, 0);
+      Serial.println("!! Temperature heated bed switched off. MAXTEMP triggered !!");
+    }
+  #endif
+#endif
+  }
+}
diff --git a/Marlin/temperature.h b/Marlin/temperature.h
new file mode 100644 (file)
index 0000000..986aca9
--- /dev/null
@@ -0,0 +1,55 @@
+/*
+  temperature.h - temperature controller
+  Part of Marlin
+
+  Copyright (c) 2011 Erik van der Zalm
+
+  Grbl 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.
+
+  Grbl 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 Grbl.  If not, see <http://www.gnu.org/licenses/>.
+*/
+
+#ifndef temperature_h
+#define temperature_h 
+
+void manage_inactivity(byte debug);
+
+void tp_init();
+void manage_heater();
+//int temp2analogu(int celsius, const short table[][2], int numtemps);
+//float analog2tempu(int raw, const short table[][2], int numtemps);
+float temp2analog(int celsius);
+float temp2analogBed(int celsius);
+float analog2temp(int raw);
+float analog2tempBed(int raw);
+
+#ifdef HEATER_USES_THERMISTOR
+    #define HEATERSOURCE 1
+#endif
+#ifdef BED_USES_THERMISTOR
+    #define BEDSOURCE 1
+#endif
+
+//#define temp2analogh( c ) temp2analogu((c),temptable,NUMTEMPS)
+//#define analog2temp( c ) analog2tempu((c),temptable,NUMTEMPS
+
+
+extern float Kp;
+extern float Ki;
+extern float Kd;
+extern float Kc;
+
+extern int target_raw[3];
+extern int current_raw[3];
+extern double pid_setpoint;
+
+#endif
index 1c780020b02e17a234e9f224028d1af07ab1b95f..725e972fa11ecc38528988adca202b8b41f684ce 100644 (file)
 #ifndef THERMISTORTABLES_H_
 #define THERMISTORTABLES_H_
 
+#define OVERSAMPLENR 16
 #if (THERMISTORHEATER == 1) || (THERMISTORBED == 1) //100k bed thermistor
 
 
 #define NUMTEMPS_1 61
 const short temptable_1[NUMTEMPS_1][2] = {
-{      (23*16) ,       300     },
-{      (25*16) ,       295     },
-{      (27*16) ,       290     },
-{      (28*16) ,       285     },
-{      (31*16) ,       280     },
-{      (33*16) ,       275     },
-{      (35*16) ,       270     },
-{      (38*16) ,       265     },
-{      (41*16) ,       260     },
-{      (44*16) ,       255     },
-{      (48*16) ,       250     },
-{      (52*16) ,       245     },
-{      (56*16) ,       240     },
-{      (61*16) ,       235     },
-{      (66*16) ,       230     },
-{      (71*16) ,       225     },
-{      (78*16) ,       220     },
-{      (84*16) ,       215     },
-{      (92*16) ,       210     },
-{      (100*16),       205     },
-{      (109*16),       200     },
-{      (120*16),       195     },
-{      (131*16),       190     },
-{      (143*16),       185     },
-{      (156*16),       180     },
-{      (171*16),       175     },
-{      (187*16),       170     },
-{      (205*16),       165     },
-{      (224*16),       160     },
-{      (245*16),       155     },
-{      (268*16),       150     },
-{      (293*16),       145     },
-{      (320*16),       140     },
-{      (348*16),       135     },
-{      (379*16),       130     },
-{      (411*16),       125     },
-{      (445*16),       120     },
-{      (480*16),       115     },
-{      (516*16),       110     },
-{      (553*16),       105     },
-{      (591*16),       100     },
-{      (628*16),       95      },
-{      (665*16),       90      },
-{      (702*16),       85      },
-{      (737*16),       80      },
-{      (770*16),       75      },
-{      (801*16),       70      },
-{      (830*16),       65      },
-{      (857*16),       60      },
-{      (881*16),       55      },
-{      (903*16),       50      },
-{      (922*16),       45      },
-{      (939*16),       40      },
-{      (954*16),       35      },
-{      (966*16),       30      },
-{      (977*16),       25      },
-{      (985*16),       20      },
-{      (993*16),       15      },
-{      (999*16),       10      },
-{      (1004*16),      5       },
-{      (1008*16),      0       } //safety
+{      (23*OVERSAMPLENR)       ,       300     },
+{      (25*OVERSAMPLENR)       ,       295     },
+{      (27*OVERSAMPLENR)       ,       290     },
+{      (28*OVERSAMPLENR)       ,       285     },
+{      (31*OVERSAMPLENR)       ,       280     },
+{      (33*OVERSAMPLENR)       ,       275     },
+{      (35*OVERSAMPLENR)       ,       270     },
+{      (38*OVERSAMPLENR)       ,       265     },
+{      (41*OVERSAMPLENR)       ,       260     },
+{      (44*OVERSAMPLENR)       ,       255     },
+{      (48*OVERSAMPLENR)       ,       250     },
+{      (52*OVERSAMPLENR)       ,       245     },
+{      (56*OVERSAMPLENR)       ,       240     },
+{      (61*OVERSAMPLENR)       ,       235     },
+{      (66*OVERSAMPLENR)       ,       230     },
+{      (71*OVERSAMPLENR)       ,       225     },
+{      (78*OVERSAMPLENR)       ,       220     },
+{      (84*OVERSAMPLENR)       ,       215     },
+{      (92*OVERSAMPLENR)       ,       210     },
+{      (100*OVERSAMPLENR),     205     },
+{      (109*OVERSAMPLENR),     200     },
+{      (120*OVERSAMPLENR),     195     },
+{      (131*OVERSAMPLENR),     190     },
+{      (143*OVERSAMPLENR),     185     },
+{      (156*OVERSAMPLENR),     180     },
+{      (171*OVERSAMPLENR),     175     },
+{      (187*OVERSAMPLENR),     170     },
+{      (205*OVERSAMPLENR),     165     },
+{      (224*OVERSAMPLENR),     160     },
+{      (245*OVERSAMPLENR),     155     },
+{      (268*OVERSAMPLENR),     150     },
+{      (293*OVERSAMPLENR),     145     },
+{      (320*OVERSAMPLENR),     140     },
+{      (348*OVERSAMPLENR),     135     },
+{      (379*OVERSAMPLENR),     130     },
+{      (411*OVERSAMPLENR),     125     },
+{      (445*OVERSAMPLENR),     120     },
+{      (480*OVERSAMPLENR),     115     },
+{      (516*OVERSAMPLENR),     110     },
+{      (553*OVERSAMPLENR),     105     },
+{      (591*OVERSAMPLENR),     100     },
+{      (628*OVERSAMPLENR),     95      },
+{      (665*OVERSAMPLENR),     90      },
+{      (702*OVERSAMPLENR),     85      },
+{      (737*OVERSAMPLENR),     80      },
+{      (770*OVERSAMPLENR),     75      },
+{      (801*OVERSAMPLENR),     70      },
+{      (830*OVERSAMPLENR),     65      },
+{      (857*OVERSAMPLENR),     60      },
+{      (881*OVERSAMPLENR),     55      },
+{      (903*OVERSAMPLENR),     50      },
+{      (922*OVERSAMPLENR),     45      },
+{      (939*OVERSAMPLENR),     40      },
+{      (954*OVERSAMPLENR),     35      },
+{      (966*OVERSAMPLENR),     30      },
+{      (977*OVERSAMPLENR),     25      },
+{      (985*OVERSAMPLENR),     20      },
+{      (993*OVERSAMPLENR),     15      },
+{      (999*OVERSAMPLENR),     10      },
+{      (1004*OVERSAMPLENR),    5       },
+{      (1008*OVERSAMPLENR),    0       } //safety
 };
 #endif
 #if (THERMISTORHEATER == 2) || (THERMISTORBED == 2) //200k bed thermistor
 #define NUMTEMPS_2 21
 const short temptable_2[NUMTEMPS_2][2] = {
-   {(1*16), 848},
-   {(54*16), 275},
-   {(107*16), 228},
-   {(160*16), 202},
-   {(213*16), 185},
-   {(266*16), 171},
-   {(319*16), 160},
-   {(372*16), 150},
-   {(425*16), 141},
-   {(478*16), 133},
-   {(531*16), 125},
-   {(584*16), 118},
-   {(637*16), 110},
-   {(690*16), 103},
-   {(743*16), 95},
-   {(796*16), 86},
-   {(849*16), 77},
-   {(902*16), 65},
-   {(955*16), 49},
-   {(1008*16), 17},
-   {(1020*16), 0} //safety
+   {(1*OVERSAMPLENR), 848},
+   {(54*OVERSAMPLENR), 275},
+   {(107*OVERSAMPLENR), 228},
+   {(160*OVERSAMPLENR), 202},
+   {(213*OVERSAMPLENR), 185},
+   {(266*OVERSAMPLENR), 171},
+   {(319*OVERSAMPLENR), 160},
+   {(372*OVERSAMPLENR), 150},
+   {(425*OVERSAMPLENR), 141},
+   {(478*OVERSAMPLENR), 133},
+   {(531*OVERSAMPLENR), 125},
+   {(584*OVERSAMPLENR), 118},
+   {(637*OVERSAMPLENR), 110},
+   {(690*OVERSAMPLENR), 103},
+   {(743*OVERSAMPLENR), 95},
+   {(796*OVERSAMPLENR), 86},
+   {(849*OVERSAMPLENR), 77},
+   {(902*OVERSAMPLENR), 65},
+   {(955*OVERSAMPLENR), 49},
+   {(1008*OVERSAMPLENR), 17},
+   {(1020*OVERSAMPLENR), 0} //safety
 };
 
 #endif
 #if (THERMISTORHEATER == 3) || (THERMISTORBED == 3) //mendel-parts
 #define NUMTEMPS_3 28
 const short temptable_3[NUMTEMPS_3][2] = {
-               {(1*16),864},
-               {(21*16),300},
-               {(25*16),290},
-               {(29*16),280},
-               {(33*16),270},
-               {(39*16),260},
-               {(46*16),250},
-               {(54*16),240},
-               {(64*16),230},
-               {(75*16),220},
-               {(90*16),210},
-               {(107*16),200},
-               {(128*16),190},
-               {(154*16),180},
-               {(184*16),170},
-               {(221*16),160},
-               {(265*16),150},
-               {(316*16),140},
-               {(375*16),130},
-               {(441*16),120},
-               {(513*16),110},
-               {(588*16),100},
-               {(734*16),80},
-               {(856*16),60},
-               {(938*16),40},
-               {(986*16),20},
-               {(1008*16),0},
-               {(1018*16),-20}
+               {(1*OVERSAMPLENR),864},
+               {(21*OVERSAMPLENR),300},
+               {(25*OVERSAMPLENR),290},
+               {(29*OVERSAMPLENR),280},
+               {(33*OVERSAMPLENR),270},
+               {(39*OVERSAMPLENR),260},
+               {(46*OVERSAMPLENR),250},
+               {(54*OVERSAMPLENR),240},
+               {(64*OVERSAMPLENR),230},
+               {(75*OVERSAMPLENR),220},
+               {(90*OVERSAMPLENR),210},
+               {(107*OVERSAMPLENR),200},
+               {(128*OVERSAMPLENR),190},
+               {(154*OVERSAMPLENR),180},
+               {(184*OVERSAMPLENR),170},
+               {(221*OVERSAMPLENR),160},
+               {(265*OVERSAMPLENR),150},
+               {(316*OVERSAMPLENR),140},
+               {(375*OVERSAMPLENR),130},
+               {(441*OVERSAMPLENR),120},
+               {(513*OVERSAMPLENR),110},
+               {(588*OVERSAMPLENR),100},
+               {(734*OVERSAMPLENR),80},
+               {(856*OVERSAMPLENR),60},
+               {(938*OVERSAMPLENR),40},
+               {(986*OVERSAMPLENR),20},
+               {(1008*OVERSAMPLENR),0},
+               {(1018*OVERSAMPLENR),-20}
        };
 
 #endif
diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h
new file mode 100644 (file)
index 0000000..5f0196f
--- /dev/null
@@ -0,0 +1,156 @@
+#ifndef __ULTRALCDH
+#define __ULTRALCDH
+#include "Configuration.h"
+
+#ifdef ULTRA_LCD
+
+  void lcd_status();
+  void lcd_init();
+  void lcd_status(const char* message);
+  void beep();
+  void buttons_check();
+  #define LCDSTATUSRIGHT
+
+  #define LCD_UPDATE_INTERVAL 100
+  #define STATUSTIMEOUT 15000
+
+  #include "Configuration.h"
+
+  #include <LiquidCrystal.h>
+  extern LiquidCrystal lcd;
+
+  //lcd display size
+
+#ifdef NEWPANEL
+ //arduino pin witch triggers an piezzo beeper
+  #define BEEPER 18
+
+  #define LCD_PINS_RS 20 
+  #define LCD_PINS_ENABLE 17
+  #define LCD_PINS_D4 16
+  #define LCD_PINS_D5 21 
+  #define LCD_PINS_D6 5
+  #define LCD_PINS_D7 6
+  
+  //buttons are directly attached
+  #define BTN_EN1 40
+  #define BTN_EN2 42
+  #define BTN_ENC 19  //the click
+  
+  #define BLEN_C 2
+  #define BLEN_B 1
+  #define BLEN_A 0
+  
+  #define SDCARDDETECT 38
+  
+  #define EN_C (1<<BLEN_C)
+  #define EN_B (1<<BLEN_B)
+  #define EN_A (1<<BLEN_A)
+  
+   //encoder rotation values
+  #define encrot0 0
+  #define encrot1 2
+  #define encrot2 3
+  #define encrot3 1
+
+  
+  #define CLICKED (buttons&EN_C)
+  #define BLOCK {blocking=millis()+blocktime;}
+  #define CARDINSERTED (READ(SDCARDDETECT)==0)
+  
+#else
+  //arduino pin witch triggers an piezzo beeper
+  #define BEEPER 18
+
+  //buttons are attached to a shift register
+  #define SHIFT_CLK 38
+  #define SHIFT_LD 42
+  #define SHIFT_OUT 40
+  #define SHIFT_EN 17
+  
+  #define LCD_PINS_RS 16 
+  #define LCD_PINS_ENABLE 5
+  #define LCD_PINS_D4 6
+  #define LCD_PINS_D5 21 
+  #define LCD_PINS_D6 20
+  #define LCD_PINS_D7 19
+  
+   //bits in the shift register that carry the buttons for:
+  // left up center down right red
+  #define BL_LE 7
+  #define BL_UP 6
+  #define BL_MI 5
+  #define BL_DW 4
+  #define BL_RI 3
+  #define BL_ST 2
+
+  #define BLEN_B 1
+  #define BLEN_A 0
+
+  //encoder rotation values
+  #define encrot0 0
+  #define encrot1 2
+  #define encrot2 3
+  #define encrot3 1
+
+  //atomatic, do not change
+  #define B_LE (1<<BL_LE)
+  #define B_UP (1<<BL_UP)
+  #define B_MI (1<<BL_MI)
+  #define B_DW (1<<BL_DW)
+  #define B_RI (1<<BL_RI)
+  #define B_ST (1<<BL_ST)
+  #define EN_B (1<<BLEN_B)
+  #define EN_A (1<<BLEN_A)
+  
+  #define CLICKED ((buttons&B_MI)||(buttons&B_ST))
+  #define BLOCK {blocking[BL_MI]=millis()+blocktime;blocking[BL_ST]=millis()+blocktime;}
+  
+#endif
+  // blocking time for recognizing a new keypress of one key, ms
+#define blocktime 500
+#define lcdslow 5
+  enum MainStatus{Main_Status, Main_Menu, Main_Prepare, Main_Control, Main_SD};
+
+  class MainMenu{
+  public:
+    MainMenu();
+    void update();
+    void getfilename(const uint8_t nr);
+    uint8_t activeline;
+    MainStatus status;
+    uint8_t displayStartingRow;
+    
+    void showStatus();
+    void showMainMenu();
+    void showPrepare();
+    void showControl();
+    void showSD();
+    bool force_lcd_update;
+    int lastencoderpos;
+    int8_t lineoffset;
+    int8_t lastlineoffset;
+    char filename[11];
+    bool linechanging;
+  };
+
+  char *fillto(int8_t n,char *c);
+  char *ftostr51(const float &x);
+  char *ftostr31(const float &x);
+  char *ftostr3(const float &x);
+
+
+
+  #define LCD_MESSAGE(x) lcd_status(x);
+  #define LCD_STATUS lcd_status()
+#else //no lcd
+  #define LCD_STATUS
+  #define LCD_MESSAGE(x)
+#endif
+  
+#ifndef ULTIPANEL  
+ #define CLICKED false
+#define BLOCK ;
+#endif 
+#endif //ULTRALCD
+
diff --git a/Marlin/ultralcd.pde b/Marlin/ultralcd.pde
new file mode 100644 (file)
index 0000000..2702af8
--- /dev/null
@@ -0,0 +1,1593 @@
+#include "ultralcd.h"
+
+
+#ifdef ULTRA_LCD
+extern volatile int feedmultiply;
+extern long position[4];   
+
+char messagetext[LCD_WIDTH]="";
+
+#include <LiquidCrystal.h>
+LiquidCrystal lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7);  //RS,Enable,D4,D5,D6,D7 
+
+unsigned long previous_millis_lcd=0;
+
+
+
+volatile char buttons=0;  //the last checked buttons in a bit array.
+int encoderpos=0;
+short lastenc=0;
+#ifdef NEWPANEL
+ long blocking=0;
+#else
+ long blocking[8]={0,0,0,0,0,0,0,0};
+#endif
+MainMenu menu;
+
+void lcd_status(const char* message)
+{
+  strncpy(messagetext,message,LCD_WIDTH);
+}
+
+void clear()
+{
+  //lcd.setCursor(0,0);
+  lcd.clear();
+  //delay(1);
+ // lcd.begin(LCD_WIDTH,LCD_HEIGHT);
+  //lcd_init();
+}
+long previous_millis_buttons=0;
+
+void lcd_init()
+{
+  //beep();
+  byte Degree[8] =
+  {
+    B01100,
+    B10010,
+    B10010,
+    B01100,
+    B00000,
+    B00000,
+    B00000,
+    B00000
+  };
+  byte Thermometer[8] =
+  {
+    B00100,
+    B01010,
+    B01010,
+    B01010,
+    B01010,
+    B10001,
+    B10001,
+    B01110
+  };
+  byte uplevel[8]={0x04, 0x0e, 0x1f, 0x04, 0x1c, 0x00, 0x00, 0x00};//thanks joris
+  byte refresh[8]={0x00, 0x06, 0x19, 0x18, 0x03, 0x13, 0x0c, 0x00}; //thanks joris
+  lcd.begin(LCD_WIDTH, LCD_HEIGHT);
+  lcd.createChar(1,Degree);
+  lcd.createChar(2,Thermometer);
+  lcd.createChar(3,uplevel);
+  lcd.createChar(4,refresh);
+  LCD_MESSAGE(fillto(LCD_WIDTH,"UltiMarlin ready."));
+}
+
+
+void beep()
+{
+  //return;
+#ifdef ULTIPANEL
+  pinMode(BEEPER,OUTPUT);
+  for(int i=0;i<20;i++){
+    WRITE(BEEPER,HIGH);
+    delay(5);
+    WRITE(BEEPER,LOW);
+    delay(5);
+  }
+#endif
+}
+
+void beepshort()
+{
+  //return;
+#ifdef ULTIPANEL
+  pinMode(BEEPER,OUTPUT);
+  for(int i=0;i<10;i++){
+    WRITE(BEEPER,HIGH);
+    delay(3);
+    WRITE(BEEPER,LOW);
+    delay(3);
+  }
+#endif  
+}
+void lcd_status()
+{
+#ifdef ULTIPANEL
+  static uint8_t oldbuttons=0;
+  static long previous_millis_buttons=0;
+  static long previous_lcdinit=0;
+//  buttons_check(); // Done in temperature interrupt
+  //previous_millis_buttons=millis();
+  
+  if((buttons==oldbuttons) &&  ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL)   )
+    return;
+  oldbuttons=buttons;
+#else
+  
+  if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL)   )
+    return;
+#endif
+    
+  previous_millis_lcd=millis();
+  menu.update();
+}
+#ifdef ULTIPANEL  
+void buttons_init()
+{
+#ifdef NEWPANEL
+  pinMode(BTN_EN1,INPUT);
+  pinMode(BTN_EN2,INPUT); 
+  pinMode(BTN_ENC,INPUT); 
+  pinMode(SDCARDDETECT,INPUT);
+  WRITE(BTN_EN1,HIGH);
+  WRITE(BTN_EN2,HIGH);
+  WRITE(BTN_ENC,HIGH);
+  WRITE(SDCARDDETECT,HIGH);
+#else
+  pinMode(SHIFT_CLK,OUTPUT);
+  pinMode(SHIFT_LD,OUTPUT);
+  pinMode(SHIFT_EN,OUTPUT);
+  pinMode(SHIFT_OUT,INPUT);
+  WRITE(SHIFT_OUT,HIGH);
+  WRITE(SHIFT_LD,HIGH); 
+  WRITE(SHIFT_EN,LOW); 
+#endif
+}
+
+
+void buttons_check()
+{
+//  volatile static bool busy=false;
+//  if(busy) 
+//    return;
+//  busy=true;
+  
+#ifdef NEWPANEL
+  uint8_t newbutton=0;
+  if(READ(BTN_EN1)==0)  newbutton|=EN_A;
+  if(READ(BTN_EN2)==0)  newbutton|=EN_B;
+  if((blocking<millis()) &&(READ(BTN_ENC)==0))
+    newbutton|=EN_C;
+  buttons=newbutton;
+#else
+  //read it from the shift register
+  uint8_t newbutton=0;
+  WRITE(SHIFT_LD,LOW);
+  WRITE(SHIFT_LD,HIGH);
+  unsigned char tmp_buttons=0;
+  for(unsigned char i=0;i<8;i++)
+  { 
+    newbutton = newbutton>>1;
+    if(READ(SHIFT_OUT))
+      newbutton|=(1<<7);
+    WRITE(SHIFT_CLK,HIGH);
+    WRITE(SHIFT_CLK,LOW);
+  }
+  buttons=~newbutton; //invert it, because a pressed switch produces a logical 0
+#endif
+  char enc=0;
+  if(buttons&EN_A)
+    enc|=(1<<0);
+  if(buttons&EN_B)
+    enc|=(1<<1);
+  if(enc!=lastenc)
+       {
+    switch(enc)
+    {
+    case encrot0:
+      if(lastenc==encrot3)
+        encoderpos++;
+      else if(lastenc==encrot1)
+        encoderpos--;
+      break;
+    case encrot1:
+      if(lastenc==encrot0)
+        encoderpos++;
+      else if(lastenc==encrot2)
+        encoderpos--;
+      break;
+    case encrot2:
+      if(lastenc==encrot1)
+        encoderpos++;
+      else if(lastenc==encrot3)
+        encoderpos--;
+      break;
+    case encrot3:
+      if(lastenc==encrot2)
+        encoderpos++;
+      else if(lastenc==encrot0)
+        encoderpos--;
+      break;
+    default:
+      ;
+    }
+  }
+  lastenc=enc;
+//  busy=false;
+}
+
+#endif
+
+MainMenu::MainMenu()
+{
+  status=Main_Status;
+  displayStartingRow=0;
+  activeline=0;
+  force_lcd_update=true;
+#ifdef ULTIPANEL
+  buttons_init();
+#endif
+  lcd_init();
+  linechanging=false;
+}
+
+extern volatile bool feedmultiplychanged;
+
+void MainMenu::showStatus()
+{ 
+#if LCD_HEIGHT==4
+  static int oldcurrentraw=-1;
+  static int oldtargetraw=-1;
+  //force_lcd_update=true;
+  if(force_lcd_update||feedmultiplychanged)  //initial display of content
+  {
+    feedmultiplychanged=false;
+    encoderpos=feedmultiply;
+    clear();
+    lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
+#if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
+    lcd.setCursor(10,0);lcd.print("B123/567\001 ");
+#endif
+  }
+    
+
+  if((abs(current_raw[0]-oldcurrentraw)>3)||force_lcd_update)
+  {
+    lcd.setCursor(1,0);
+    lcd.print(ftostr3(analog2temp(current_raw[0])));
+    oldcurrentraw=current_raw[0];
+  }
+  if((target_raw[0]!=oldtargetraw)||force_lcd_update)
+  {
+    lcd.setCursor(5,0);
+    lcd.print(ftostr3(analog2temp(target_raw[0])));
+    oldtargetraw=target_raw[0];
+  }
+  #if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
+  static int oldcurrentbedraw=-1;
+  static int oldtargetbedraw=-1; 
+  if((current_bed_raw!=oldcurrentbedraw)||force_lcd_update)
+  {
+    lcd.setCursor(1,0);
+    lcd.print(ftostr3(analog2temp(current_bed_raw)));
+    oldcurrentraw=current_raw[1];
+  }
+  if((target_bed_raw!=oldtargebedtraw)||force_lcd_update)
+  {
+    lcd.setCursor(5,0);
+    lcd.print(ftostr3(analog2temp(target_bed_raw)));
+    oldtargetraw=target_bed_raw;
+  }
+  #endif
+  //starttime=2;
+  static uint16_t oldtime=0;
+  if(starttime!=0)
+  {
+    lcd.setCursor(0,1);
+    uint16_t time=millis()/60000-starttime/60000;
+    
+    if(starttime!=oldtime)
+    {
+      lcd.print(itostr2(time/60));lcd.print("h ");lcd.print(itostr2(time%60));lcd.print("m");
+      oldtime=time;
+    }
+  }
+  static int oldzpos=0;
+  int currentz=current_position[2]*10;
+  if((currentz!=oldzpos)||force_lcd_update)
+  {
+    lcd.setCursor(10,1);
+    lcd.print("Z:");lcd.print(itostr31(currentz));
+    oldzpos=currentz;
+  }
+  static int oldfeedmultiply=0;
+  int curfeedmultiply=feedmultiply;
+  if(encoderpos!=curfeedmultiply||force_lcd_update)
+  {
+   curfeedmultiply=encoderpos;
+   if(curfeedmultiply<10)
+     curfeedmultiply=10;
+   if(curfeedmultiply>999)
+     curfeedmultiply=999;
+   feedmultiply=curfeedmultiply;
+   encoderpos=curfeedmultiply;
+  }
+  if((curfeedmultiply!=oldfeedmultiply)||force_lcd_update)
+  {
+   oldfeedmultiply=curfeedmultiply;
+   lcd.setCursor(0,2);
+   lcd.print(itostr3(curfeedmultiply));lcd.print("% ");
+  }
+  if(messagetext[0]!='\0')
+  {
+    lcd.setCursor(0,LCD_HEIGHT-1);
+    lcd.print(fillto(LCD_WIDTH,messagetext));
+    messagetext[0]='\0';
+  }
+#else //smaller LCDS----------------------------------
+  static int oldcurrentraw=-1;
+  static int oldtargetraw=-1;
+  if(force_lcd_update)  //initial display of content
+  {
+    encoderpos=feedmultiply;
+    lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
+    #if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
+    lcd.setCursor(10,0);lcd.print("B123/567\001 ");
+    #endif
+  }
+    
+
+  if((abs(current_raw[0]-oldcurrentraw)>3)||force_lcd_update)
+  {
+    lcd.setCursor(1,0);
+    lcd.print(ftostr3(analog2temp(current_raw[0])));
+    oldcurrentraw=current_raw[0];
+  }
+  if((target_raw[0]!=oldtargetraw)||force_lcd_update)
+  {
+    lcd.setCursor(5,0);
+    lcd.print(ftostr3(analog2temp(target_raw[0])));
+    oldtargetraw=target_raw[0];
+  }
+
+  if(messagetext[0]!='\0')
+  {
+    lcd.setCursor(0,LCD_HEIGHT-1);
+    lcd.print(fillto(LCD_WIDTH,messagetext));
+    messagetext[0]='\0';
+  }
+
+#endif
+}
+
+enum {ItemP_exit, ItemP_home, ItemP_origin, ItemP_preheat, ItemP_extrude, ItemP_disstep};
+
+void MainMenu::showPrepare()
+{
+ uint8_t line=0;
+ if(lastlineoffset!=lineoffset)
+ {
+   force_lcd_update=true;
+   clear(); 
+ }
+ for(uint8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
+ {
+   //Serial.println((int)(line-lineoffset));
+  switch(i)
+  {
+    case ItemP_exit:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Prepare");
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK
+          status=Main_Menu;
+          beepshort();
+        }
+      }break;
+    case ItemP_home:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Auto Home");
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK
+          enquecommand("G28 X-105 Y-105 Z0");
+          beepshort();
+        }
+      }break;
+    case ItemP_origin:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Set Origin");
+          
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK
+          enquecommand("G92 X0 Y0 Z0");
+          beepshort();
+        }
+      }break;
+    case ItemP_preheat:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Preheat"); 
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK
+          target_raw[0] = temp2analog(170);
+          beepshort();
+        }
+      }break;
+    case ItemP_extrude:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Extrude");
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK
+          enquecommand("G92 E0");
+          enquecommand("G1 F700 E50");
+          beepshort();
+        }
+      }break;
+    case ItemP_disstep:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Disable Steppers");
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK
+          enquecommand("M84");
+          beepshort();
+        }
+      }break;
+    default:   
+      break;
+  }
+  line++;
+ }
+ lastlineoffset=lineoffset;
+ if((encoderpos/lcdslow!=lastencoderpos/lcdslow)||force_lcd_update)
+ {
+   
+    lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
+    
+    if(encoderpos<0)
+    {
+     lineoffset--;
+     if(lineoffset<0)
+       lineoffset=0;
+     encoderpos=0;
+     force_lcd_update=true;
+    }
+    if(encoderpos/lcdslow>3)
+    {
+     lineoffset++;
+     encoderpos=3*lcdslow;
+     if(lineoffset>(ItemP_disstep+1-LCD_HEIGHT))
+       lineoffset=ItemP_disstep+1-LCD_HEIGHT;
+     force_lcd_update=true;
+    }
+    //encoderpos=encoderpos%LCD_HEIGHT;
+    lastencoderpos=encoderpos;
+    activeline=encoderpos/lcdslow;
+    lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');   
+  } 
+}
+enum {
+  ItemC_exit, ItemC_nozzle, 
+  ItemC_PID_P,ItemC_PID_I,ItemC_PID_D,ItemC_PID_C,
+  ItemC_fan, 
+  ItemC_acc, ItemC_xyjerk, 
+  ItemC_vmaxx, ItemC_vmaxy, ItemC_vmaxz, ItemC_vmaxe, 
+  ItemC_vtravmin,ItemC_vmin,  
+  ItemC_amaxx, ItemC_amaxy, ItemC_amaxz, ItemC_amaxe, 
+  ItemC_aret,ItemC_esteps, ItemC_store, ItemC_load,ItemC_failsafe
+};
+
+void MainMenu::showControl()
+{
+ uint8_t line=0;
+ if((lastlineoffset!=lineoffset)||force_lcd_update)
+ {
+   force_lcd_update=true;
+   clear();
+ }
+ for(uint8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
+ {
+  switch(i)
+  {
+    case ItemC_exit:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Control");
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK
+          status=Main_Menu;
+          beepshort();
+        }
+      }break;
+    case ItemC_nozzle:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" \002Nozzle:");
+          lcd.setCursor(13,line);lcd.print(ftostr3(analog2temp(target_raw[0])));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)analog2temp(target_raw[0]);
+            }
+            else
+            {
+              target_raw[0] = temp2analog(encoderpos);
+              encoderpos=activeline*lcdslow;
+              beepshort();
+            }
+            BLOCK;
+          }
+          if(linechanging)
+          {
+            if(encoderpos<0) encoderpos=0;
+            if(encoderpos>260) encoderpos=260;
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
+          }
+        }
+      }break;
+      
+      case ItemC_fan:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Fan speed:");
+          lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED) //nalogWrite(FAN_PIN,  fanpwm);
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=fanpwm;
+            }
+            else
+            {
+              fanpwm = constrain(encoderpos,0,255);
+              encoderpos=fanpwm;
+              analogWrite(FAN_PIN,  fanpwm);
+
+              beepshort();
+            }
+            BLOCK;
+          }
+          if(linechanging)
+          {
+            if(encoderpos<0) encoderpos=0;
+            if(encoderpos>255) encoderpos=255;
+            fanpwm=encoderpos;
+              analogWrite(FAN_PIN,  fanpwm);
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
+          }
+        }
+      }break;
+    case ItemC_acc:
+    {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Acc:");
+          lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcd.print("00");
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)acceleration/100;
+            }
+            else
+            {
+              acceleration= encoderpos*100;
+              encoderpos=activeline*lcdslow;
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<5) encoderpos=5;
+            if(encoderpos>990) encoderpos=990;
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
+          }
+        }
+      }break;
+    case ItemC_xyjerk: //max_xy_jerk
+      {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Vxy-jerk: ");
+          lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk/60));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)max_xy_jerk/60;
+            }
+            else
+            {
+              max_xy_jerk= encoderpos*60;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<1) encoderpos=1;
+            if(encoderpos>990) encoderpos=990;
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
+          }
+        }
+      }break;
+      case ItemC_PID_P: 
+      {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" PID-P: ");
+          lcd.setCursor(13,line);lcd.print(itostr4(Kp));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)Kp/5;
+            }
+            else
+            {
+              Kp= encoderpos*5;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<1) encoderpos=1;
+            if(encoderpos>9990/5) encoderpos=9990/5;
+            lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5));
+          }
+        }
+      }break;
+    case ItemC_PID_I: 
+      {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" PID-I: ");
+          lcd.setCursor(13,line);lcd.print(ftostr51(Ki));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)(Ki*10);
+            }
+            else
+            {
+              Ki= encoderpos/10.;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<0) encoderpos=0;
+            if(encoderpos>9990) encoderpos=9990;
+            lcd.setCursor(13,line);lcd.print(ftostr51(encoderpos/10.));
+          }
+        }
+      }break;
+      case ItemC_PID_D: 
+      {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" PID-D: ");
+          lcd.setCursor(13,line);lcd.print(itostr4(Kd));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)Kd/5;
+            }
+            else
+            {
+              Kd= encoderpos*5;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<0) encoderpos=0;
+            if(encoderpos>9990/5) encoderpos=9990/5;
+            lcd.setCursor(13,line);lcd.print(itostr4(encoderpos*5));
+          }
+        }
+      }break;
+    
+    
+      
+    case ItemC_PID_C: 
+      {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" PID-C: ");
+          lcd.setCursor(13,line);lcd.print(itostr3(Kc));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)Kc;
+            }
+            else
+            {
+              Kc= encoderpos;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<0) encoderpos=0;
+            if(encoderpos>990) encoderpos=990;
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
+          }
+        }
+      }break;
+    case ItemC_vmaxx:
+    case ItemC_vmaxy:
+    case ItemC_vmaxz:
+    case ItemC_vmaxe:
+      {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Vmax ");
+          if(i==ItemC_vmaxx)lcd.print("x:");
+          if(i==ItemC_vmaxy)lcd.print("y:");
+          if(i==ItemC_vmaxz)lcd.print("z:");
+          if(i==ItemC_vmaxe)lcd.print("e:");
+          lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemC_vmaxx]/60));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)max_feedrate[i-ItemC_vmaxx]/60;
+            }
+            else
+            {
+              max_feedrate[i-ItemC_vmaxx]= encoderpos*60;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<1) encoderpos=1;
+            if(encoderpos>990) encoderpos=990;
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
+          }
+        }
+      }break;
+    
+    case ItemC_vmin:
+    {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Vmin:");
+          lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate/60));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)(minimumfeedrate/60.);
+            }
+            else
+            {
+              minimumfeedrate= encoderpos*60;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<0) encoderpos=0;
+            if(encoderpos>990) encoderpos=990;
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
+          }
+        }
+      }break;
+    case ItemC_vtravmin:
+    {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" VTrav min:");
+          lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate/60));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)mintravelfeedrate/60;
+            }
+            else
+            {
+              mintravelfeedrate= encoderpos*60;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<0) encoderpos=0;
+            if(encoderpos>990) encoderpos=990;
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
+          }
+        }
+      }break;
+    
+    case ItemC_amaxx:      
+    case ItemC_amaxy:
+    case ItemC_amaxz:
+    case ItemC_amaxe:
+    {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Amax ");
+          if(i==ItemC_amaxx)lcd.print("x:");
+          if(i==ItemC_amaxy)lcd.print("y:");
+          if(i==ItemC_amaxz)lcd.print("z:");
+          if(i==ItemC_amaxe)lcd.print("e:");
+          lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemC_amaxx]/100));lcd.print("00");
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)max_acceleration_units_per_sq_second[i-ItemC_amaxx]/100;
+            }
+            else
+            {
+              max_acceleration_units_per_sq_second[i-ItemC_amaxx]= encoderpos*100;
+              encoderpos=activeline*lcdslow;
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<1) encoderpos=1;
+            if(encoderpos>990) encoderpos=990;
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
+          }
+        }
+      }break;
+    case ItemC_aret://float retract_acceleration = 7000;
+    {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" A-retract:");
+          lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcd.print("00");
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)retract_acceleration/100;
+            }
+            else
+            {
+              retract_acceleration= encoderpos*100;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<10) encoderpos=10;
+            if(encoderpos>990) encoderpos=990;
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
+          }
+        }
+      }break;
+    case ItemC_esteps://axis_steps_per_unit[i] = code_value();
+         {
+      if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" Esteps/mm:");
+          lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
+        }
+        
+        if((activeline==line) )
+        {
+          if(CLICKED)
+          {
+            linechanging=!linechanging;
+            if(linechanging)
+            {
+               encoderpos=(int)axis_steps_per_unit[3];
+            }
+            else
+            {
+              float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
+              position[E_AXIS]=lround(position[E_AXIS]*factor);
+              //current_position[3]*=factor;
+              axis_steps_per_unit[E_AXIS]= encoderpos;
+              encoderpos=activeline*lcdslow;
+                
+            }
+            BLOCK;
+            beepshort();
+          }
+          if(linechanging)
+          {
+            if(encoderpos<5) encoderpos=5;
+            if(encoderpos>9999) encoderpos=9999;
+            lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
+          }
+        }
+      }break; 
+    case ItemC_store:
+    {
+      if(force_lcd_update)
+      {
+        lcd.setCursor(0,line);lcd.print(" Store EPROM");
+      }
+      if((activeline==line) && CLICKED)
+      {
+        //enquecommand("M84");
+        beepshort();
+        BLOCK;
+        StoreSettings();
+      }
+    }break;
+    case ItemC_load:
+    {
+      if(force_lcd_update)
+      {
+        lcd.setCursor(0,line);lcd.print(" Load EPROM");
+      }
+      if((activeline==line) && CLICKED)
+      {
+        //enquecommand("M84");
+        beepshort();
+        BLOCK;
+        RetrieveSettings();
+      }
+    }break;
+    case ItemC_failsafe:
+    {
+      if(force_lcd_update)
+      {
+        lcd.setCursor(0,line);lcd.print(" Restore Failsafe");
+      }
+      if((activeline==line) && CLICKED)
+      {
+        //enquecommand("M84");
+        beepshort();
+        BLOCK;
+        RetrieveSettings(true);
+      }
+    }break;
+    default:   
+      break;
+  }
+  line++;
+ }
+ lastlineoffset=lineoffset;
+
+ if(!linechanging &&  ((encoderpos/lcdslow!=lastencoderpos/lcdslow)||force_lcd_update))
+ {
+   
+    lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
+    
+    if(encoderpos<0)
+    {
+     lineoffset--;
+     if(lineoffset<0)
+       lineoffset=0;
+     encoderpos=0;
+     force_lcd_update=true;
+    }
+    if(encoderpos/lcdslow>3)
+    {
+     lineoffset++;
+     encoderpos=3*lcdslow;
+     if(lineoffset>(ItemC_failsafe+1-LCD_HEIGHT))
+       lineoffset=ItemC_failsafe+1-LCD_HEIGHT;
+     force_lcd_update=true;
+    }
+    //encoderpos=encoderpos%LCD_HEIGHT;
+    lastencoderpos=encoderpos;
+    activeline=encoderpos/lcdslow;
+    if(activeline>3) activeline=3;
+    lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');   
+  } 
+}
+
+#include "SdFat.h"
+
+void MainMenu::getfilename(const uint8_t nr)
+{
+#ifdef SDSUPPORT  
+  dir_t p;
+  root.rewind();
+  uint8_t cnt=0;
+  filename[0]='\0';
+  while (root.readDir(p) > 0)
+  {
+    if (p.name[0] == DIR_NAME_FREE) break;
+    if (p.name[0] == DIR_NAME_DELETED || p.name[0] == '.'|| p.name[0] == '_') continue;
+    if (!DIR_IS_FILE_OR_SUBDIR(&p)) continue;
+    if(p.name[8]!='G') continue;
+    if(p.name[9]=='~') continue;
+    if(cnt++!=nr) continue;
+    //Serial.println((char*)p.name);
+    uint8_t writepos=0;
+    for (uint8_t i = 0; i < 11; i++) 
+    {
+      if (p.name[i] == ' ') continue;
+      if (i == 8) {
+        filename[writepos++]='.';
+      }
+      filename[writepos++]=p.name[i];
+    }
+    filename[writepos++]=0;
+  }
+#endif  
+}
+
+uint8_t getnrfilenames()
+{
+#ifdef SDSUPPORT
+  dir_t p;
+  root.rewind();
+  uint8_t cnt=0;
+  while (root.readDir(p) > 0)
+  {
+    if (p.name[0] == DIR_NAME_FREE) break;
+    if (p.name[0] == DIR_NAME_DELETED || p.name[0] == '.'|| p.name[0] == '_') continue;
+    if (!DIR_IS_FILE_OR_SUBDIR(&p)) continue;
+    if(p.name[8]!='G') continue;
+    if(p.name[9]=='~') continue;
+    cnt++;
+  }
+  return cnt;
+#endif
+}
+
+void MainMenu::showSD()
+{
+
+#ifdef SDSUPPORT
+ uint8_t line=0;
+
+ if(lastlineoffset!=lineoffset)
+ {
+   force_lcd_update=true; 
+ }
+ static uint8_t nrfiles=0;
+ if(force_lcd_update)
+ {
+   clear();
+  if(sdactive)
+  {
+    nrfiles=getnrfilenames();
+  }
+  else
+  {
+    nrfiles=0;
+    lineoffset=0;
+  }
+  //Serial.print("Nr files:"); Serial.println((int)nrfiles);
+ }
+ for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
+ {
+  switch(i)
+  {
+    case 0:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);lcd.print(" File");
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK
+          status=Main_Menu;
+          beepshort();
+        }
+      }break;
+    case 1:
+      {
+        if(force_lcd_update)
+        {
+          lcd.setCursor(0,line);
+#ifdef CARDINSERTED
+          if(CARDINSERTED)
+#else
+          if(true)
+#endif
+          {
+            lcd.print(" \004Refresh");
+          }
+          else
+          {
+            lcd.print(" \004Insert Card");
+          }
+          
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK;
+          beepshort();
+          initsd();
+          force_lcd_update=true;
+           nrfiles=getnrfilenames();
+        }
+      }break;
+    default:
+    {
+      if(i-2<nrfiles)
+      {
+        if(force_lcd_update)
+        {
+          getfilename(i-2);
+          //Serial.print("Filenr:");Serial.println(i-2);
+          lcd.setCursor(0,line);lcd.print(" ");lcd.print(filename);
+        }
+        if((activeline==line) && CLICKED)
+        {
+          BLOCK
+          getfilename(i-2);
+          char cmd[30];
+          for(int i=0;i<strlen(filename);i++)
+            filename[i]=tolower(filename[i]);
+          sprintf(cmd,"M23 %s",filename);
+          //sprintf(cmd,"M115");
+          enquecommand(cmd);
+          enquecommand("M24");
+          beep(); 
+          status=Main_Status;
+          lcd_status(filename);
+        }
+      }
+      
+    }
+      break;
+  }
+  line++;
+ }
+ lastlineoffset=lineoffset;
+ if((encoderpos!=lastencoderpos)||force_lcd_update)
+ {
+   
+    lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?' ':' ');
+    
+    if(encoderpos<0)
+    {
+     lineoffset--;
+     if(lineoffset<0)
+       lineoffset=0;
+     encoderpos=0;
+     force_lcd_update=true;
+    }
+    if(encoderpos/lcdslow>3)
+    {
+     lineoffset++;
+     encoderpos=3*lcdslow;
+     if(lineoffset>(1+nrfiles+1-LCD_HEIGHT))
+       lineoffset=1+nrfiles+1-LCD_HEIGHT;
+     force_lcd_update=true;
+     
+    }
+    lastencoderpos=encoderpos;
+    activeline=encoderpos;
+    if(activeline>3) 
+    {
+      activeline=3;
+    }
+    if(activeline<0) 
+    {
+      activeline=0;
+    }
+    if(activeline>1+nrfiles) activeline=1+nrfiles;
+    if(lineoffset>1+nrfiles) lineoffset=1+nrfiles;
+    lcd.setCursor(0,activeline);lcd.print((activeline+lineoffset)?'>':'\003');   
+    
+  }
+#endif
+}
+
+enum {ItemM_watch, ItemM_prepare, ItemM_control, ItemM_file };
+void MainMenu::showMainMenu()
+{
+   //if(int(encoderpos/lcdslow)!=int(lastencoderpos/lcdslow))
+   //  force_lcd_update=true;
+#ifndef ULTIPANEL
+   force_lcd_update=false;
+#endif
+   //Serial.println((int)activeline);
+   if(force_lcd_update)
+     clear();
+  for(short line=0;line<LCD_HEIGHT;line++)
+  {
+    switch(line)
+    { 
+      case ItemM_watch:
+      {
+        if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Watch   \x7E");}
+        if((activeline==line)&&CLICKED)
+        {
+          BLOCK;
+          beepshort();
+          status=Main_Status;
+        }
+      } break;
+      case ItemM_prepare:
+      {
+        if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Prepare \x7E");}
+        if((activeline==line)&&CLICKED)
+        {
+          BLOCK;
+          status=Main_Prepare;
+          beepshort();
+        }
+      } break;
+       
+      case ItemM_control:
+      {
+        if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Control \x7E");}
+        if((activeline==line)&&CLICKED)
+        {
+          BLOCK;
+          status=Main_Control;
+          beepshort();
+        }
+      }break;
+#ifdef SDSUPPORT
+      case ItemM_file:    
+      {
+        if(force_lcd_update) 
+        {
+          lcd.setCursor(0,line);
+#ifdef CARDINSERTED
+          if(CARDINSERTED)
+#else
+          if(true)
+#endif
+          {
+            if(sdmode)
+              lcd.print(" Stop Print   \x7E");
+            else
+              lcd.print(" Card Menu    \x7E");
+          }
+          else
+          {
+           lcd.print(" No Card"); 
+          }
+        }
+        #ifdef CARDINSERTED
+        if(CARDINSERTED)
+        #endif
+        if((activeline==line)&&CLICKED)
+        {
+          sdmode = false;
+          BLOCK;
+          status=Main_SD;
+          beepshort();
+        }
+      }break;
+#endif
+      default: 
+        Serial.println('NEVER say never');
+      break;
+    }
+  }
+  if(activeline<0) activeline=0;
+  if(activeline>=LCD_HEIGHT) activeline=LCD_HEIGHT-1;
+  if((encoderpos!=lastencoderpos)||force_lcd_update)
+  {
+    lcd.setCursor(0,activeline);lcd.print(activeline?' ':' ');
+    if(encoderpos<0) encoderpos=0;
+    if(encoderpos>3*lcdslow) encoderpos=3*lcdslow;
+    activeline=abs(encoderpos/lcdslow)%LCD_HEIGHT;
+     if(activeline<0) activeline=0;
+  if(activeline>=LCD_HEIGHT) activeline=LCD_HEIGHT-1;
+    lastencoderpos=encoderpos;
+    lcd.setCursor(0,activeline);lcd.print(activeline?'>':'\003');
+  }
+
+  
+  
+}
+
+void MainMenu::update()
+{
+  static MainStatus oldstatus=Main_Menu;  //init automatically causes foce_lcd_update=true
+  static long timeoutToStatus=0;
+  static bool oldcardstatus=false;
+#ifdef CARDINSERTED
+  if((CARDINSERTED != oldcardstatus))
+  {
+    force_lcd_update=true;
+    oldcardstatus=CARDINSERTED;
+    //Serial.println("SD CHANGE");
+    if(CARDINSERTED)
+    {
+      initsd();
+      lcd_status("Card inserted");
+    }
+    else
+    {
+      sdactive=false;
+      lcd_status("Card removed");
+      
+    }
+  }
+#endif
+  if(status!=oldstatus)
+  {
+    //Serial.println(status);
+    //clear();
+    force_lcd_update=true;
+    encoderpos=0;
+    lineoffset=0;
+    
+    oldstatus=status;
+  }
+  if( (encoderpos!=lastencoderpos) || CLICKED)
+    timeoutToStatus=millis()+STATUSTIMEOUT;
+
+  switch(status)
+  { 
+      case Main_Status: 
+      {  
+        showStatus();
+        if(CLICKED)
+        {
+           linechanging=false;
+           BLOCK
+           status=Main_Menu;
+           timeoutToStatus=millis()+STATUSTIMEOUT;
+        }
+      }break;
+      case Main_Menu: 
+      {
+        showMainMenu();
+        linechanging=false;
+      }break;
+      case Main_Prepare: 
+      {
+        showPrepare(); 
+      }break;
+      case Main_Control:
+      {
+        showControl(); 
+      }break;
+      case Main_SD: 
+      {
+        showSD();
+      }break;
+  }
+  
+  if(timeoutToStatus<millis())
+    status=Main_Status;
+  force_lcd_update=false;
+  lastencoderpos=encoderpos;
+}
+
+
+
+
+//return for string conversion routines
+char conv[8];
+
+///  convert float to string with +123.4 format
+char *ftostr3(const float &x)
+{
+  //sprintf(conv,"%5.1f",x);
+  int xx=x;
+  conv[0]=(xx/100)%10+'0';
+  conv[1]=(xx/10)%10+'0';
+  conv[2]=(xx)%10+'0';
+  conv[3]=0;
+  return conv;
+}
+char *itostr2(const uint8_t &x)
+{
+  //sprintf(conv,"%5.1f",x);
+  int xx=x;
+  conv[0]=(xx/10)%10+'0';
+  conv[1]=(xx)%10+'0';
+  conv[2]=0;
+  return conv;
+}
+///  convert float to string with +123.4 format
+char *ftostr31(const float &x)
+{
+  //sprintf(conv,"%5.1f",x);
+  int xx=x*10;
+  conv[0]=(xx>=0)?'+':'-';
+  xx=abs(xx);
+  conv[1]=(xx/1000)%10+'0';
+  conv[2]=(xx/100)%10+'0';
+  conv[3]=(xx/10)%10+'0';
+  conv[4]='.';
+  conv[5]=(xx)%10+'0';
+  conv[6]=0;
+  return conv;
+}
+
+char *itostr31(const int &xx)
+{
+  //sprintf(conv,"%5.1f",x);
+  conv[0]=(xx>=0)?'+':'-';
+  conv[1]=(xx/1000)%10+'0';
+  conv[2]=(xx/100)%10+'0';
+  conv[3]=(xx/10)%10+'0';
+  conv[4]='.';
+  conv[5]=(xx)%10+'0';
+  conv[6]=0;
+  return conv;
+}
+char *itostr3(const int &xx)
+{
+  conv[0]=(xx/100)%10+'0';
+  conv[1]=(xx/10)%10+'0';
+  conv[2]=(xx)%10+'0';
+  conv[3]=0;
+  return conv;
+}
+
+char *itostr4(const int &xx)
+{
+  conv[0]=(xx/1000)%10+'0';
+  conv[1]=(xx/100)%10+'0';
+  conv[2]=(xx/10)%10+'0';
+  conv[3]=(xx)%10+'0';
+  conv[4]=0;
+  return conv;
+}
+
+///  convert float to string with +1234.5 format
+char *ftostr51(const float &x)
+{
+  int xx=x*10;
+  conv[0]=(xx>=0)?'+':'-';
+  xx=abs(xx);
+  conv[1]=(xx/10000)%10+'0';
+  conv[2]=(xx/1000)%10+'0';
+  conv[3]=(xx/100)%10+'0';
+  conv[4]=(xx/10)%10+'0';
+  conv[5]='.';
+  conv[6]=(xx)%10+'0';
+  conv[7]=0;
+  return conv;
+}
+
+char *fillto(int8_t n,char *c)
+{
+  static char ret[25];
+  bool endfound=false;
+  for(int8_t i=0;i<n;i++)
+  {
+    ret[i]=c[i];
+    if(c[i]==0)
+    {
+      endfound=true;
+    }
+    if(endfound)
+    {
+      ret[i]=' ';
+    }
+  }
+  ret[n]=0;
+  return ret;
+  
+}
+
+#else
+inline void lcd_status() {};
+#endif
+
diff --git a/Marlin/wiring.c b/Marlin/wiring.c
deleted file mode 100644 (file)
index adee6cb..0000000
+++ /dev/null
@@ -1,176 +0,0 @@
-/*
-  wiring.c - Partial implementation of the Wiring API for the ATmega8.
-  Part of Arduino - http://www.arduino.cc/
-
-  Copyright (c) 2005-2006 David A. Mellis
-
-  This library is free software; you can redistribute it and/or
-  modify it under the terms of the GNU Lesser General Public
-  License as published by the Free Software Foundation; either
-  version 2.1 of the License, or (at your option) any later version.
-
-  This library is distributed in the hope that it will be useful,
-  but WITHOUT ANY WARRANTY; without even the implied warranty of
-  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
-  Lesser General Public License for more details.
-
-  You should have received a copy of the GNU Lesser General
-  Public License along with this library; if not, write to the
-  Free Software Foundation, Inc., 59 Temple Place, Suite 330,
-  Boston, MA  02111-1307  USA
-
-  $Id: wiring.c 388 2008-03-08 22:05:23Z mellis $
-*/
-
-#include "wiring_private.h"
-
-volatile unsigned long timer0_millis = 0;
-
-SIGNAL(TIMER0_OVF_vect)
-{
-       // timer 0 prescale factor is 64 and the timer overflows at 256
-        timer0_millis++;
-}
-
-unsigned long millis()
-{
-       unsigned long m;
-       uint8_t oldSREG = SREG;
-       
-       // disable interrupts while we read timer0_millis or we might get an
-       // inconsistent value (e.g. in the middle of the timer0_millis++)
-       cli();
-       m = timer0_millis;
-       SREG = oldSREG;
-       
-       return m;
-}
-
-void delay(unsigned long ms)
-{
-       unsigned long start = millis();
-       
-       while (millis() - start <= ms)
-               ;
-}
-
-/* Delay for the given number of microseconds.  Assumes a 8 or 16 MHz clock. 
- * Disables interrupts, which will disrupt the millis() function if used
- * too frequently. */
-void delayMicroseconds(unsigned int us)
-{
-       uint8_t oldSREG;
-
-       // calling avrlib's delay_us() function with low values (e.g. 1 or
-       // 2 microseconds) gives delays longer than desired.
-       //delay_us(us);
-
-#if F_CPU >= 16000000L
-       // for the 16 MHz clock on most Arduino boards
-
-       // for a one-microsecond delay, simply return.  the overhead
-       // of the function call yields a delay of approximately 1 1/8 us.
-       if (--us == 0)
-               return;
-
-       // the following loop takes a quarter of a microsecond (4 cycles)
-       // per iteration, so execute it four times for each microsecond of
-       // delay requested.
-       us <<= 2;
-
-       // account for the time taken in the preceeding commands.
-       us -= 2;
-#else
-       // for the 8 MHz internal clock on the ATmega168
-
-       // for a one- or two-microsecond delay, simply return.  the overhead of
-       // the function calls takes more than two microseconds.  can't just
-       // subtract two, since us is unsigned; we'd overflow.
-       if (--us == 0)
-               return;
-       if (--us == 0)
-               return;
-
-       // the following loop takes half of a microsecond (4 cycles)
-       // per iteration, so execute it twice for each microsecond of
-       // delay requested.
-       us <<= 1;
-
-       // partially compensate for the time taken by the preceeding commands.
-       // we can't subtract any more than this or we'd overflow w/ small delays.
-       us--;
-#endif
-
-       // disable interrupts, otherwise the timer 0 overflow interrupt that
-       // tracks milliseconds will make us delay longer than we want.
-       oldSREG = SREG;
-       cli();
-
-       // busy wait
-       __asm__ __volatile__ (
-               "1: sbiw %0,1" "\n\t" // 2 cycles
-               "brne 1b" : "=w" (us) : "0" (us) // 2 cycles
-       );
-
-       // reenable interrupts.
-       SREG = oldSREG;
-}
-
-void init()
-{
-       // this needs to be called before setup() or some functions won't
-       // work there
-       sei();
-       
-       // on the ATmega168, timer 0 is also used for fast hardware pwm
-       // (using phase-correct PWM would mean that timer 0 overflowed half as often
-       // resulting in different millis() behavior on the ATmega8 and ATmega168)
-       sbi(TCCR0A, WGM01);
-       sbi(TCCR0A, WGM00);
-
-       // set timer 0 prescale factor to 64
-       sbi(TCCR0B, CS01);
-       sbi(TCCR0B, CS00);
-
-       // enable timer 0 overflow interrupt
-       sbi(TIMSK0, TOIE0);
-
-       // timers 1 and 2 are used for phase-correct hardware pwm
-       // this is better for motors as it ensures an even waveform
-       // note, however, that fast pwm mode can achieve a frequency of up
-       // 8 MHz (with a 16 MHz clock) at 50% duty cycle
-#if 0
-       // set timer 1 prescale factor to 64
-       sbi(TCCR1B, CS11);
-       sbi(TCCR1B, CS10);
-
-       // put timer 1 in 8-bit phase correct pwm mode
-       sbi(TCCR1A, WGM10);
-
-       // set timer 2 prescale factor to 64
-       sbi(TCCR2B, CS22);
-
-       // configure timer 2 for phase correct pwm (8-bit)
-       sbi(TCCR2A, WGM20);
-
-       // set a2d prescale factor to 128
-       // 16 MHz / 128 = 125 KHz, inside the desired 50-200 KHz range.
-       // XXX: this will not work properly for other clock speeds, and
-       // this code should use F_CPU to determine the prescale factor.
-       sbi(ADCSRA, ADPS2);
-       sbi(ADCSRA, ADPS1);
-       sbi(ADCSRA, ADPS0);
-
-       // enable a2d conversions
-       sbi(ADCSRA, ADEN);
-
-       // the bootloader connects pins 0 and 1 to the USART; disconnect them
-       // here so they can be used as normal digital i/o; they will be
-       // reconnected in Serial.begin()
-       UCSR0B = 0;
-       #if defined(__AVR_ATmega644P__)
-       //TODO: test to see if disabling this helps?
-       //UCSR1B = 0;
-       #endif
-#endif
-}
diff --git a/Marlin/wiring_serial.c b/Marlin/wiring_serial.c
deleted file mode 100644 (file)
index c027944..0000000
+++ /dev/null
@@ -1,139 +0,0 @@
-/*
-  wiring_serial.c - serial functions.
-  Part of Arduino - http://www.arduino.cc/
-
-  Copyright (c) 2005-2006 David A. Mellis
-  Modified 29 January 2009, Marius Kintel for Sanguino - http://www.sanguino.cc/
-
-  This library is free software; you can redistribute it and/or
-  modify it under the terms of the GNU Lesser General Public
-  License as published by the Free Software Foundation; either
-  version 2.1 of the License, or (at your option) any later version.
-
-  This library is distributed in the hope that it will be useful,
-  but WITHOUT ANY WARRANTY; without even the implied warranty of
-  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
-  Lesser General Public License for more details.
-
-  You should have received a copy of the GNU Lesser General
-  Public License along with this library; if not, write to the
-  Free Software Foundation, Inc., 59 Temple Place, Suite 330,
-  Boston, MA  02111-1307  USA
-
-  $Id: wiring.c 248 2007-02-03 15:36:30Z mellis $
-*/
-
-
-#include "wiring_private.h"
-
-// Define constants and variables for buffering incoming serial data.  We're
-// using a ring buffer (I think), in which rx_buffer_head is the index of the
-// location to which to write the next incoming character and rx_buffer_tail
-// is the index of the location from which to read.
-#define RX_BUFFER_SIZE 128
-#define RX_BUFFER_MASK 0x7f
-
-#if defined(__AVR_ATmega644P__)
-unsigned char rx_buffer[2][RX_BUFFER_SIZE];
-int rx_buffer_head[2] = {0, 0};
-int rx_buffer_tail[2] = {0, 0};
-#else
-unsigned char rx_buffer[1][RX_BUFFER_SIZE];
-int rx_buffer_head[1] = {0};
-int rx_buffer_tail[1] = {0};
-#endif
-
-
-#define BEGIN_SERIAL(uart_, baud_) \
-{ \
-    UBRR##uart_##H = ((F_CPU / 16 + baud / 2) / baud - 1) >> 8; \
-    UBRR##uart_##L = ((F_CPU / 16 + baud / 2) / baud - 1); \
-    \
-    /* reset config for UART */ \
-    UCSR##uart_##A = 0; \
-    UCSR##uart_##B = 0; \
-    UCSR##uart_##C = 0; \
-    \
-    /* enable rx and tx */ \
-    sbi(UCSR##uart_##B, RXEN##uart_);\
-    sbi(UCSR##uart_##B, TXEN##uart_);\
-    \
-    /* enable interrupt on complete reception of a byte */ \
-    sbi(UCSR##uart_##B, RXCIE##uart_); \
-    UCSR##uart_##C = _BV(UCSZ##uart_##1)|_BV(UCSZ##uart_##0); \
-    /* defaults to 8-bit, no parity, 1 stop bit */ \
-}
-
-void beginSerial(uint8_t uart, long baud)
-{
-  if (uart == 0) BEGIN_SERIAL(0, baud)
-#if defined(__AVR_ATmega644P__)
-  else BEGIN_SERIAL(1, baud)
-#endif
-}
-
-#define SERIAL_WRITE(uart_, c_) \
-    while (!(UCSR##uart_##A & (1 << UDRE##uart_))) \
-      ; \
-    UDR##uart_ = c
-
-void serialWrite(uint8_t uart, unsigned char c)
-{
-  if (uart == 0) {
-    SERIAL_WRITE(0, c);
-  }
-#if defined(__AVR_ATmega644P__)
-  else {
-    SERIAL_WRITE(1, c);
-  }
-#endif
-}
-
-int serialAvailable(uint8_t uart)
-{
-  return (RX_BUFFER_SIZE + rx_buffer_head[uart] - rx_buffer_tail[uart]) & RX_BUFFER_MASK;
-}
-
-int serialRead(uint8_t uart)
-{
-  // if the head isn't ahead of the tail, we don't have any characters
-  if (rx_buffer_head[uart] == rx_buffer_tail[uart]) {
-    return -1;
-  } else {
-    unsigned char c = rx_buffer[uart][rx_buffer_tail[uart]];
-    rx_buffer_tail[uart] = (rx_buffer_tail[uart] + 1) & RX_BUFFER_MASK;
-    return c;
-  }
-}
-
-void serialFlush(uint8_t uart)
-{
-  // don't reverse this or there may be problems if the RX interrupt
-  // occurs after reading the value of rx_buffer_head but before writing
-  // the value to rx_buffer_tail; the previous value of rx_buffer_head
-  // may be written to rx_buffer_tail, making it appear as if the buffer
-  // were full, not empty.
-  rx_buffer_head[uart] = rx_buffer_tail[uart];
-}
-
-#define UART_ISR(uart_) \
-ISR(USART##uart_##_RX_vect) \
-{ \
-  unsigned char c = UDR##uart_; \
-  \
-  int i = (rx_buffer_head[uart_] + 1) & RX_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 != rx_buffer_tail[uart_]) { \
-    rx_buffer[uart_][rx_buffer_head[uart_]] = c; \
-    rx_buffer_head[uart_] = i; \
-  } \
-}
-
-UART_ISR(0)
-#if defined(__AVR_ATmega644P__) 
-UART_ISR(1)
-#endif