Browse Source

Merged Marlin, Marlin non gen6 and Ultimaker changes

Erik van der Zalm 12 years ago
parent
commit
094afe7c10
22 changed files with 4802 additions and 2043 deletions
  1. 111
    38
      Marlin/Configuration.h
  2. 123
    0
      Marlin/EEPROM.h
  3. 237
    210
      Marlin/Makefile
  4. 34
    58
      Marlin/Marlin.h
  5. 417
    1297
      Marlin/Marlin.pde
  6. 1
    0
      Marlin/fastio.h
  7. 10
    0
      Marlin/lcd.h
  8. 1
    0
      Marlin/lcd.pde
  9. 83
    11
      Marlin/pins.h
  10. 584
    0
      Marlin/planner.cpp
  11. 90
    0
      Marlin/planner.h
  12. 4
    4
      Marlin/speed_lookuptable.h
  13. 592
    0
      Marlin/stepper.cpp
  14. 40
    0
      Marlin/stepper.h
  15. 84
    0
      Marlin/streaming.h
  16. 476
    0
      Marlin/temperature.cpp
  17. 55
    0
      Marlin/temperature.h
  18. 111
    110
      Marlin/thermistortables.h
  19. 156
    0
      Marlin/ultralcd.h
  20. 1593
    0
      Marlin/ultralcd.pde
  21. 0
    176
      Marlin/wiring.c
  22. 0
    139
      Marlin/wiring_serial.c

+ 111
- 38
Marlin/Configuration.h View File

@@ -1,39 +1,71 @@
1 1
 #ifndef CONFIGURATION_H
2 2
 #define CONFIGURATION_H
3 3
 
4
+//#define DEBUG_STEPS
5
+
4 6
 // BASIC SETTINGS: select your board type, thermistor type, axis scaling, and endstop configuration
5 7
 
6 8
 //// The following define selects which electronics board you have. Please choose the one that matches your setup
7
-// Gen6 = 5, 
8
-#define MOTHERBOARD 5 
9
+// MEGA/RAMPS up to 1.2 = 3,
10
+// RAMPS 1.3 = 33
11
+// Gen6 = 5,
12
+// Sanguinololu 1.2 and above = 62
13
+// Ultimaker = 7,
14
+#define MOTHERBOARD 7
15
+//#define MOTHERBOARD 5
9 16
 
10 17
 //// Thermistor settings:
11 18
 // 1 is 100k thermistor
12 19
 // 2 is 200k thermistor
13 20
 // 3 is mendel-parts thermistor
14 21
 #define THERMISTORHEATER 3
22
+// Select one of these only to define how the nozzle temp is read.
23
+//#define HEATER_USES_THERMISTOR
24
+#define HEATER_USES_AD595
25
+
26
+// Select one of these only to define how the bed temp is read.
27
+//#define BED_USES_THERMISTOR
28
+//#define BED_USES_AD595
15 29
 
30
+#define HEATER_CHECK_INTERVAL 50
31
+#define BED_CHECK_INTERVAL 5000
32
+#define BNUMTEMPS NUMTEMPS
33
+#define bedtemptable temptable
16 34
 
17
-//// Calibration variables
18
-// X, Y, Z, E steps per unit - Metric Mendel / Orca with V9 extruder:
19
-float axis_steps_per_unit[] = {40, 40, 3333.92, 67}; 
20
-// For E steps per unit = 67 for v9 with direct drive (needs finetuning) for other extruders this needs to be changed 
21
-// Metric Prusa Mendel with Makergear geared stepper extruder:
22
-//float axis_steps_per_unit[] = {80,80,3200/1.25,1380}; 
23 35
 
24 36
 //// Endstop Settings
25 37
 #define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
26 38
 // The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
27
-const bool ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops. 
39
+const bool ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. 
28 40
 // For optos H21LOB set to true, for Mendel-Parts newer optos TCST2103 set to false
29 41
 
30 42
 // This determines the communication speed of the printer
31
-#define BAUDRATE 250000
43
+//#define BAUDRATE 250000
44
+#define BAUDRATE 115200
45
+//#define BAUDRATE 230400
32 46
 
33 47
 // Comment out (using // at the start of the line) to disable SD support:
34
-//#define SDSUPPORT
48
+
49
+// #define ULTRA_LCD  //any lcd 
50
+#define LCD_WIDTH 16
51
+#define LCD_HEIGHT 2
52
+
53
+#define ULTIPANEL
54
+#ifdef ULTIPANEL
55
+ //#define NEWPANEL  //enable this if you have a click-encoder panel
56
+ #define SDSUPPORT
57
+ #define ULTRA_LCD
58
+ #define LCD_WIDTH 20
59
+#define LCD_HEIGHT 4
60
+#endif
61
+
62
+
63
+//#define SDSUPPORT // Enable SD Card Support in Hardware Console
35 64
 
36 65
 
66
+
67
+const int dropsegments=5; //everything with this number of steps  will be ignored as move
68
+
37 69
 //// ADVANCED SETTINGS - to tweak parameters
38 70
 
39 71
 #include "thermistortables.h"
@@ -47,14 +79,14 @@ const bool ENDSTOPS_INVERTING = false; // set to true to invert the logic of the
47 79
 // Disables axis when it's not being used.
48 80
 #define DISABLE_X false
49 81
 #define DISABLE_Y false
50
-#define DISABLE_Z true
82
+#define DISABLE_Z false
51 83
 #define DISABLE_E false
52 84
 
53 85
 // Inverting axis direction
54 86
 #define INVERT_X_DIR true    // for Mendel set to false, for Orca set to true
55 87
 #define INVERT_Y_DIR false   // for Mendel set to true, for Orca set to false
56 88
 #define INVERT_Z_DIR true    // for Mendel set to false, for Orca set to true
57
-#define INVERT_E_DIR true   // for direct drive extruder v9 set to true, for geared extruder set to false
89
+#define INVERT_E_DIR false   // for direct drive extruder v9 set to true, for geared extruder set to false
58 90
 
59 91
 //// ENDSTOP SETTINGS:
60 92
 // 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
63 95
 #define Z_HOME_DIR -1
64 96
 
65 97
 #define min_software_endstops false //If true, axis won't move to coordinates less than zero.
66
-#define max_software_endstops true  //If true, axis won't move to coordinates greater than the defined lengths below.
67
-#define X_MAX_LENGTH 200
68
-#define Y_MAX_LENGTH 200
69
-#define Z_MAX_LENGTH 100
98
+#define max_software_endstops false  //If true, axis won't move to coordinates greater than the defined lengths below.
99
+#define X_MAX_LENGTH 210
100
+#define Y_MAX_LENGTH 210
101
+#define Z_MAX_LENGTH 210
70 102
 
71 103
 //// MOVEMENT SETTINGS
72 104
 #define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
73
-float max_feedrate[] = {60000, 60000, 100, 500000}; // set the max speeds
74
-float homing_feedrate[] = {2400, 2400, 80, 0};  // set the homing speeds
75
-bool axis_relative_modes[] = {false, false, false, false};
76
-
77
-//// Acceleration settings
78
-// 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.
79
-float acceleration = 2000;         // Normal acceleration mm/s^2
80
-float retract_acceleration = 7000; // Normal acceleration mm/s^2
81
-float max_xy_jerk = 20.0*60;
82
-float max_z_jerk = 0.4*60;
83
-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
105
+//note: on bernhards ultimaker 200 200 12 are working well.
106
+#define HOMING_FEEDRATE {50*60, 50*60, 12*60, 0}  // set the homing speeds
107
+//the followint checks if an extrusion is existent in the move. if _not_, the speed of the move is set to the maximum speed. 
108
+//!!!!!!Use only if you know that your printer works at the maximum declared speeds.
109
+// works around the skeinforge cool-bug. There all moves are slowed to have a minimum layer time. However slow travel moves= ooze
110
+#define TRAVELING_AT_MAXSPEED  
111
+#define AXIS_RELATIVE_MODES {false, false, false, false}
112
+
113
+#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step)
114
+
115
+// default settings 
116
+
117
+#define DEFAULT_AXIS_STEPS_PER_UNIT   {79.87220447,79.87220447,200*8/3,14}                    // default steps per unit for ultimaker 
118
+#define DEFAULT_MAX_FEEDRATE          {160*60, 160*60, 10*60, 500000}        
119
+#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.
120
+
121
+#define DEFAULT_ACCELERATION          3000    // X, Y, Z and E max acceleration in mm/s^2 for printing moves 
122
+#define DEFAULT_RETRACT_ACCELERATION  7000   // X, Y, Z and E max acceleration in mm/s^2 for r retracts
123
+
124
+#define DEFAULT_MINIMUMFEEDRATE       10     // minimum feedrate
125
+#define DEFAULT_MINTRAVELFEEDRATE     10
126
+
127
+// 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.
128
+#define DEFAULT_MINSEGMENTTIME        20000
129
+#define DEFAULT_XYJERK                30.0*60    
130
+#define DEFAULT_ZJERK                 10.0*60
131
+
84 132
 
85 133
 // The watchdog waits for the watchperiod in milliseconds whenever an M104 or M109 increases the target temperature
134
+//this enables the watchdog interrupt.
135
+#define USE_WATCHDOG
136
+//you cannot reboot on a mega2560 due to a bug in he bootloader. Hence, you have to reset manually, and this is done hereby:
137
+#define RESET_MANUAL
138
+
139
+#define WATCHDOG_TIMEOUT 4
140
+
141
+
86 142
 // 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
87 143
 //#define WATCHPERIOD 5000 //5 seconds
88 144
 
89 145
 //// The minimal temperature defines the temperature below which the heater will not be enabled
90 146
 #define MINTEMP 5
147
+#define BED_MINTEMP 5
91 148
 
92 149
 
93 150
 // When temperature exceeds max temp, your heater will be switched off.
94 151
 // This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
95 152
 // You should use MINTEMP for thermistor short/failure protection.
96 153
 #define MAXTEMP 275
97
-
154
+#define BED_MAXTEMP 150
98 155
 
99 156
 /// PID settings:
100 157
 // Uncomment the following line to enable PID support.
101
-//#define PIDTEMP
158
+//#define SMOOTHING
159
+//#define SMOOTHFACTOR 5.0
160
+//float current_raw_average=0;
161
+
162
+#define PIDTEMP
102 163
 #ifdef PIDTEMP
103
-//#define PID_DEBUG 1 // Sends debug data to the serial port. 
164
+//#define PID_DEBUG // Sends debug data to the serial port. 
104 165
 //#define PID_OPENLOOP 1 // Puts PID in open loop. M104 sets the output power in %
105
-#define PID_MAX 156 // limits current to nozzle
106
-#define PID_INTEGRAL_DRIVE_MAX 156.0
107
-#define PID_dT 0.16
108
-double Kp = 20.0;
109
-double Ki = 1.5*PID_dT;
110
-double Kd = 80/PID_dT;
166
+#define PID_MAX 255 // limits current to nozzle
167
+#define PID_INTEGRAL_DRIVE_MAX 255
168
+#define PID_dT 0.10 // 100ms sample time
169
+#define DEFAULT_Kp 20.0
170
+#define DEFAULT_Ki 1.5*PID_dT
171
+#define DEFAULT_Kd 80/PID_dT
172
+#define DEFAULT_Kc 0
111 173
 #endif // PIDTEMP
112 174
 
113 175
 
@@ -121,7 +183,7 @@ double Kd = 80/PID_dT;
121 183
 //#define ADVANCE
122 184
 
123 185
 #ifdef ADVANCE
124
-#define EXTRUDER_ADVANCE_K 0.02
186
+#define EXTRUDER_ADVANCE_K .3
125 187
 
126 188
 #define D_FILAMENT 1.7
127 189
 #define STEPS_MM_E 65
@@ -130,4 +192,15 @@ double Kd = 80/PID_dT;
130 192
 
131 193
 #endif // ADVANCE
132 194
 
195
+#if defined SDSUPPORT
196
+// The number of linear motions that can be in the plan at any give time.  
197
+  #define BLOCK_BUFFER_SIZE 16   // SD,LCD,Buttons take more memory, block buffer needs to be smaller
198
+#else
199
+  #define BLOCK_BUFFER_SIZE 16 // maximize block buffer
200
+#endif
201
+
202
+#ifdef SIMPLE_LCD
203
+  #define BLOCK_BUFFER_SIZE 16 // A little less buffer for just a simple LCD
204
+#endif
205
+
133 206
 #endif

+ 123
- 0
Marlin/EEPROM.h View File

@@ -0,0 +1,123 @@
1
+
2
+#include "planner.h"
3
+#include "temperature.h"
4
+
5
+//======================================================================================
6
+template <class T> int EEPROM_writeAnything(int &ee, const T& value)
7
+{
8
+    const byte* p = (const byte*)(const void*)&value;
9
+    int i;
10
+    for (i = 0; i < sizeof(value); i++)
11
+	  EEPROM.write(ee++, *p++);
12
+    return i;
13
+}
14
+//======================================================================================
15
+template <class T> int EEPROM_readAnything(int &ee, T& value)
16
+{
17
+    byte* p = (byte*)(void*)&value;
18
+    int i;
19
+    for (i = 0; i < sizeof(value); i++)
20
+	  *p++ = EEPROM.read(ee++);
21
+    return i;
22
+}
23
+//======================================================================================
24
+
25
+#define EEPROM_OFFSET 100
26
+
27
+#define EEPROM_VERSION "V04"  // IMPORTANT:  Whenever there are changes made to the variables stored in EEPROM
28
+                              // in the functions below, also increment the version number. This makes sure that
29
+                              // the default values are used whenever there is a change to the data, to prevent
30
+                              // wrong data being written to the variables.
31
+                              // ALSO:  always make sure the variables in the Store and retrieve sections are in the same order.
32
+void StoreSettings() {
33
+  char ver[4]= "000";
34
+  int i=EEPROM_OFFSET;
35
+  EEPROM_writeAnything(i,ver); // invalidate data first 
36
+  EEPROM_writeAnything(i,axis_steps_per_unit);  
37
+  EEPROM_writeAnything(i,max_feedrate);  
38
+  EEPROM_writeAnything(i,max_acceleration_units_per_sq_second);
39
+  EEPROM_writeAnything(i,acceleration);
40
+  EEPROM_writeAnything(i,retract_acceleration);
41
+  EEPROM_writeAnything(i,minimumfeedrate);
42
+  EEPROM_writeAnything(i,mintravelfeedrate);
43
+  EEPROM_writeAnything(i,minsegmenttime);
44
+  EEPROM_writeAnything(i,max_xy_jerk);
45
+  EEPROM_writeAnything(i,max_z_jerk);
46
+  #ifdef PIDTEMP
47
+  EEPROM_writeAnything(i,Kp);
48
+  EEPROM_writeAnything(i,Ki);
49
+  EEPROM_writeAnything(i,Kd);
50
+#else
51
+  EEPROM_writeAnything(i,3000);
52
+  EEPROM_writeAnything(i,0);
53
+  EEPROM_writeAnything(i,0);
54
+#endif
55
+  char ver2[4]=EEPROM_VERSION;
56
+  i=EEPROM_OFFSET;
57
+  EEPROM_writeAnything(i,ver2); // validate data
58
+   ECHOLN("Settings Stored");
59
+
60
+}
61
+
62
+void RetrieveSettings(bool def=false){  // if def=true, the default values will be used
63
+  int i=EEPROM_OFFSET;
64
+  char stored_ver[4];
65
+  char ver[4]=EEPROM_VERSION;
66
+  EEPROM_readAnything(i,stored_ver); //read stored version
67
+//  ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]");
68
+  if ((!def)&&(strncmp(ver,stored_ver,3)==0)) {   // version number match
69
+      EEPROM_readAnything(i,axis_steps_per_unit);  
70
+      EEPROM_readAnything(i,max_feedrate);  
71
+      EEPROM_readAnything(i,max_acceleration_units_per_sq_second);
72
+      EEPROM_readAnything(i,acceleration);
73
+      EEPROM_readAnything(i,retract_acceleration);
74
+      EEPROM_readAnything(i,minimumfeedrate);
75
+      EEPROM_readAnything(i,mintravelfeedrate);
76
+      EEPROM_readAnything(i,minsegmenttime);
77
+      EEPROM_readAnything(i,max_xy_jerk);
78
+      EEPROM_readAnything(i,max_z_jerk);
79
+#ifndef PIDTEMP
80
+      float Kp,Ki,Kd;
81
+#endif
82
+      EEPROM_readAnything(i,Kp);
83
+      EEPROM_readAnything(i,Ki);
84
+      EEPROM_readAnything(i,Kd);
85
+
86
+      ECHOLN("Stored settings retreived:");
87
+  }
88
+  else {
89
+    float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT;
90
+    float tmp2[]=DEFAULT_MAX_FEEDRATE;
91
+    long tmp3[]=DEFAULT_MAX_ACCELERATION;
92
+    for (int i=0;i<4;i++) {
93
+      axis_steps_per_unit[i]=tmp1[i];  
94
+      max_feedrate[i]=tmp2[i];  
95
+      max_acceleration_units_per_sq_second[i]=tmp3[i];
96
+    }
97
+    acceleration=DEFAULT_ACCELERATION;
98
+    retract_acceleration=DEFAULT_RETRACT_ACCELERATION;
99
+    minimumfeedrate=DEFAULT_MINIMUMFEEDRATE;
100
+    minsegmenttime=DEFAULT_MINSEGMENTTIME;       
101
+    mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
102
+    max_xy_jerk=DEFAULT_XYJERK;
103
+    max_z_jerk=DEFAULT_ZJERK;
104
+    ECHOLN("Using Default settings:");
105
+  }
106
+  ECHOLN("Steps per unit:");
107
+  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));
108
+  ECHOLN("Maximum feedrates (mm/s):");
109
+  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));
110
+  ECHOLN("Maximum Acceleration (mm/s2):");
111
+  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));
112
+  ECHOLN("Acceleration: S=acceleration, T=retract acceleration");
113
+  ECHOLN("   M204 S"  <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2));
114
+  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)");
115
+  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));
116
+#ifdef PIDTEMP
117
+  ECHOLN("PID settings:");
118
+  ECHOLN("   M301 P"  << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));  
119
+#endif
120
+  
121
+}  
122
+
123
+

+ 237
- 210
Marlin/Makefile View File

@@ -1,247 +1,274 @@
1
-# Marlin Arduino Project Makefile
2
-# 
3
-# Makefile Based on:
4
-# Arduino 0011 Makefile
5
-# Arduino adaptation by mellis, eighthave, oli.keller
6 1
 #
7
-# This has been tested with Arduino 0022.
8
-# 
9
-# This makefile allows you to build sketches from the command line
10
-# without the Arduino environment (or Java).
2
+# Arduino 0022 Makefile 
3
+# Uno with DOGS102 Shield
11 4
 #
12
-# Detailed instructions for using the makefile:
5
+# written by olikraus@gmail.com
13 6
 #
14
-#  1. Modify the line containg "INSTALL_DIR" to point to the directory that
15
-#     contains the Arduino installation (for example, under Mac OS X, this
16
-#     might be /Applications/arduino-0012).
7
+# Features:
8
+#   - boards.txt is used to derive parameters
9
+#   - All intermediate files are put into a separate directory (TMPDIRNAME)
10
+#   - Simple use: Copy Makefile into the same directory of the .pde file
17 11
 #
18
-#  2. Modify the line containing "PORT" to refer to the filename
19
-#     representing the USB or serial connection to your Arduino board
20
-#     (e.g. PORT = /dev/tty.USB0).  If the exact name of this file
21
-#     changes, you can use * as a wildcard (e.g. PORT = /dev/tty.usb*).
12
+# Limitations:
13
+#   - requires UNIX environment
14
+#   - TMPDIRNAME must be subdirectory of the current directory.
22 15
 #
23
-#  3. Set the line containing "MCU" to match your board's processor. 
24
-#     Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth
25
-#     or Diecimila have the atmega168.  If you're using a LilyPad Arduino,
26
-#     change F_CPU to 8000000.
16
+# Targets
17
+# 	all		build everything
18
+#	upload	build and upload to arduino
19
+#	clean	remove all temporary files (includes final hex file)
27 20
 #
28
-#  4. Type "make" and press enter to compile/verify your program.
21
+# History
22
+#	001	28 Apr 2010	first  release
23
+#	002  05 Oct 2010	added 'uno'
29 24
 #
30
-#  5. Type "make upload", reset your Arduino board, and press enter to
31
-#     upload your program to the Arduino board.
32
-#
33
-# $Id$
34
-
35
-TARGET = Marlin
36
-INSTALL_DIR = ../../Desktop/arduino-0018/
37
-UPLOAD_RATE = 38400
38
-AVRDUDE_PROGRAMMER = stk500v1
39
-PORT = /dev/ttyUSB0
40
-#MCU = atmega2560
41
-#For "old" Arduino Mega
42
-#MCU = atmega1280
43
-#For Sanguinololu
44
-MCU = atmega644p 
45
-F_CPU = 16000000
46
-
47
-
48
-############################################################################
49
-# Below here nothing should be changed...
50
-
51
-ARDUINO = $(INSTALL_DIR)/hardware/Sanguino/cores/arduino
52
-AVR_TOOLS_PATH = $(INSTALL_DIR)/hardware/tools/avr/bin
53
-SRC =  $(ARDUINO)/pins_arduino.c wiring.c wiring_serial.c \
54
-$(ARDUINO)/wiring_analog.c $(ARDUINO)/wiring_digital.c \
55
-$(ARDUINO)/wiring_pulse.c \
56
-$(ARDUINO)/wiring_shift.c $(ARDUINO)/WInterrupts.c
57
-CXXSRC = $(ARDUINO)/HardwareSerial.cpp $(ARDUINO)/WMath.cpp \
58
-$(ARDUINO)/Print.cpp ./SdFile.cpp ./SdVolume.cpp ./Sd2Card.cpp
59
-FORMAT = ihex
60
-
61
-
62
-# Name of this Makefile (used for "make depend").
63
-MAKEFILE = Makefile
64
-
65
-# Debugging format.
66
-# Native formats for AVR-GCC's -g are stabs [default], or dwarf-2.
67
-# AVR (extended) COFF requires stabs, plus an avr-objcopy run.
68
-DEBUG = stabs
69
-
70
-OPT = s
71
-
72
-# Place -D or -U options here
73
-CDEFS = -DF_CPU=$(F_CPU)
74
-CXXDEFS = -DF_CPU=$(F_CPU)
75
-
76
-# Place -I options here
77
-CINCS = -I$(ARDUINO)
78
-CXXINCS = -I$(ARDUINO)
79
-
80
-# Compiler flag to set the C Standard level.
81
-# c89   - "ANSI" C
82
-# gnu89 - c89 plus GCC extensions
83
-# c99   - ISO C99 standard (not yet fully implemented)
84
-# gnu99 - c99 plus GCC extensions
85
-#CSTANDARD = -std=gnu99
86
-CDEBUG = -g$(DEBUG)
87
-CWARN = -Wall -Wunused-variable
88
-CTUNING = -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -w -ffunction-sections -fdata-sections -DARDUINO=22
89
-#CEXTRA = -Wa,-adhlns=$(<:.c=.lst)
90
-
91
-CFLAGS = $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CEXTRA) $(CTUNING)
92
-CXXFLAGS = $(CDEFS) $(CINCS) -O$(OPT) -Wall $(CEXTRA) $(CTUNING)
93
-#ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs 
94
-LDFLAGS = -lm
95
-
96
-
97
-# Programming support using avrdude. Settings and variables.
98
-AVRDUDE_PORT = $(PORT)
99
-AVRDUDE_WRITE_FLASH = -U flash:w:applet/$(TARGET).hex:i
100
-AVRDUDE_FLAGS = -D -C $(INSTALL_DIR)/hardware/tools/avrdude.conf \
101
--p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) \
102
--b $(UPLOAD_RATE)
103
-
104
-# Program settings
105
-CC = $(AVR_TOOLS_PATH)/avr-gcc
106
-CXX = $(AVR_TOOLS_PATH)/avr-g++
107
-OBJCOPY = $(AVR_TOOLS_PATH)/avr-objcopy
108
-OBJDUMP = $(AVR_TOOLS_PATH)/avr-objdump
109
-AR  = $(AVR_TOOLS_PATH)/avr-ar
110
-SIZE = $(AVR_TOOLS_PATH)/avr-size
111
-NM = $(AVR_TOOLS_PATH)/avr-nm
112
-AVRDUDE = $(INSTALL_DIR)/hardware/tools/avrdude
113
-REMOVE = rm -f
114
-MV = mv -f
115
-
116
-# Define all object files.
117
-OBJ = $(SRC:.c=.o) $(CXXSRC:.cpp=.o) $(ASRC:.S=.o) 
118
-
119
-# Define all listing files.
120
-LST = $(ASRC:.S=.lst) $(CXXSRC:.cpp=.lst) $(SRC:.c=.lst)
121
-
122
-# Combine all necessary flags and optional flags.
123
-# Add target processor to flags.
124
-ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS)
125
-ALL_CXXFLAGS = -mmcu=$(MCU) -I. $(CXXFLAGS)
126
-ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
127
-
128
-
129
-# Default target.
130
-all: applet_files_ez build sizeafter
131
-
132
-build: elf hex 
133
-
134
-applet_files_ez: $(TARGET).pde
135
-	# Here is the "preprocessing".
136
-	# It creates a .cpp file based with the same name as the .pde file.
137
-	# On top of the new .cpp file comes the WProgram.h header.
138
-	# At the end there is a generic main() function attached.
139
-	# Then the .cpp file will be compiled. Errors during compile will
140
-	# refer to this new, automatically generated, file. 
141
-	# Not the original .pde file you actually edit...
142
-	test -d applet || mkdir applet
143
-	echo '#include "WProgram.h"' > applet/$(TARGET).cpp
144
-	cat $(TARGET).pde >> applet/$(TARGET).cpp
145
-	cat $(ARDUINO)/main.cpp >> applet/$(TARGET).cpp
146
-
147
-elf: applet/$(TARGET).elf
148
-hex: applet/$(TARGET).hex
149
-eep: applet/$(TARGET).eep
150
-lss: applet/$(TARGET).lss 
151
-sym: applet/$(TARGET).sym
152 25
 
153
-# Program the device.  
154
-upload: applet/$(TARGET).hex
155
-	$(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH)
26
+#=== user configuration ===
27
+# All ...PATH variables must have a '/' at the end
156 28
 
29
+# Board (and prozessor) information: see $(ARDUINO_PATH)hardware/arduino/boards.txt
30
+# Some examples:
31
+#	BOARD		DESCRIPTION
32
+#	uno			Arduino Uno
33
+#	atmega328	Arduino Duemilanove or Nano w/ ATmega328
34
+#	diecimila		Arduino Diecimila, Duemilanove, or Nano w/ ATmega168
35
+#	mega		Arduino Mega
36
+#	mini			Arduino Mini
37
+#	lilypad328	LilyPad Arduino w/ ATmega328  
38
+BOARD:=mega
157 39
 
158
-	# Display size of file.
159
-HEXSIZE = $(SIZE) --target=$(FORMAT) applet/$(TARGET).hex
160
-ELFSIZE = $(SIZE)  applet/$(TARGET).elf
161
-sizebefore:
162
-	@if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(HEXSIZE); echo; fi
40
+# additional (comma separated) defines 
41
+# -DDOGM128_HW		board is connected to DOGM128 display
42
+# -DDOGM132_HW		board is connected to DOGM132 display
43
+# -DDOGS102_HW		board is connected to DOGS102 display
44
+# -DDOG_REVERSE		180 degree rotation
45
+# -DDOG_SPI_SW_ARDUINO	force SW shiftOut
46
+DEFS=-DDOGS102_HW -DDOG_DOUBLE_MEMORY -DDOG_SPI_SW_ARDUINO
163 47
 
164
-sizeafter:
165
-	@if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(HEXSIZE); echo; fi
48
+# The location where the avr tools (e.g. avr-gcc) are located. Requires a '/' at the end.
49
+# Can be empty if all tools are accessable through the search path
50
+AVR_TOOLS_PATH:=/usr/bin/
51
+
52
+# Install path of the arduino software. Requires a '/' at the end.
53
+ARDUINO_PATH:=/home/bkubicek/software/arduino-0022/
54
+
55
+# Install path for avrdude. Requires a '/' at the end. Can be empty if avrdude is in the search path.
56
+AVRDUDE_PATH:= 
57
+
58
+# The unix device where we can reach the arduino board
59
+# Uno: /dev/ttyACM0
60
+# Duemilanove: /dev/ttyUSB0
61
+AVRDUDE_PORT:=/dev/ttyACM0
62
+
63
+# List of all libaries which should be included.
64
+#EXTRA_DIRS=$(ARDUINO_PATH)libraries/LiquidCrystal/
65
+#EXTRA_DIRS+=$(ARDUINO_PATH)libraries/Dogm/
66
+#EXTRA_DIRS+=/home/kraus/src/arduino/dogm128/hg/libraries/Dogm/
67
+
68
+#=== fetch parameter from boards.txt processor parameter ===
69
+# the basic idea is to get most of the information from boards.txt
166 70
 
71
+BOARDS_TXT:=$(ARDUINO_PATH)hardware/arduino/boards.txt
72
+
73
+# get the MCU value from the $(BOARD).build.mcu variable. For the atmega328 board this is atmega328p
74
+MCU:=$(shell sed -n -e "s/$(BOARD).build.mcu=\(.*\)/\1/p" $(BOARDS_TXT))
75
+# get the F_CPU value from the $(BOARD).build.f_cpu variable. For the atmega328 board this is 16000000
76
+F_CPU:=$(shell sed -n -e "s/$(BOARD).build.f_cpu=\(.*\)/\1/p" $(BOARDS_TXT))
167 77
 
168
-# Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
169
-COFFCONVERT=$(OBJCOPY) --debugging \
170
---change-section-address .data-0x800000 \
171
---change-section-address .bss-0x800000 \
172
---change-section-address .noinit-0x800000 \
173
---change-section-address .eeprom-0x810000 
78
+# avrdude
79
+# get the AVRDUDE_UPLOAD_RATE value from the $(BOARD).upload.speed variable. For the atmega328 board this is 57600
80
+AVRDUDE_UPLOAD_RATE:=$(shell sed -n -e "s/$(BOARD).upload.speed=\(.*\)/\1/p" $(BOARDS_TXT))
81
+# get the AVRDUDE_PROGRAMMER value from the $(BOARD).upload.protocol variable. For the atmega328 board this is stk500
82
+# AVRDUDE_PROGRAMMER:=$(shell sed -n -e "s/$(BOARD).upload.protocol=\(.*\)/\1/p" $(BOARDS_TXT))
83
+# use stk500v1, because stk500 will default to stk500v2
84
+AVRDUDE_PROGRAMMER:=stk500v1
174 85
 
86
+#=== identify user files ===
87
+PDESRC:=$(shell ls *.pde)
88
+TARGETNAME=$(basename $(PDESRC))
175 89
 
176
-coff: applet/$(TARGET).elf
177
-	$(COFFCONVERT) -O coff-avr applet/$(TARGET).elf $(TARGET).cof
90
+CDIRS:=$(EXTRA_DIRS) $(addsuffix utility/,$(EXTRA_DIRS))
91
+CDIRS:=*.c utility/*.c $(addsuffix *.c,$(CDIRS)) $(ARDUINO_PATH)hardware/arduino/cores/arduino/*.c
92
+CSRC:=$(shell ls $(CDIRS) 2>/dev/null)
178 93
 
94
+CCSRC:=$(shell ls *.cc 2>/dev/null)
179 95
 
180
-extcoff: $(TARGET).elf
181
-	$(COFFCONVERT) -O coff-ext-avr applet/$(TARGET).elf $(TARGET).cof
96
+CPPDIRS:=$(EXTRA_DIRS) $(addsuffix utility/,$(EXTRA_DIRS))
97
+CPPDIRS:=*.cpp utility/*.cpp $(addsuffix *.cpp,$(CPPDIRS)) $(ARDUINO_PATH)hardware/arduino/cores/arduino/*.cpp 
98
+CPPSRC:=$(shell ls $(CPPDIRS) 2>/dev/null)
182 99
 
100
+#=== build internal variables ===
183 101
 
184
-.SUFFIXES: .elf .hex .eep .lss .sym
102
+# the name of the subdirectory where everything is stored
103
+TMPDIRNAME:=tmp
104
+TMPDIRPATH:=$(TMPDIRNAME)/
105
+
106
+AVRTOOLSPATH:=$(AVR_TOOLS_PATH)
107
+
108
+OBJCOPY:=$(AVRTOOLSPATH)avr-objcopy
109
+OBJDUMP:=$(AVRTOOLSPATH)avr-objdump
110
+SIZE:=$(AVRTOOLSPATH)avr-size
111
+
112
+CPPSRC:=$(addprefix $(TMPDIRPATH),$(PDESRC:.pde=.cpp)) $(CPPSRC)
113
+
114
+COBJ:=$(CSRC:.c=.o)
115
+CCOBJ:=$(CCSRC:.cc=.o)
116
+CPPOBJ:=$(CPPSRC:.cpp=.o)
117
+
118
+OBJFILES:=$(COBJ)  $(CCOBJ)  $(CPPOBJ)
119
+DIRS:= $(dir $(OBJFILES))
120
+
121
+DEPFILES:=$(OBJFILES:.o=.d)
122
+# assembler files from avr-gcc -S
123
+ASSFILES:=$(OBJFILES:.o=.s)
124
+# disassembled object files with avr-objdump -S
125
+DISFILES:=$(OBJFILES:.o=.dis)
185 126
 
186
-.elf.hex:
187
-	$(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
188 127
 
189
-.elf.eep:
190
-	-$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
191
-	--change-section-lma .eeprom=0 -O $(FORMAT) $< $@
128
+LIBNAME:=$(TMPDIRPATH)$(TARGETNAME).a
129
+ELFNAME:=$(TMPDIRPATH)$(TARGETNAME).elf
130
+HEXNAME:=$(TMPDIRPATH)$(TARGETNAME).hex
192 131
 
193
-# Create extended listing file from ELF output file.
194
-.elf.lss:
195
-	$(OBJDUMP) -h -S $< > $@
132
+AVRDUDE_FLAGS = -V -F
133
+AVRDUDE_FLAGS += -C $(ARDUINO_PATH)/hardware/tools/avrdude.conf 
134
+AVRDUDE_FLAGS += -p $(MCU)
135
+AVRDUDE_FLAGS += -P $(AVRDUDE_PORT)
136
+AVRDUDE_FLAGS += -c $(AVRDUDE_PROGRAMMER) 
137
+AVRDUDE_FLAGS += -b $(AVRDUDE_UPLOAD_RATE)
138
+AVRDUDE_FLAGS += -U flash:w:$(HEXNAME)
196 139
 
197
-# Create a symbol table from ELF output file.
198
-.elf.sym:
199
-	$(NM) -n $< > $@
140
+AVRDUDE = avrdude
200 141
 
201
-	# Link: create ELF output file from library.
202
-applet/$(TARGET).elf: $(TARGET).pde applet/core.a 
203
-	$(CC) $(ALL_CFLAGS) -Wl,--gc-sections -o $@ applet/$(TARGET).cpp -L. applet/core.a $(LDFLAGS)
142
+#=== predefined variable override ===
143
+# use "make -p -f/dev/null" to see the default rules and definitions
204 144
 
205
-applet/core.a: $(OBJ)
206
-	@for i in $(OBJ); do echo $(AR) rcs applet/core.a $$i; $(AR) rcs applet/core.a $$i; done
145
+# Build C and C++ flags. Include path information must be placed here
146
+COMMON_FLAGS = -DF_CPU=$(F_CPU) -mmcu=$(MCU) $(DEFS)
147
+# COMMON_FLAGS += -gdwarf-2
148
+COMMON_FLAGS += -Os
149
+COMMON_FLAGS += -Wall -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums
150
+COMMON_FLAGS += -I. 
151
+COMMON_FLAGS += -I$(ARDUINO_PATH)hardware/arduino/cores/arduino
152
+COMMON_FLAGS += $(addprefix -I,$(EXTRA_DIRS))
153
+COMMON_FLAGS += -ffunction-sections -fdata-sections -Wl,--gc-sections
154
+COMMON_FLAGS += -Wl,--relax
155
+COMMON_FLAGS += -mcall-prologues
207 156
 
157
+CFLAGS = $(COMMON_FLAGS) -std=gnu99 -Wstrict-prototypes  
158
+CXXFLAGS = $(COMMON_FLAGS) 
208 159
 
160
+# Replace standard build tools by avr tools
161
+CC = $(AVRTOOLSPATH)avr-gcc
162
+CXX = $(AVRTOOLSPATH)avr-g++
163
+AR  = @$(AVRTOOLSPATH)avr-ar
209 164
 
210
-# Compile: create object files from C++ source files.
211
-.cpp.o:
212
-	$(CXX) -c $(ALL_CXXFLAGS) $< -o $@ 
213 165
 
214
-# Compile: create object files from C source files.
215
-.c.o:
216
-	$(CC) -c $(ALL_CFLAGS) $< -o $@ 
166
+# "rm" must be able to delete a directory tree
167
+RM = rm -rf 
217 168
 
169
+#=== rules ===
218 170
 
219
-# Compile: create assembler files from C source files.
220
-.c.s:
221
-	$(CC) -S $(ALL_CFLAGS) $< -o $@
171
+# add rules for the C/C++ files where the .o file is placed in the TMPDIRPATH
172
+# reuse existing variables as far as possible
222 173
 
174
+$(TMPDIRPATH)%.o: %.c
175
+	@echo compile $<
176
+	@$(COMPILE.c) $(OUTPUT_OPTION) $<
177
+
178
+$(TMPDIRPATH)%.o: %.cc
179
+	@echo compile $< 
180
+	@$(COMPILE.cc) $(OUTPUT_OPTION) $<
181
+
182
+$(TMPDIRPATH)%.o: %.cpp
183
+	@echo compile $<
184
+	@$(COMPILE.cpp) $(OUTPUT_OPTION) $<
185
+
186
+$(TMPDIRPATH)%.s: %.c
187
+	@$(COMPILE.c) $(OUTPUT_OPTION) -S $<
188
+
189
+$(TMPDIRPATH)%.s: %.cc
190
+	@$(COMPILE.cc) $(OUTPUT_OPTION) -S $<
191
+
192
+$(TMPDIRPATH)%.s: %.cpp
193
+	@$(COMPILE.cpp) $(OUTPUT_OPTION) -S $<
194
+
195
+$(TMPDIRPATH)%.dis: $(TMPDIRPATH)%.o
196
+	@$(OBJDUMP) -S $< > $@
197
+
198
+.SUFFIXES: .elf .hex .pde
199
+
200
+.elf.hex:
201
+	@$(OBJCOPY) -O ihex -R .eeprom $< $@
202
+	
203
+$(TMPDIRPATH)%.cpp: %.pde
204
+	@cat $(ARDUINO_PATH)hardware/arduino/cores/arduino/main.cpp > $@
205
+	@cat $< >> $@
206
+	@echo >> $@
207
+	@echo 'extern "C" void __cxa_pure_virtual() { while (1); }' >> $@
223 208
 
224
-# Assemble: create object files from assembler source files.
225
-.S.o:
226
-	$(CC) -c $(ALL_ASFLAGS) $< -o $@
227 209
 
210
+.PHONY: all
211
+all: tmpdir $(HEXNAME) assemblersource showsize
212
+	ls -al $(HEXNAME) $(ELFNAME)
228 213
 
214
+$(ELFNAME): $(LIBNAME)($(addprefix $(TMPDIRPATH),$(OBJFILES))) 
215
+	$(LINK.o) $(COMMON_FLAGS) $(LIBNAME) $(LOADLIBES) $(LDLIBS) -o $@
229 216
 
230
-# Target: clean project.
217
+$(LIBNAME)(): $(addprefix $(TMPDIRPATH),$(OBJFILES))
218
+
219
+#=== create temp directory ===
220
+# not really required, because it will be also created during the dependency handling
221
+.PHONY: tmpdir
222
+tmpdir:
223
+	@test -d $(TMPDIRPATH) || mkdir $(TMPDIRPATH)
224
+
225
+#=== create assembler files for each C/C++ file ===
226
+.PHONY: assemblersource
227
+assemblersource: $(addprefix $(TMPDIRPATH),$(ASSFILES)) $(addprefix $(TMPDIRPATH),$(DISFILES))
228
+
229
+
230
+#=== show the section sizes of the ELF file ===
231
+.PHONY: showsize
232
+showsize: $(ELFNAME)
233
+	$(SIZE) $<
234
+
235
+#=== clean up target ===
236
+# this is simple: the TMPDIRPATH is removed
237
+.PHONY: clean
231 238
 clean:
232
-	$(REMOVE) applet/$(TARGET).hex applet/$(TARGET).eep applet/$(TARGET).cof applet/$(TARGET).elf \
233
-	applet/$(TARGET).map applet/$(TARGET).sym applet/$(TARGET).lss applet/core.a \
234
-	$(OBJ) $(LST) $(SRC:.c=.s) $(SRC:.c=.d) $(CXXSRC:.cpp=.s) $(CXXSRC:.cpp=.d)
235
-
236
-depend:
237
-	if grep '^# DO NOT DELETE' $(MAKEFILE) >/dev/null; \
238
-	then \
239
-		sed -e '/^# DO NOT DELETE/,$$d' $(MAKEFILE) > \
240
-			$(MAKEFILE).$$$$ && \
241
-		$(MV) $(MAKEFILE).$$$$ $(MAKEFILE); \
242
-	fi
243
-	echo '# DO NOT DELETE THIS LINE -- make depend depends on it.' \
244
-		>> $(MAKEFILE); \
245
-	$(CC) -M -mmcu=$(MCU) $(CDEFS) $(CINCS) $(SRC) $(ASRC) >> $(MAKEFILE)
246
-
247
-.PHONY:	all build elf hex eep lss sym program coff extcoff clean depend applet_files sizebefore sizeafter
239
+	$(RM) $(TMPDIRPATH)
240
+
241
+# Program the device.  
242
+# step 1: reset the arduino board with the stty command
243
+# step 2: user avrdude to upload the software
244
+.PHONY: upload
245
+upload: $(HEXNAME)
246
+	stty -F $(AVRDUDE_PORT) hupcl
247
+	$(AVRDUDE) $(AVRDUDE_FLAGS)
248
+
249
+
250
+# === dependency handling ===
251
+# From the gnu make manual (section 4.14, Generating Prerequisites Automatically)
252
+# Additionally (because this will be the first executed rule) TMPDIRPATH is created here.
253
+# Instead of "sed" the "echo" command is used
254
+# cd $(TMPDIRPATH); mkdir -p $(DIRS) 2> /dev/null; cd ..
255
+DEPACTION=test -d $(TMPDIRPATH) || mkdir $(TMPDIRPATH);\
256
+mkdir -p $(addprefix $(TMPDIRPATH),$(DIRS));\
257
+set -e; echo -n $@ $(dir $@) > $@; $(CC) -MM $(COMMON_FLAGS) $< >> $@
258
+
259
+
260
+$(TMPDIRPATH)%.d: %.c
261
+	@$(DEPACTION)
262
+
263
+$(TMPDIRPATH)%.d: %.cc
264
+	@$(DEPACTION)
265
+
266
+
267
+$(TMPDIRPATH)%.d: %.cpp
268
+	@$(DEPACTION)
269
+
270
+# Include dependency files. If a .d file is missing, a warning is created and the .d file is created
271
+# This warning is not a problem (gnu make manual, section 3.3 Including Other Makefiles)
272
+-include $(addprefix $(TMPDIRPATH),$(DEPFILES))
273
+
274
+

+ 34
- 58
Marlin/Marlin.h View File

@@ -1,27 +1,20 @@
1
+#ifndef __MARLINH
2
+#define __MARLINH
3
+
1 4
 // Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
2 5
 // Licence: GPL
3 6
 #include <WProgram.h>
4 7
 #include "fastio.h"
5
-extern "C" void __cxa_pure_virtual();
6
-void __cxa_pure_virtual(){};
8
+
9
+
10
+#define ECHO(x) Serial << "echo: " << x;
11
+#define ECHOLN(x) Serial << "echo: "<<x<<endl;
12
+
7 13
 void get_command();
8 14
 void process_commands();
9 15
 
10 16
 void manage_inactivity(byte debug);
11 17
 
12
-void manage_heater();
13
-int temp2analogu(int celsius, const short table[][2], int numtemps);
14
-float analog2tempu(int raw, const short table[][2], int numtemps);
15
-#ifdef HEATER_USES_THERMISTOR
16
-    #define HEATERSOURCE 1
17
-#endif
18
-#ifdef BED_USES_THERMISTOR
19
-    #define BEDSOURCE 1
20
-#endif
21
-
22
-#define temp2analogh( c ) temp2analogu((c),temptable,NUMTEMPS)
23
-#define analog2temp( c ) analog2tempu((c),temptable,NUMTEMPS)
24
-
25 18
 #if X_ENABLE_PIN > -1
26 19
 #define  enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
27 20
 #define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
@@ -43,9 +36,12 @@ float analog2tempu(int raw, const short table[][2], int numtemps);
43 36
 #define enable_z() ;
44 37
 #define disable_z() ;
45 38
 #endif
39
+
46 40
 #if E_ENABLE_PIN > -1
47
-#define  enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
48
-#define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
41
+
42
+	#define  enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
43
+	#define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
44
+
49 45
 #else
50 46
 #define enable_e() ;
51 47
 #define disable_e() ;
@@ -61,47 +57,27 @@ void ClearToSend();
61 57
 
62 58
 void get_coordinates();
63 59
 void prepare_move();
64
-void linear_move(unsigned long steps_remaining[]);
65
-void do_step(int axis);
66 60
 void kill(byte debug);
67 61
 
68
-// This struct is used when buffering the setup for each linear movement "nominal" values are as specified in 
69
-// the source g-code and may never actually be reached if acceleration management is active.
70
-typedef struct {
71
-  // Fields used by the bresenham algorithm for tracing the line
72
-  long steps_x, steps_y, steps_z, steps_e;  // Step count along each axis
73
-  long step_event_count;                    // The number of step events required to complete this block
74
-  volatile long accelerate_until;                    // The index of the step event on which to stop acceleration
75
-  volatile long decelerate_after;                    // The index of the step event on which to start decelerating
76
-  volatile long acceleration_rate;                   // The acceleration rate used for acceleration calculation
77
-  unsigned char direction_bits;             // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
78
-
79
-  long advance_rate;
80
-  volatile long initial_advance;
81
-  volatile long final_advance;
82
-  float advance;
83
-
84
-  // Fields used by the motion planner to manage acceleration
85
-  float speed_x, speed_y, speed_z, speed_e;          // Nominal mm/minute for each axis
86
-  float nominal_speed;                               // The nominal speed for this block in mm/min  
87
-  float millimeters;                                 // The total travel of this block in mm
88
-  float entry_speed;
89
-  float acceleration;                                // acceleration mm/sec^2
90
-
91
-  // Settings for the trapezoid generator
92
-  long nominal_rate;                                 // The nominal step rate for this block in step_events/sec 
93
-  volatile long initial_rate;                        // The jerk-adjusted step rate at start of block  
94
-  volatile long final_rate;                          // The minimal rate at exit
95
-  long acceleration_st;                              // acceleration steps/sec^2
96
-  volatile char busy;
97
-} block_t;
98
-
99
-void check_axes_activity();
100
-void plan_init();
101
-void st_init();
102
-void tp_init();
103
-void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
104
-void plan_set_position(float x, float y, float z, float e);
105
-void st_wake_up();
106
-void st_synchronize();
62
+//void check_axes_activity();
63
+//void plan_init();
64
+//void st_init();
65
+//void tp_init();
66
+//void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
67
+//void plan_set_position(float x, float y, float z, float e);
68
+//void st_wake_up();
69
+//void st_synchronize();
70
+void enquecommand(const char *cmd);
71
+void wd_reset();
72
+
73
+#ifndef CRITICAL_SECTION_START
74
+#define CRITICAL_SECTION_START  unsigned char _sreg = SREG; cli();
75
+#define CRITICAL_SECTION_END    SREG = _sreg;
76
+#endif //CRITICAL_SECTION_START
107 77
 
78
+extern float homing_feedrate[];
79
+extern bool axis_relative_modes[];
80
+
81
+void manage_inactivity(byte debug);
82
+
83
+#endif

+ 417
- 1297
Marlin/Marlin.pde
File diff suppressed because it is too large
View File


+ 1
- 0
Marlin/fastio.h View File

@@ -27,6 +27,7 @@
27 27
 #define		_READ(IO)					((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN)))
28 28
 /// write to a pin
29 29
 #define		_WRITE(IO, v)			do { if (v) {DIO ##  IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ##  IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }; } while (0)
30
+//#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)
30 31
 /// toggle a pin
31 32
 #define		_TOGGLE(IO)				do {DIO ##  IO ## _RPORT = MASK(DIO ## IO ## _PIN); } while (0)
32 33
 

+ 10
- 0
Marlin/lcd.h View File

@@ -0,0 +1,10 @@
1
+#ifndef __LCDH
2
+#define __LCDH
3
+
4
+
5
+
6
+
7
+
8
+
9
+
10
+#endif

+ 1
- 0
Marlin/lcd.pde View File

@@ -0,0 +1 @@
1
+

+ 83
- 11
Marlin/pins.h View File

@@ -60,8 +60,8 @@
60 60
 
61 61
 #define HEATER_0_PIN        6
62 62
 #define TEMP_0_PIN          0    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
63
-
64
-
63
+#define HEATER_1_PIN        -1
64
+#define HEATER_2_PIN        -1
65 65
 #endif
66 66
 
67 67
 
@@ -133,7 +133,8 @@
133 133
 
134 134
 #define HEATER_0_PIN       14
135 135
 #define TEMP_0_PIN          4 //D27   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
136
-
136
+#define HEATER_1_PIN        -1
137
+#define HEATER_2_PIN        -1
137 138
 /*  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)  */
138 139
 
139 140
 
@@ -194,7 +195,8 @@
194 195
 
195 196
 #define HEATER_0_PIN    -1
196 197
 #define TEMP_0_PIN      -1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
197
-
198
+#define HEATER_1_PIN        -1
199
+#define HEATER_2_PIN        -1
198 200
 
199 201
 
200 202
 
@@ -255,8 +257,10 @@
255 257
 
256 258
 #define HEATER_0_PIN       10
257 259
 #define HEATER_1_PIN       8
260
+#define HEATER_2_PIN        -1
258 261
 #define TEMP_0_PIN         13   // ANALOG NUMBERING
259 262
 #define TEMP_1_PIN         14   // ANALOG NUMBERING
263
+#define TEMP_2_PIN         -1   // ANALOG NUMBERING
260 264
 
261 265
 
262 266
 #else // RAMPS_V_1_1 or RAMPS_V_1_2 as default
@@ -301,9 +305,10 @@
301 305
   #define HEATER_1_PIN      8    // RAMPS 1.1
302 306
   #define FAN_PIN           9    // RAMPS 1.1
303 307
 #endif
304
-
308
+#define HEATER_2_PIN        -1
305 309
 #define TEMP_0_PIN          2    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
306 310
 #define TEMP_1_PIN          1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
311
+#define TEMP_2_PIN          -1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
307 312
 #endif
308 313
 
309 314
 // SPI for Max6675 Thermocouple 
@@ -361,7 +366,8 @@
361 366
 
362 367
 #define HEATER_0_PIN        6
363 368
 #define TEMP_0_PIN          0    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
364
-
369
+#define HEATER_1_PIN        -1
370
+#define HEATER_2_PIN        -1
365 371
 
366 372
 #endif
367 373
 
@@ -404,12 +410,13 @@
404 410
     #define TEMP_0_PIN      5     //changed @ rkoeppl 20110410
405 411
     #define HEATER_0_PIN    14    //changed @ rkoeppl 20110410
406 412
     #define HEATER_1_PIN    -1    //changed @ rkoeppl 20110410
407
-    
413
+    #define HEATER_2_PIN        -1
408 414
     
409 415
     #define SDPOWER          -1
410 416
     #define SDSS          17
411 417
     #define LED_PIN         -1    //changed @ rkoeppl 20110410
412 418
     #define TEMP_1_PIN      -1    //changed @ rkoeppl 20110410
419
+    #define TEMP_2_PIN      -1
413 420
     #define FAN_PIN         -1    //changed @ rkoeppl 20110410
414 421
     #define PS_ON_PIN       -1    //changed @ rkoeppl 20110410
415 422
     //our pin for debugging.
@@ -421,6 +428,7 @@
421 428
     #define RX_ENABLE_PIN	13
422 429
 
423 430
 #endif
431
+
424 432
 /****************************************************************************************
425 433
 * Sanguinololu pin assignment
426 434
 *
@@ -482,13 +490,77 @@
482 490
 
483 491
 #define TEMP_0_PIN          7   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder)
484 492
 #define TEMP_1_PIN          6   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
485
-#define SDPOWER          -1
486
-#define SDSS          31
493
+#define TEMP_2_PIN         -1
494
+#define SDPOWER            -1
495
+#define SDSS               31
496
+#define HEATER_2_PIN       -1
487 497
 
488
-#ifndef KNOWN_BOARD
489
-#error Unknown MOTHERBOARD value in configuration.h
490 498
 #endif
491 499
 
500
+
501
+#if MOTHERBOARD == 7
502
+#define KNOWN_BOARD
503
+/*****************************************************************
504
+* Ultimaker pin assignment
505
+******************************************************************/
506
+
507
+#ifndef __AVR_ATmega1280__
508
+ #ifndef __AVR_ATmega2560__
509
+ #error Oops!  Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
510
+ #endif
511
+#endif
512
+
513
+#define X_STEP_PIN 25
514
+#define X_DIR_PIN 23
515
+#define X_MIN_PIN 22
516
+#define X_MAX_PIN 24
517
+#define X_ENABLE_PIN 27
518
+
519
+#define Y_STEP_PIN 31
520
+#define Y_DIR_PIN 33
521
+#define Y_MIN_PIN 26
522
+#define Y_MAX_PIN 28
523
+#define Y_ENABLE_PIN 29
524
+
525
+#define Z_STEP_PIN 37 
526
+#define Z_DIR_PIN 39
527
+#define Z_MIN_PIN 30
528
+#define Z_MAX_PIN 32
529
+#define Z_ENABLE_PIN 35
530
+
531
+#define HEATER_1_PIN 4 
532
+#define TEMP_1_PIN 11  
533
+
534
+#define EXTRUDER_0_STEP_PIN 43 
535
+#define EXTRUDER_0_DIR_PIN 45
536
+#define EXTRUDER_0_ENABLE_PIN 41
537
+#define HEATER_0_PIN  2
538
+#define TEMP_0_PIN 8   
539
+
540
+#define EXTRUDER_1_STEP_PIN 49 
541
+#define EXTRUDER_1_DIR_PIN 47
542
+#define EXTRUDER_1_ENABLE_PIN 51
543
+#define EXTRUDER_1_HEATER_PIN 3
544
+#define EXTRUDER_1_TEMPERATURE_PIN 10 
545
+#define HEATER_2_PIN 51
546
+#define TEMP_2_PIN 3
547
+
548
+
549
+
550
+#define E_STEP_PIN         EXTRUDER_0_STEP_PIN
551
+#define E_DIR_PIN          EXTRUDER_0_DIR_PIN
552
+#define E_ENABLE_PIN       EXTRUDER_0_ENABLE_PIN
553
+
554
+#define SDPOWER            -1
555
+#define SDSS               53
556
+#define LED_PIN            13
557
+#define FAN_PIN            7
558
+#define PS_ON_PIN          12
559
+#define KILL_PIN           -1
492 560
 #endif
493 561
 
562
+
563
+#ifndef KNOWN_BOARD
564
+#error Unknown MOTHERBOARD value in configuration.h
565
+#endif
494 566
 #endif

+ 584
- 0
Marlin/planner.cpp View File

@@ -0,0 +1,584 @@
1
+/*
2
+  planner.c - buffers movement commands and manages the acceleration profile plan
3
+  Part of Grbl
4
+
5
+  Copyright (c) 2009-2011 Simen Svale Skogsrud
6
+
7
+  Grbl is free software: you can redistribute it and/or modify
8
+  it under the terms of the GNU General Public License as published by
9
+  the Free Software Foundation, either version 3 of the License, or
10
+  (at your option) any later version.
11
+
12
+  Grbl is distributed in the hope that it will be useful,
13
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
14
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
15
+  GNU General Public License for more details.
16
+
17
+  You should have received a copy of the GNU General Public License
18
+  along with Grbl.  If not, see <http://www.gnu.org/licenses/>.
19
+*/
20
+
21
+/* The ring buffer implementation gleaned from the wiring_serial library by David A. Mellis. */
22
+
23
+/*  
24
+  Reasoning behind the mathematics in this module (in the key of 'Mathematica'):
25
+  
26
+  s == speed, a == acceleration, t == time, d == distance
27
+
28
+  Basic definitions:
29
+
30
+    Speed[s_, a_, t_] := s + (a*t) 
31
+    Travel[s_, a_, t_] := Integrate[Speed[s, a, t], t]
32
+
33
+  Distance to reach a specific speed with a constant acceleration:
34
+
35
+    Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t]
36
+      d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance()
37
+
38
+  Speed after a given distance of travel with constant acceleration:
39
+
40
+    Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t]
41
+      m -> Sqrt[2 a d + s^2]    
42
+
43
+    DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2]
44
+
45
+  When to start braking (di) to reach a specified destionation speed (s2) after accelerating
46
+  from initial speed s1 without ever stopping at a plateau:
47
+
48
+    Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di]
49
+      di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance()
50
+
51
+    IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a)
52
+*/
53
+                                                                                                            
54
+
55
+//#include <inttypes.h>
56
+//#include <math.h>       
57
+//#include <stdlib.h>
58
+
59
+#include "Marlin.h"
60
+#include "Configuration.h"
61
+#include "pins.h"
62
+#include "fastio.h"
63
+#include "planner.h"
64
+#include "stepper.h"
65
+#include "temperature.h"
66
+#include "ultralcd.h"
67
+
68
+unsigned long minsegmenttime;
69
+float max_feedrate[4]; // set the max speeds
70
+float axis_steps_per_unit[4];
71
+long max_acceleration_units_per_sq_second[4]; // Use M201 to override by software
72
+float minimumfeedrate;
73
+float acceleration;         // Normal acceleration mm/s^2  THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
74
+float retract_acceleration; //  mm/s^2   filament pull-pack and push-forward  while standing still in the other axis M204 TXXXX
75
+float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
76
+float max_z_jerk;
77
+float mintravelfeedrate;
78
+unsigned long axis_steps_per_sqr_second[NUM_AXIS];
79
+// Manage heater variables.
80
+
81
+static block_t block_buffer[BLOCK_BUFFER_SIZE];            // A ring buffer for motion instfructions
82
+static volatile unsigned char block_buffer_head;           // Index of the next block to be pushed
83
+static volatile unsigned char block_buffer_tail;           // Index of the block to process now
84
+
85
+// The current position of the tool in absolute steps
86
+ long position[4];   
87
+
88
+#define ONE_MINUTE_OF_MICROSECONDS 60000000.0
89
+
90
+// Calculates the distance (not time) it takes to accelerate from initial_rate to target_rate using the 
91
+// given acceleration:
92
+inline float estimate_acceleration_distance(float initial_rate, float target_rate, float acceleration) {
93
+  if (acceleration!=0) {
94
+  return((target_rate*target_rate-initial_rate*initial_rate)/
95
+         (2.0*acceleration));
96
+  }
97
+  else {
98
+    return 0.0;  // acceleration was 0, set acceleration distance to 0
99
+  }
100
+}
101
+
102
+// This function gives you the point at which you must start braking (at the rate of -acceleration) if 
103
+// you started at speed initial_rate and accelerated until this point and want to end at the final_rate after
104
+// a total travel of distance. This can be used to compute the intersection point between acceleration and
105
+// deceleration in the cases where the trapezoid has no plateau (i.e. never reaches maximum speed)
106
+
107
+inline float intersection_distance(float initial_rate, float final_rate, float acceleration, float distance) {
108
+ if (acceleration!=0) {
109
+  return((2.0*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/
110
+         (4.0*acceleration) );
111
+  }
112
+  else {
113
+    return 0.0;  // acceleration was 0, set intersection distance to 0
114
+  }
115
+}
116
+
117
+// Calculates trapezoid parameters so that the entry- and exit-speed is compensated by the provided factors.
118
+
119
+void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit_speed) {
120
+  if(block->busy == true) return; // If block is busy then bail out.
121
+  float entry_factor = entry_speed / block->nominal_speed;
122
+  float exit_factor = exit_speed / block->nominal_speed;
123
+  long initial_rate = ceil(block->nominal_rate*entry_factor);
124
+  long final_rate = ceil(block->nominal_rate*exit_factor);
125
+  
126
+#ifdef ADVANCE
127
+  long initial_advance = block->advance*entry_factor*entry_factor;
128
+  long final_advance = block->advance*exit_factor*exit_factor;
129
+#endif // ADVANCE
130
+
131
+  // Limit minimal step rate (Otherwise the timer will overflow.)
132
+  if(initial_rate <120) initial_rate=120;
133
+  if(final_rate < 120) final_rate=120;
134
+  
135
+  // Calculate the acceleration steps
136
+  long acceleration = block->acceleration_st;
137
+  long accelerate_steps = estimate_acceleration_distance(initial_rate, block->nominal_rate, acceleration);
138
+  long decelerate_steps = estimate_acceleration_distance(final_rate, block->nominal_rate, acceleration);
139
+  // Calculate the size of Plateau of Nominal Rate. 
140
+  long plateau_steps = block->step_event_count-accelerate_steps-decelerate_steps;
141
+
142
+  // Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will
143
+  // have to use intersection_distance() to calculate when to abort acceleration and start braking 
144
+  // in order to reach the final_rate exactly at the end of this block.
145
+  if (plateau_steps < 0) {  
146
+    accelerate_steps = intersection_distance(initial_rate, final_rate, acceleration, block->step_event_count);
147
+    plateau_steps = 0;
148
+  }  
149
+
150
+  long decelerate_after = accelerate_steps+plateau_steps;
151
+
152
+  CRITICAL_SECTION_START;  // Fill variables used by the stepper in a critical section
153
+  if(block->busy == false) { // Don't update variables if block is busy.
154
+    block->accelerate_until = accelerate_steps;
155
+    block->decelerate_after = decelerate_after;
156
+    block->initial_rate = initial_rate;
157
+    block->final_rate = final_rate;
158
+#ifdef ADVANCE
159
+    block->initial_advance = initial_advance;
160
+    block->final_advance = final_advance;
161
+#endif //ADVANCE
162
+  }
163
+  CRITICAL_SECTION_END;
164
+}                    
165
+
166
+// Calculates the maximum allowable speed at this point when you must be able to reach target_velocity using the 
167
+// acceleration within the allotted distance.
168
+inline float max_allowable_speed(float acceleration, float target_velocity, float distance) {
169
+  return(
170
+  sqrt(target_velocity*target_velocity-2*acceleration*60*60*distance)
171
+    );
172
+}
173
+
174
+// "Junction jerk" in this context is the immediate change in speed at the junction of two blocks.
175
+// This method will calculate the junction jerk as the euclidean distance between the nominal 
176
+// velocities of the respective blocks.
177
+inline float junction_jerk(block_t *before, block_t *after) {
178
+  return(sqrt(
179
+    pow((before->speed_x-after->speed_x), 2)+
180
+    pow((before->speed_y-after->speed_y), 2)));
181
+}
182
+
183
+// Return the safe speed which is max_jerk/2, e.g. the 
184
+// speed under which you cannot exceed max_jerk no matter what you do.
185
+float safe_speed(block_t *block) {
186
+  float safe_speed;
187
+  safe_speed = max_xy_jerk/2;  
188
+  if(abs(block->speed_z) > max_z_jerk/2) safe_speed = max_z_jerk/2;
189
+  if (safe_speed > block->nominal_speed) safe_speed = block->nominal_speed;
190
+  return safe_speed;  
191
+}
192
+
193
+// The kernel called by planner_recalculate() when scanning the plan from last to first entry.
194
+void planner_reverse_pass_kernel(block_t *previous, block_t *current, block_t *next) {
195
+  if(!current) { 
196
+    return; 
197
+  }
198
+
199
+  float entry_speed = current->nominal_speed;
200
+  float exit_factor;
201
+  float exit_speed;
202
+  if (next) {
203
+    exit_speed = next->entry_speed;
204
+  } 
205
+  else {
206
+    exit_speed = safe_speed(current);
207
+  }
208
+
209
+  // Calculate the entry_factor for the current block. 
210
+  if (previous) {
211
+    // Reduce speed so that junction_jerk is within the maximum allowed
212
+    float jerk = junction_jerk(previous, current);
213
+    if((previous->steps_x == 0) && (previous->steps_y == 0)) {
214
+      entry_speed = safe_speed(current);
215
+    }
216
+    else if (jerk > max_xy_jerk) {
217
+      entry_speed = (max_xy_jerk/jerk) * entry_speed;
218
+    } 
219
+    if(abs(previous->speed_z - current->speed_z) > max_z_jerk) {
220
+      entry_speed = (max_z_jerk/abs(previous->speed_z - current->speed_z)) * entry_speed;
221
+    } 
222
+    // If the required deceleration across the block is too rapid, reduce the entry_factor accordingly.
223
+    if (entry_speed > exit_speed) {
224
+      float max_entry_speed = max_allowable_speed(-current->acceleration,exit_speed, current->millimeters);
225
+      if (max_entry_speed < entry_speed) {
226
+        entry_speed = max_entry_speed;
227
+      }
228
+    }    
229
+  } 
230
+  else {
231
+    entry_speed = safe_speed(current);
232
+  }
233
+  // Store result
234
+  current->entry_speed = entry_speed;
235
+}
236
+
237
+// planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This 
238
+// implements the reverse pass.
239
+void planner_reverse_pass() {
240
+  char block_index = block_buffer_head;
241
+  if(((block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1)) > 3) {
242
+    block_index = (block_buffer_head - 3) & (BLOCK_BUFFER_SIZE - 1);
243
+    block_t *block[5] = {
244
+      NULL, NULL, NULL, NULL, NULL  };
245
+    while(block_index != block_buffer_tail) { 
246
+      block_index = (block_index-1) & (BLOCK_BUFFER_SIZE -1); 
247
+      block[2]= block[1];
248
+      block[1]= block[0];
249
+      block[0] = &block_buffer[block_index];
250
+      planner_reverse_pass_kernel(block[0], block[1], block[2]);
251
+    }
252
+    planner_reverse_pass_kernel(NULL, block[0], block[1]);
253
+  }
254
+}
255
+
256
+// The kernel called by planner_recalculate() when scanning the plan from first to last entry.
257
+void planner_forward_pass_kernel(block_t *previous, block_t *current, block_t *next) {
258
+  if(!current) { 
259
+    return; 
260
+  }
261
+  if(previous) {
262
+    // If the previous block is an acceleration block, but it is not long enough to 
263
+    // complete the full speed change within the block, we need to adjust out entry
264
+    // speed accordingly. Remember current->entry_factor equals the exit factor of 
265
+    // the previous block.
266
+    if(previous->entry_speed < current->entry_speed) {
267
+      float max_entry_speed = max_allowable_speed(-previous->acceleration, previous->entry_speed, previous->millimeters);
268
+      if (max_entry_speed < current->entry_speed) {
269
+        current->entry_speed = max_entry_speed;
270
+      }
271
+    }
272
+  }
273
+}
274
+
275
+// planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This 
276
+// implements the forward pass.
277
+void planner_forward_pass() {
278
+  char block_index = block_buffer_tail;
279
+  block_t *block[3] = {
280
+    NULL, NULL, NULL  };
281
+
282
+  while(block_index != block_buffer_head) {
283
+    block[0] = block[1];
284
+    block[1] = block[2];
285
+    block[2] = &block_buffer[block_index];
286
+    planner_forward_pass_kernel(block[0],block[1],block[2]);
287
+    block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1);
288
+  }
289
+  planner_forward_pass_kernel(block[1], block[2], NULL);
290
+}
291
+
292
+// Recalculates the trapezoid speed profiles for all blocks in the plan according to the 
293
+// entry_factor for each junction. Must be called by planner_recalculate() after 
294
+// updating the blocks.
295
+void planner_recalculate_trapezoids() {
296
+  char block_index = block_buffer_tail;
297
+  block_t *current;
298
+  block_t *next = NULL;
299
+  while(block_index != block_buffer_head) {
300
+    current = next;
301
+    next = &block_buffer[block_index];
302
+    if (current) {
303
+      calculate_trapezoid_for_block(current, current->entry_speed, next->entry_speed);      
304
+    }
305
+    block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1);
306
+  }
307
+  calculate_trapezoid_for_block(next, next->entry_speed, safe_speed(next));
308
+}
309
+
310
+// Recalculates the motion plan according to the following algorithm:
311
+//
312
+//   1. Go over every block in reverse order and calculate a junction speed reduction (i.e. block_t.entry_factor) 
313
+//      so that:
314
+//     a. The junction jerk is within the set limit
315
+//     b. No speed reduction within one block requires faster deceleration than the one, true constant 
316
+//        acceleration.
317
+//   2. Go over every block in chronological order and dial down junction speed reduction values if 
318
+//     a. The speed increase within one block would require faster accelleration than the one, true 
319
+//        constant acceleration.
320
+//
321
+// When these stages are complete all blocks have an entry_factor that will allow all speed changes to 
322
+// be performed using only the one, true constant acceleration, and where no junction jerk is jerkier than 
323
+// the set limit. Finally it will:
324
+//
325
+//   3. Recalculate trapezoids for all blocks.
326
+
327
+void planner_recalculate() {   
328
+  planner_reverse_pass();
329
+  planner_forward_pass();
330
+  planner_recalculate_trapezoids();
331
+}
332
+
333
+void plan_init() {
334
+  block_buffer_head = 0;
335
+  block_buffer_tail = 0;
336
+  memset(position, 0, sizeof(position)); // clear position
337
+}
338
+
339
+
340
+void plan_discard_current_block() {
341
+  if (block_buffer_head != block_buffer_tail) {
342
+    block_buffer_tail = (block_buffer_tail + 1) & (BLOCK_BUFFER_SIZE - 1);  
343
+  }
344
+}
345
+
346
+block_t *plan_get_current_block() {
347
+  if (block_buffer_head == block_buffer_tail) { 
348
+    return(NULL); 
349
+  }
350
+  block_t *block = &block_buffer[block_buffer_tail];
351
+  block->busy = true;
352
+  return(block);
353
+}
354
+
355
+void check_axes_activity() {
356
+  unsigned char x_active = 0;
357
+  unsigned char y_active = 0;  
358
+  unsigned char z_active = 0;
359
+  unsigned char e_active = 0;
360
+  block_t *block;
361
+
362
+  if(block_buffer_tail != block_buffer_head) {
363
+    char block_index = block_buffer_tail;
364
+    while(block_index != block_buffer_head) {
365
+      block = &block_buffer[block_index];
366
+      if(block->steps_x != 0) x_active++;
367
+      if(block->steps_y != 0) y_active++;
368
+      if(block->steps_z != 0) z_active++;
369
+      if(block->steps_e != 0) e_active++;
370
+      block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1);
371
+    }
372
+  }
373
+  if((DISABLE_X) && (x_active == 0)) disable_x();
374
+  if((DISABLE_Y) && (y_active == 0)) disable_y();
375
+  if((DISABLE_Z) && (z_active == 0)) disable_z();
376
+  if((DISABLE_E) && (e_active == 0)) disable_e();
377
+}
378
+
379
+// Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in 
380
+// mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
381
+// calculation the caller must also provide the physical length of the line in millimeters.
382
+void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
383
+
384
+  // The target position of the tool in absolute steps
385
+  // Calculate target position in absolute steps
386
+  long target[4];
387
+  target[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
388
+  target[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
389
+  target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);     
390
+  target[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);     
391
+
392
+  // Calculate the buffer head after we push this byte
393
+  int next_buffer_head = (block_buffer_head + 1) & (BLOCK_BUFFER_SIZE - 1);
394
+
395
+  // If the buffer is full: good! That means we are well ahead of the robot. 
396
+  // Rest here until there is room in the buffer.
397
+  while(block_buffer_tail == next_buffer_head) { 
398
+    manage_heater(); 
399
+    manage_inactivity(1); 
400
+    LCD_STATUS;
401
+  }
402
+
403
+  // Prepare to set up new block
404
+  block_t *block = &block_buffer[block_buffer_head];
405
+  
406
+  // Mark block as not busy (Not executed by the stepper interrupt)
407
+  block->busy = false;
408
+
409
+  // Number of steps for each axis
410
+  block->steps_x = labs(target[X_AXIS]-position[X_AXIS]);
411
+  block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
412
+  block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
413
+  block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
414
+  block->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, block->steps_e)));
415
+
416
+  // Bail if this is a zero-length block
417
+  if (block->step_event_count <=dropsegments) { 
418
+    return; 
419
+  };
420
+
421
+  //enable active axes
422
+  if(block->steps_x != 0) enable_x();
423
+  if(block->steps_y != 0) enable_y();
424
+  if(block->steps_z != 0) enable_z();
425
+  if(block->steps_e != 0) enable_e();
426
+
427
+  float delta_x_mm = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
428
+  float delta_y_mm = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
429
+  float delta_z_mm = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
430
+  float delta_e_mm = (target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS];
431
+  block->millimeters = sqrt(square(delta_x_mm) + square(delta_y_mm) + square(delta_z_mm) + square(delta_e_mm));
432
+
433
+  unsigned long microseconds;
434
+
435
+  if (block->steps_e == 0) {
436
+	if(feed_rate<mintravelfeedrate) feed_rate=mintravelfeedrate;
437
+  }
438
+  else {
439
+    	if(feed_rate<minimumfeedrate) feed_rate=minimumfeedrate;
440
+  } 
441
+
442
+  microseconds = lround((block->millimeters/feed_rate)*1000000);
443
+
444
+  // slow down when de buffer starts to empty, rather than wait at the corner for a buffer refill
445
+  // reduces/removes corner blobs as the machine won't come to a full stop.
446
+  int blockcount=(block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
447
+  
448
+  if ((blockcount>0) && (blockcount < (BLOCK_BUFFER_SIZE - 4))) {
449
+    if (microseconds<minsegmenttime)  { // buffer is draining, add extra time.  The amount of time added increases if the buffer is still emptied more.
450
+        microseconds=microseconds+lround(2*(minsegmenttime-microseconds)/blockcount);
451
+    }
452
+  }
453
+  else {
454
+    if (microseconds<minsegmenttime) microseconds=minsegmenttime;
455
+  }
456
+  //  END OF SLOW DOWN SECTION  
457
+  
458
+  
459
+  // Calculate speed in mm/minute for each axis
460
+  float multiplier = 60.0*1000000.0/microseconds;
461
+  block->speed_z = delta_z_mm * multiplier; 
462
+  block->speed_x = delta_x_mm * multiplier;
463
+  block->speed_y = delta_y_mm * multiplier;
464
+  block->speed_e = delta_e_mm * multiplier; 
465
+
466
+
467
+  // Limit speed per axis
468
+  float speed_factor = 1; //factor <=1 do decrease speed
469
+  if(abs(block->speed_x) > max_feedrate[X_AXIS]) {
470
+    //// [ErikDeBruijn] IS THIS THE BUG WE'RE LOOING FOR????
471
+    //// [bernhard] No its not, according to Zalm.
472
+		//// the if would always be true, since tmp_speedfactor <=0 due the inial if, so its safe to set. the next lines actually compare.
473
+    speed_factor = max_feedrate[X_AXIS] / abs(block->speed_x);
474
+    //if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
475
+  }
476
+  if(abs(block->speed_y) > max_feedrate[Y_AXIS]){
477
+    float tmp_speed_factor = max_feedrate[Y_AXIS] / abs(block->speed_y);
478
+    if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
479
+  }
480
+  if(abs(block->speed_z) > max_feedrate[Z_AXIS]){
481
+    float tmp_speed_factor = max_feedrate[Z_AXIS] / abs(block->speed_z);
482
+    if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
483
+  }
484
+  if(abs(block->speed_e) > max_feedrate[E_AXIS]){
485
+    float tmp_speed_factor = max_feedrate[E_AXIS] / abs(block->speed_e);
486
+    if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
487
+  }
488
+  multiplier = multiplier * speed_factor;
489
+  block->speed_z = delta_z_mm * multiplier; 
490
+  block->speed_x = delta_x_mm * multiplier;
491
+  block->speed_y = delta_y_mm * multiplier;
492
+  block->speed_e = delta_e_mm * multiplier; 
493
+  block->nominal_speed = block->millimeters * multiplier;
494
+  block->nominal_rate = ceil(block->step_event_count * multiplier / 60);  
495
+
496
+  if(block->nominal_rate < 120) block->nominal_rate = 120;
497
+  block->entry_speed = safe_speed(block);
498
+
499
+  // Compute the acceleration rate for the trapezoid generator. 
500
+  float travel_per_step = block->millimeters/block->step_event_count;
501
+  if(block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0) {
502
+    block->acceleration_st = ceil( (retract_acceleration)/travel_per_step); // convert to: acceleration steps/sec^2
503
+  }
504
+  else {
505
+    block->acceleration_st = ceil( (acceleration)/travel_per_step);      // convert to: acceleration steps/sec^2
506
+    float tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
507
+    // Limit acceleration per axis
508
+    if((tmp_acceleration * block->steps_x) > axis_steps_per_sqr_second[X_AXIS]) {
509
+      block->acceleration_st = axis_steps_per_sqr_second[X_AXIS];
510
+      tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
511
+    }
512
+    if((tmp_acceleration * block->steps_y) > axis_steps_per_sqr_second[Y_AXIS]) {
513
+      block->acceleration_st = axis_steps_per_sqr_second[Y_AXIS];
514
+      tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
515
+    }
516
+    if((tmp_acceleration * block->steps_e) > axis_steps_per_sqr_second[E_AXIS]) {
517
+      block->acceleration_st = axis_steps_per_sqr_second[E_AXIS];
518
+      tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
519
+    }
520
+    if((tmp_acceleration * block->steps_z) > axis_steps_per_sqr_second[Z_AXIS]) {
521
+      block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
522
+      tmp_acceleration = (float)block->acceleration_st / (float)block->step_event_count;
523
+    }
524
+  }
525
+  block->acceleration = block->acceleration_st * travel_per_step;
526
+  block->acceleration_rate = (long)((float)block->acceleration_st * 8.388608);
527
+
528
+#ifdef ADVANCE
529
+  // Calculate advance rate
530
+  if((block->steps_e == 0) || (block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0)) {
531
+    block->advance_rate = 0;
532
+    block->advance = 0;
533
+  }
534
+  else {
535
+    long acc_dist = estimate_acceleration_distance(0, block->nominal_rate, block->acceleration_st);
536
+    float advance = (STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K) * 
537
+      (block->speed_e * block->speed_e * EXTRUTION_AREA * EXTRUTION_AREA / 3600.0)*65536;
538
+    block->advance = advance;
539
+    if(acc_dist == 0) {
540
+      block->advance_rate = 0;
541
+    } 
542
+    else {
543
+      block->advance_rate = advance / (float)acc_dist;
544
+    }
545
+  }
546
+#endif // ADVANCE
547
+
548
+  // compute a preliminary conservative acceleration trapezoid
549
+  float safespeed = safe_speed(block);
550
+  calculate_trapezoid_for_block(block, safespeed, safespeed); 
551
+
552
+  // Compute direction bits for this block
553
+  block->direction_bits = 0;
554
+  if (target[X_AXIS] < position[X_AXIS]) { 
555
+    block->direction_bits |= (1<<X_AXIS); 
556
+  }
557
+  if (target[Y_AXIS] < position[Y_AXIS]) { 
558
+    block->direction_bits |= (1<<Y_AXIS); 
559
+  }
560
+  if (target[Z_AXIS] < position[Z_AXIS]) { 
561
+    block->direction_bits |= (1<<Z_AXIS); 
562
+  }
563
+  if (target[E_AXIS] < position[E_AXIS]) { 
564
+    block->direction_bits |= (1<<E_AXIS); 
565
+  }
566
+
567
+  // Move buffer head
568
+  block_buffer_head = next_buffer_head;     
569
+
570
+  // Update position 
571
+  memcpy(position, target, sizeof(target)); // position[] = target[]
572
+
573
+  planner_recalculate();
574
+  st_wake_up();
575
+}
576
+
577
+void plan_set_position(float x, float y, float z, float e)
578
+{
579
+  position[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
580
+  position[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);
581
+  position[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]);     
582
+  position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]);     
583
+}
584
+

+ 90
- 0
Marlin/planner.h View File

@@ -0,0 +1,90 @@
1
+/*
2
+  planner.h - buffers movement commands and manages the acceleration profile plan
3
+  Part of Grbl
4
+
5
+  Copyright (c) 2009-2011 Simen Svale Skogsrud
6
+
7
+  Grbl is free software: you can redistribute it and/or modify
8
+  it under the terms of the GNU General Public License as published by
9
+  the Free Software Foundation, either version 3 of the License, or
10
+  (at your option) any later version.
11
+
12
+  Grbl is distributed in the hope that it will be useful,
13
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
14
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
15
+  GNU General Public License for more details.
16
+
17
+  You should have received a copy of the GNU General Public License
18
+  along with Grbl.  If not, see <http://www.gnu.org/licenses/>.
19
+*/
20
+
21
+// This module is to be considered a sub-module of stepper.c. Please don't include 
22
+// this file from any other module.
23
+
24
+#ifndef planner_h
25
+#define planner_h
26
+
27
+// This struct is used when buffering the setup for each linear movement "nominal" values are as specified in 
28
+// the source g-code and may never actually be reached if acceleration management is active.
29
+typedef struct {
30
+  // Fields used by the bresenham algorithm for tracing the line
31
+  long steps_x, steps_y, steps_z, steps_e;  // Step count along each axis
32
+  long step_event_count;                    // The number of step events required to complete this block
33
+  volatile long accelerate_until;                    // The index of the step event on which to stop acceleration
34
+  volatile long decelerate_after;                    // The index of the step event on which to start decelerating
35
+  volatile long acceleration_rate;                   // The acceleration rate used for acceleration calculation
36
+  unsigned char direction_bits;             // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
37
+#ifdef ADVANCE
38
+  long advance_rate;
39
+  volatile long initial_advance;
40
+  volatile long final_advance;
41
+  float advance;
42
+#endif
43
+
44
+  // Fields used by the motion planner to manage acceleration
45
+  float speed_x, speed_y, speed_z, speed_e;          // Nominal mm/minute for each axis
46
+  float nominal_speed;                               // The nominal speed for this block in mm/min  
47
+  float millimeters;                                 // The total travel of this block in mm
48
+  float entry_speed;
49
+  float acceleration;                                // acceleration mm/sec^2
50
+
51
+  // Settings for the trapezoid generator
52
+  long nominal_rate;                                 // The nominal step rate for this block in step_events/sec 
53
+  volatile long initial_rate;                        // The jerk-adjusted step rate at start of block  
54
+  volatile long final_rate;                          // The minimal rate at exit
55
+  long acceleration_st;                              // acceleration steps/sec^2
56
+  volatile char busy;
57
+} block_t;
58
+      
59
+// Initialize the motion plan subsystem      
60
+void plan_init();
61
+
62
+// Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in 
63
+// millimaters. Feed rate specifies the speed of the motion.
64
+void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
65
+
66
+// Set position. Used for G92 instructions.
67
+void plan_set_position(float x, float y, float z, float e);
68
+
69
+// Called when the current block is no longer needed. Discards the block and makes the memory
70
+// availible for new blocks.
71
+void plan_discard_current_block();
72
+
73
+// Gets the current block. Returns NULL if buffer empty
74
+block_t *plan_get_current_block();
75
+
76
+void check_axes_activity();
77
+
78
+extern unsigned long minsegmenttime;
79
+extern float max_feedrate[4]; // set the max speeds
80
+extern float axis_steps_per_unit[4];
81
+extern long max_acceleration_units_per_sq_second[4]; // Use M201 to override by software
82
+extern float minimumfeedrate;
83
+extern float acceleration;         // Normal acceleration mm/s^2  THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
84
+extern float retract_acceleration; //  mm/s^2   filament pull-pack and push-forward  while standing still in the other axis M204 TXXXX
85
+extern float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
86
+extern float max_z_jerk;
87
+extern float mintravelfeedrate;
88
+extern unsigned long axis_steps_per_sqr_second[NUM_AXIS];
89
+
90
+#endif

+ 4
- 4
Marlin/speed_lookuptable.h View File

@@ -3,7 +3,7 @@
3 3
 
4 4
 #include <avr/pgmspace.h>
5 5
 
6
-uint16_t speed_lookuptable_fast[256][2] PROGMEM = {
6
+uint16_t speed_lookuptable_fast[256][2] PROGMEM = {\
7 7
 { 62500, 55556}, { 6944, 3268}, { 3676, 1176}, { 2500, 607}, { 1893, 369}, { 1524, 249}, { 1275, 179}, { 1096, 135}, 
8 8
 { 961, 105}, { 856, 85}, { 771, 69}, { 702, 58}, { 644, 49}, { 595, 42}, { 553, 37}, { 516, 32}, 
9 9
 { 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 = {
35 35
 { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 1}, { 33, 0}, { 33, 0}, 
36 36
 { 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 1}, { 32, 0}, { 32, 0}, { 32, 0}, 
37 37
 { 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0}, 
38
-{ 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}, 
38
+{ 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
39 39
 };
40
-uint16_t speed_lookuptable_slow[256][2] PROGMEM = {
40
+uint16_t speed_lookuptable_slow[256][2] PROGMEM = {\
41 41
 { 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894}, 
42 42
 { 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657}, 
43 43
 { 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 = {
69 69
 { 1096, 5}, { 1091, 5}, { 1086, 4}, { 1082, 5}, { 1077, 5}, { 1072, 4}, { 1068, 5}, { 1063, 4}, 
70 70
 { 1059, 5}, { 1054, 4}, { 1050, 4}, { 1046, 5}, { 1041, 4}, { 1037, 4}, { 1033, 5}, { 1028, 4}, 
71 71
 { 1024, 4}, { 1020, 4}, { 1016, 4}, { 1012, 4}, { 1008, 4}, { 1004, 4}, { 1000, 4}, { 996, 4}, 
72
-{ 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}, 
72
+{ 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}
73 73
 };
74 74
 
75 75
 #endif

+ 592
- 0
Marlin/stepper.cpp View File

@@ -0,0 +1,592 @@
1
+/*
2
+  stepper.c - stepper motor driver: executes motion plans using stepper motors
3
+  Part of Grbl
4
+
5
+  Copyright (c) 2009-2011 Simen Svale Skogsrud
6
+
7
+  Grbl is free software: you can redistribute it and/or modify
8
+  it under the terms of the GNU General Public License as published by
9
+  the Free Software Foundation, either version 3 of the License, or
10
+  (at your option) any later version.
11
+
12
+  Grbl is distributed in the hope that it will be useful,
13
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
14
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
15
+  GNU General Public License for more details.
16
+
17
+  You should have received a copy of the GNU General Public License
18
+  along with Grbl.  If not, see <http://www.gnu.org/licenses/>.
19
+*/
20
+
21
+/* The timer calculations of this module informed by the 'RepRap cartesian firmware' by Zack Smith
22
+   and Philipp Tiefenbacher. */
23
+
24
+#include "stepper.h"
25
+#include "Configuration.h"
26
+#include "Marlin.h"
27
+#include "planner.h"
28
+#include "pins.h"
29
+#include "fastio.h"
30
+#include "temperature.h"
31
+#include "ultralcd.h"
32
+
33
+#include "speed_lookuptable.h"
34
+
35
+// if DEBUG_STEPS is enabled, M114 can be used to compare two methods of determining the X,Y,Z position of the printer.
36
+// for debugging purposes only, should be disabled by default
37
+#ifdef DEBUG_STEPS
38
+volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
39
+volatile int count_direction[NUM_AXIS] = { 1, 1, 1, 1};
40
+#endif
41
+
42
+
43
+// intRes = intIn1 * intIn2 >> 16
44
+// uses:
45
+// r26 to store 0
46
+// r27 to store the byte 1 of the 24 bit result
47
+#define MultiU16X8toH16(intRes, charIn1, intIn2) \
48
+asm volatile ( \
49
+"clr r26 \n\t" \
50
+"mul %A1, %B2 \n\t" \
51
+"movw %A0, r0 \n\t" \
52
+"mul %A1, %A2 \n\t" \
53
+"add %A0, r1 \n\t" \
54
+"adc %B0, r26 \n\t" \
55
+"lsr r0 \n\t" \
56
+"adc %A0, r26 \n\t" \
57
+"adc %B0, r26 \n\t" \
58
+"clr r1 \n\t" \
59
+: \
60
+"=&r" (intRes) \
61
+: \
62
+"d" (charIn1), \
63
+"d" (intIn2) \
64
+: \
65
+"r26" \
66
+)
67
+
68
+// intRes = longIn1 * longIn2 >> 24
69
+// uses:
70
+// r26 to store 0
71
+// r27 to store the byte 1 of the 48bit result
72
+#define MultiU24X24toH16(intRes, longIn1, longIn2) \
73
+asm volatile ( \
74
+"clr r26 \n\t" \
75
+"mul %A1, %B2 \n\t" \
76
+"mov r27, r1 \n\t" \
77
+"mul %B1, %C2 \n\t" \
78
+"movw %A0, r0 \n\t" \
79
+"mul %C1, %C2 \n\t" \
80
+"add %B0, r0 \n\t" \
81
+"mul %C1, %B2 \n\t" \
82
+"add %A0, r0 \n\t" \
83
+"adc %B0, r1 \n\t" \
84
+"mul %A1, %C2 \n\t" \
85
+"add r27, r0 \n\t" \
86
+"adc %A0, r1 \n\t" \
87
+"adc %B0, r26 \n\t" \
88
+"mul %B1, %B2 \n\t" \
89
+"add r27, r0 \n\t" \
90
+"adc %A0, r1 \n\t" \
91
+"adc %B0, r26 \n\t" \
92
+"mul %C1, %A2 \n\t" \
93
+"add r27, r0 \n\t" \
94
+"adc %A0, r1 \n\t" \
95
+"adc %B0, r26 \n\t" \
96
+"mul %B1, %A2 \n\t" \
97
+"add r27, r1 \n\t" \
98
+"adc %A0, r26 \n\t" \
99
+"adc %B0, r26 \n\t" \
100
+"lsr r27 \n\t" \
101
+"adc %A0, r26 \n\t" \
102
+"adc %B0, r26 \n\t" \
103
+"clr r1 \n\t" \
104
+: \
105
+"=&r" (intRes) \
106
+: \
107
+"d" (longIn1), \
108
+"d" (longIn2) \
109
+: \
110
+"r26" , "r27" \
111
+)
112
+
113
+// Some useful constants
114
+
115
+#define ENABLE_STEPPER_DRIVER_INTERRUPT()  TIMSK1 |= (1<<OCIE1A)
116
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 &= ~(1<<OCIE1A)
117
+
118
+static block_t *current_block;  // A pointer to the block currently being traced
119
+
120
+// Variables used by The Stepper Driver Interrupt
121
+static unsigned char out_bits;        // The next stepping-bits to be output
122
+static long counter_x,       // Counter variables for the bresenham line tracer
123
+            counter_y, 
124
+            counter_z,       
125
+            counter_e;
126
+static unsigned long step_events_completed; // The number of step events executed in the current block
127
+#ifdef ADVANCE
128
+static long advance_rate, advance, final_advance = 0;
129
+static short old_advance = 0;
130
+static short e_steps;
131
+#endif
132
+static unsigned char busy = false; // TRUE when SIG_OUTPUT_COMPARE1A is being serviced. Used to avoid retriggering that handler.
133
+static long acceleration_time, deceleration_time;
134
+//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
135
+static unsigned short acc_step_rate; // needed for deccelaration start point
136
+static char step_loops;
137
+
138
+
139
+//         __________________________
140
+//        /|                        |\     _________________         ^
141
+//       / |                        | \   /|               |\        |
142
+//      /  |                        |  \ / |               | \       s
143
+//     /   |                        |   |  |               |  \      p
144
+//    /    |                        |   |  |               |   \     e
145
+//   +-----+------------------------+---+--+---------------+----+    e
146
+//   |               BLOCK 1            |      BLOCK 2          |    d
147
+//
148
+//                           time ----->
149
+// 
150
+//  The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates 
151
+//  first block->accelerate_until step_events_completed, then keeps going at constant speed until 
152
+//  step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
153
+//  The slope of acceleration is calculated with the leib ramp alghorithm.
154
+
155
+void st_wake_up() {
156
+  //  TCNT1 = 0;
157
+  ENABLE_STEPPER_DRIVER_INTERRUPT();  
158
+}
159
+
160
+inline unsigned short calc_timer(unsigned short step_rate) {
161
+  unsigned short timer;
162
+  if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY;
163
+  
164
+  if(step_rate > 20000) { // If steprate > 20kHz >> step 4 times
165
+    step_rate = step_rate >> 2;
166
+    step_loops = 4;
167
+  }
168
+  else if(step_rate > 10000) { // If steprate > 10kHz >> step 2 times
169
+    step_rate = step_rate >> 1;
170
+    step_loops = 2;
171
+  }
172
+  else {
173
+    step_loops = 1;
174
+  } 
175
+  
176
+  if(step_rate < 32) step_rate = 32;
177
+  step_rate -= 32; // Correct for minimal speed
178
+  if(step_rate >= (8*256)){ // higher step rate 
179
+    unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
180
+    unsigned char tmp_step_rate = (step_rate & 0x00ff);
181
+    unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
182
+    MultiU16X8toH16(timer, tmp_step_rate, gain);
183
+    timer = (unsigned short)pgm_read_word_near(table_address) - timer;
184
+  }
185
+  else { // lower step rates
186
+    unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0];
187
+    table_address += ((step_rate)>>1) & 0xfffc;
188
+    timer = (unsigned short)pgm_read_word_near(table_address);
189
+    timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
190
+  }
191
+  if(timer < 100) timer = 100;
192
+  return timer;
193
+}
194
+
195
+// Initializes the trapezoid generator from the current block. Called whenever a new 
196
+// block begins.
197
+inline void trapezoid_generator_reset() {
198
+#ifdef ADVANCE
199
+  advance = current_block->initial_advance;
200
+  final_advance = current_block->final_advance;
201
+#endif
202
+  deceleration_time = 0;
203
+  // advance_rate = current_block->advance_rate;
204
+  // step_rate to timer interval
205
+  acc_step_rate = current_block->initial_rate;
206
+  acceleration_time = calc_timer(acc_step_rate);
207
+  OCR1A = acceleration_time;
208
+}
209
+
210
+// "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.  
211
+// It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. 
212
+ISR(TIMER1_COMPA_vect)
213
+{        
214
+  if(busy){ Serial.print(*(unsigned short *)OCR1A); Serial.println(" BUSY");
215
+    return; 
216
+  } // The busy-flag is used to avoid reentering this interrupt
217
+
218
+  busy = true;
219
+  sei(); // Re enable interrupts (normally disabled while inside an interrupt handler)
220
+
221
+  // If there is no current block, attempt to pop one from the buffer
222
+  if (current_block == NULL) {
223
+    // Anything in the buffer?
224
+    current_block = plan_get_current_block();
225
+    if (current_block != NULL) {
226
+      trapezoid_generator_reset();
227
+      counter_x = -(current_block->step_event_count >> 1);
228
+      counter_y = counter_x;
229
+      counter_z = counter_x;
230
+      counter_e = counter_x;
231
+      step_events_completed = 0;
232
+      #ifdef ADVANCE
233
+      e_steps = 0;
234
+      #endif
235
+    } 
236
+    else {
237
+//      DISABLE_STEPPER_DRIVER_INTERRUPT();
238
+    }    
239
+  } 
240
+
241
+  if (current_block != NULL) {
242
+    // Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
243
+    out_bits = current_block->direction_bits;
244
+
245
+#ifdef ADVANCE
246
+    // Calculate E early.
247
+    counter_e += current_block->steps_e;
248
+    if (counter_e > 0) {
249
+      counter_e -= current_block->step_event_count;
250
+      if ((out_bits & (1<<E_AXIS)) != 0) { // - direction
251
+        CRITICAL_SECTION_START;
252
+        e_steps--;
253
+        CRITICAL_SECTION_END;
254
+      }
255
+      else {
256
+        CRITICAL_SECTION_START;
257
+        e_steps++;
258
+        CRITICAL_SECTION_END;
259
+      }
260
+    }    
261
+    // Do E steps + advance steps
262
+    CRITICAL_SECTION_START;
263
+    e_steps += ((advance >> 16) - old_advance);
264
+    CRITICAL_SECTION_END;
265
+    old_advance = advance >> 16;  
266
+#endif //ADVANCE
267
+
268
+    // Set direction en check limit switches
269
+if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
270
+      WRITE(X_DIR_PIN, INVERT_X_DIR);
271
+      #ifdef DEBUG_STEPS
272
+      count_direction[X_AXIS]=-1;
273
+      #endif
274
+#if X_MIN_PIN > -1
275
+      if(READ(X_MIN_PIN) != ENDSTOPS_INVERTING) {
276
+        step_events_completed = current_block->step_event_count;
277
+      }
278
+#endif
279
+    }
280
+    else { // +direction 
281
+        WRITE(X_DIR_PIN,!INVERT_X_DIR);
282
+        #ifdef DEBUG_STEPS
283
+        count_direction[X_AXIS]=1;
284
+        #endif
285
+#if X_MAX_PIN > -1
286
+        if((READ(X_MAX_PIN) != ENDSTOPS_INVERTING)  && (current_block->steps_x >0)){
287
+          step_events_completed = current_block->step_event_count;
288
+        }
289
+#endif
290
+    }
291
+
292
+    if ((out_bits & (1<<Y_AXIS)) != 0) {   // -direction
293
+      WRITE(Y_DIR_PIN,INVERT_Y_DIR);
294
+      #ifdef DEBUG_STEPS
295
+      count_direction[Y_AXIS]=-1;
296
+      #endif
297
+#if Y_MIN_PIN > -1
298
+      if(READ(Y_MIN_PIN) != ENDSTOPS_INVERTING) {
299
+        step_events_completed = current_block->step_event_count;
300
+      }
301
+#endif
302
+    }
303
+    else { // +direction
304
+    WRITE(Y_DIR_PIN,!INVERT_Y_DIR);
305
+      #ifdef DEBUG_STEPS
306
+      count_direction[Y_AXIS]=1;
307
+      #endif
308
+#if Y_MAX_PIN > -1
309
+    if((READ(Y_MAX_PIN) != ENDSTOPS_INVERTING) && (current_block->steps_y >0)){
310
+        step_events_completed = current_block->step_event_count;
311
+      }
312
+#endif
313
+    }
314
+
315
+    if ((out_bits & (1<<Z_AXIS)) != 0) {   // -direction
316
+      WRITE(Z_DIR_PIN,INVERT_Z_DIR);
317
+      #ifdef DEBUG_STEPS
318
+      count_direction[Z_AXIS]=-1;
319
+      #endif
320
+#if Z_MIN_PIN > -1
321
+      if(READ(Z_MIN_PIN) != ENDSTOPS_INVERTING) {
322
+        step_events_completed = current_block->step_event_count;
323
+      }
324
+#endif
325
+    }
326
+    else { // +direction
327
+        WRITE(Z_DIR_PIN,!INVERT_Z_DIR);
328
+        #ifdef DEBUG_STEPS
329
+        count_direction[Z_AXIS]=1;
330
+        #endif
331
+#if Z_MAX_PIN > -1
332
+        if((READ(Z_MAX_PIN) != ENDSTOPS_INVERTING)  && (current_block->steps_z >0)){
333
+          step_events_completed = current_block->step_event_count;
334
+        }
335
+#endif
336
+    }
337
+
338
+#ifndef ADVANCE
339
+    if ((out_bits & (1<<E_AXIS)) != 0)   // -direction
340
+      WRITE(E_DIR_PIN,INVERT_E_DIR);
341
+    else // +direction
342
+      WRITE(E_DIR_PIN,!INVERT_E_DIR);
343
+#endif //!ADVANCE
344
+
345
+    for(char i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves) 
346
+      counter_x += current_block->steps_x;
347
+      if (counter_x > 0) {
348
+        WRITE(X_STEP_PIN, HIGH);
349
+        counter_x -= current_block->step_event_count;
350
+        WRITE(X_STEP_PIN, LOW);
351
+        #ifdef DEBUG_STEPS
352
+        count_position[X_AXIS]+=count_direction[X_AXIS];   
353
+        #endif
354
+      }
355
+
356
+      counter_y += current_block->steps_y;
357
+      if (counter_y > 0) {
358
+        WRITE(Y_STEP_PIN, HIGH);
359
+        counter_y -= current_block->step_event_count;
360
+        WRITE(Y_STEP_PIN, LOW);
361
+        #ifdef DEBUG_STEPS
362
+        count_position[Y_AXIS]+=count_direction[Y_AXIS];
363
+        #endif
364
+      }
365
+
366
+      counter_z += current_block->steps_z;
367
+      if (counter_z > 0) {
368
+        WRITE(Z_STEP_PIN, HIGH);
369
+        counter_z -= current_block->step_event_count;
370
+        WRITE(Z_STEP_PIN, LOW);
371
+        #ifdef DEBUG_STEPS
372
+        count_position[Z_AXIS]+=count_direction[Z_AXIS];
373
+        #endif
374
+      }
375
+
376
+#ifndef ADVANCE
377
+      counter_e += current_block->steps_e;
378
+      if (counter_e > 0) {
379
+        WRITE(E_STEP_PIN, HIGH);
380
+        counter_e -= current_block->step_event_count;
381
+        WRITE(E_STEP_PIN, LOW);
382
+      }
383
+#endif //!ADVANCE
384
+      step_events_completed += 1;  
385
+      if(step_events_completed >= current_block->step_event_count) break;
386
+    }
387
+    // Calculare new timer value
388
+    unsigned short timer;
389
+    unsigned short step_rate;
390
+    if (step_events_completed <= current_block->accelerate_until) {
391
+      MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
392
+      acc_step_rate += current_block->initial_rate;
393
+      
394
+      // upper limit
395
+      if(acc_step_rate > current_block->nominal_rate)
396
+        acc_step_rate = current_block->nominal_rate;
397
+
398
+      // step_rate to timer interval
399
+      timer = calc_timer(acc_step_rate);
400
+#ifdef ADVANCE
401
+      advance += advance_rate;
402
+#endif
403
+      acceleration_time += timer;
404
+      OCR1A = timer;
405
+    } 
406
+    else if (step_events_completed > current_block->decelerate_after) {   
407
+      MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
408
+      
409
+      if(step_rate > acc_step_rate) { // Check step_rate stays positive
410
+        step_rate = current_block->final_rate;
411
+      }
412
+      else {
413
+        step_rate = acc_step_rate - step_rate; // Decelerate from aceleration end point.
414
+      }
415
+
416
+      // lower limit
417
+      if(step_rate < current_block->final_rate)
418
+        step_rate = current_block->final_rate;
419
+
420
+      // step_rate to timer interval
421
+      timer = calc_timer(step_rate);
422
+#ifdef ADVANCE
423
+      advance -= advance_rate;
424
+      if(advance < final_advance)
425
+        advance = final_advance;
426
+#endif //ADVANCE
427
+      deceleration_time += timer;
428
+      OCR1A = timer;
429
+    }       
430
+    // If current block is finished, reset pointer 
431
+    if (step_events_completed >= current_block->step_event_count) {
432
+      current_block = NULL;
433
+      plan_discard_current_block();
434
+    }   
435
+  } 
436
+  cli(); // disable interrupts
437
+  busy=false;
438
+}
439
+
440
+#ifdef ADVANCE
441
+
442
+unsigned char old_OCR0A;
443
+// Timer interrupt for E. e_steps is set in the main routine;
444
+// Timer 0 is shared with millies
445
+ISR(TIMER0_COMPA_vect)
446
+{
447
+  // Critical section needed because Timer 1 interrupt has higher priority. 
448
+  // The pin set functions are placed on trategic position to comply with the stepper driver timing.
449
+  WRITE(E_STEP_PIN, LOW);
450
+  // Set E direction (Depends on E direction + advance)
451
+  if (e_steps < 0) {
452
+    WRITE(E_DIR_PIN,INVERT_E_DIR);    
453
+    e_steps++;
454
+    WRITE(E_STEP_PIN, HIGH);
455
+  } 
456
+  if (e_steps > 0) {
457
+    WRITE(E_DIR_PIN,!INVERT_E_DIR);
458
+    e_steps--;
459
+    WRITE(E_STEP_PIN, HIGH);
460
+  }
461
+  old_OCR0A += 25; // 10kHz interrupt
462
+  OCR0A = old_OCR0A;
463
+}
464
+#endif // ADVANCE
465
+
466
+void st_init()
467
+{
468
+    //Initialize Dir Pins
469
+#if X_DIR_PIN > -1
470
+  SET_OUTPUT(X_DIR_PIN);
471
+#endif
472
+#if Y_DIR_PIN > -1 
473
+  SET_OUTPUT(Y_DIR_PIN);
474
+#endif
475
+#if Z_DIR_PIN > -1 
476
+  SET_OUTPUT(Z_DIR_PIN);
477
+#endif
478
+#if E_DIR_PIN > -1 
479
+  SET_OUTPUT(E_DIR_PIN);
480
+#endif
481
+
482
+  //Initialize Enable Pins - steppers default to disabled.
483
+
484
+#if (X_ENABLE_PIN > -1)
485
+  SET_OUTPUT(X_ENABLE_PIN);
486
+  if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
487
+#endif
488
+#if (Y_ENABLE_PIN > -1)
489
+  SET_OUTPUT(Y_ENABLE_PIN);
490
+  if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
491
+#endif
492
+#if (Z_ENABLE_PIN > -1)
493
+  SET_OUTPUT(Z_ENABLE_PIN);
494
+  if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
495
+#endif
496
+#if (E_ENABLE_PIN > -1)
497
+  SET_OUTPUT(E_ENABLE_PIN);
498
+  if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH);
499
+#endif
500
+
501
+  //endstops and pullups
502
+#ifdef ENDSTOPPULLUPS
503
+#if X_MIN_PIN > -1
504
+  SET_INPUT(X_MIN_PIN); 
505
+  WRITE(X_MIN_PIN,HIGH);
506
+#endif
507
+#if X_MAX_PIN > -1
508
+  SET_INPUT(X_MAX_PIN); 
509
+  WRITE(X_MAX_PIN,HIGH);
510
+#endif
511
+#if Y_MIN_PIN > -1
512
+  SET_INPUT(Y_MIN_PIN); 
513
+  WRITE(Y_MIN_PIN,HIGH);
514
+#endif
515
+#if Y_MAX_PIN > -1
516
+  SET_INPUT(Y_MAX_PIN); 
517
+  WRITE(Y_MAX_PIN,HIGH);
518
+#endif
519
+#if Z_MIN_PIN > -1
520
+  SET_INPUT(Z_MIN_PIN); 
521
+  WRITE(Z_MIN_PIN,HIGH);
522
+#endif
523
+#if Z_MAX_PIN > -1
524
+  SET_INPUT(Z_MAX_PIN); 
525
+  WRITE(Z_MAX_PIN,HIGH);
526
+#endif
527
+#else //ENDSTOPPULLUPS
528
+#if X_MIN_PIN > -1
529
+  SET_INPUT(X_MIN_PIN); 
530
+#endif
531
+#if X_MAX_PIN > -1
532
+  SET_INPUT(X_MAX_PIN); 
533
+#endif
534
+#if Y_MIN_PIN > -1
535
+  SET_INPUT(Y_MIN_PIN); 
536
+#endif
537
+#if Y_MAX_PIN > -1
538
+  SET_INPUT(Y_MAX_PIN); 
539
+#endif
540
+#if Z_MIN_PIN > -1
541
+  SET_INPUT(Z_MIN_PIN); 
542
+#endif
543
+#if Z_MAX_PIN > -1
544
+  SET_INPUT(Z_MAX_PIN); 
545
+#endif
546
+#endif //ENDSTOPPULLUPS
547
+ 
548
+
549
+  //Initialize Step Pins
550
+#if (X_STEP_PIN > -1) 
551
+  SET_OUTPUT(X_STEP_PIN);
552
+#endif  
553
+#if (Y_STEP_PIN > -1) 
554
+  SET_OUTPUT(Y_STEP_PIN);
555
+#endif  
556
+#if (Z_STEP_PIN > -1) 
557
+  SET_OUTPUT(Z_STEP_PIN);
558
+#endif  
559
+#if (E_STEP_PIN > -1) 
560
+  SET_OUTPUT(E_STEP_PIN);
561
+#endif  
562
+
563
+  // waveform generation = 0100 = CTC
564
+  TCCR1B &= ~(1<<WGM13);
565
+  TCCR1B |=  (1<<WGM12);
566
+  TCCR1A &= ~(1<<WGM11); 
567
+  TCCR1A &= ~(1<<WGM10);
568
+
569
+  // output mode = 00 (disconnected)
570
+  TCCR1A &= ~(3<<COM1A0); 
571
+  TCCR1A &= ~(3<<COM1B0); 
572
+  TCCR1B = (TCCR1B & ~(0x07<<CS10)) | (2<<CS10); // 2MHz timer
573
+
574
+  OCR1A = 0x4000;
575
+  DISABLE_STEPPER_DRIVER_INTERRUPT();  
576
+
577
+#ifdef ADVANCE
578
+  e_steps = 0;
579
+  TIMSK0 |= (1<<OCIE0A);
580
+#endif //ADVANCE
581
+  sei();
582
+}
583
+
584
+// Block until all buffered steps are executed
585
+void st_synchronize()
586
+{
587
+  while(plan_get_current_block()) {
588
+    manage_heater();
589
+    manage_inactivity(1);
590
+    LCD_STATUS;
591
+  }   
592
+}

+ 40
- 0
Marlin/stepper.h View File

@@ -0,0 +1,40 @@
1
+/*
2
+  stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
3
+  Part of Grbl
4
+
5
+  Copyright (c) 2009-2011 Simen Svale Skogsrud
6
+
7
+  Grbl is free software: you can redistribute it and/or modify
8
+  it under the terms of the GNU General Public License as published by
9
+  the Free Software Foundation, either version 3 of the License, or
10
+  (at your option) any later version.
11
+
12
+  Grbl is distributed in the hope that it will be useful,
13
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
14
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
15
+  GNU General Public License for more details.
16
+
17
+  You should have received a copy of the GNU General Public License
18
+  along with Grbl.  If not, see <http://www.gnu.org/licenses/>.
19
+*/
20
+
21
+#ifndef stepper_h
22
+#define stepper_h 
23
+// Initialize and start the stepper motor subsystem
24
+void st_init();
25
+
26
+// Block until all buffered steps are executed
27
+void st_synchronize();
28
+
29
+// The stepper subsystem goes to sleep when it runs out of things to execute. Call this
30
+// to notify the subsystem that it is time to go to work.
31
+void st_wake_up();
32
+
33
+// if DEBUG_STEPS is enabled, M114 can be used to compare two methods of determining the X,Y,Z position of the printer.
34
+// for debugging purposes only, should be disabled by default
35
+#ifdef DEBUG_STEPS
36
+extern volatile long count_position[NUM_AXIS];
37
+extern volatile int count_direction[NUM_AXIS];
38
+#endif
39
+
40
+#endif

+ 84
- 0
Marlin/streaming.h View File

@@ -0,0 +1,84 @@
1
+/*
2
+Streaming.h - Arduino library for supporting the << streaming operator
3
+Copyright (c) 2010 Mikal Hart.  All rights reserved.
4
+
5
+This library is free software; you can redistribute it and/or
6
+modify it under the terms of the GNU Lesser General Public
7
+License as published by the Free Software Foundation; either
8
+version 2.1 of the License, or (at your option) any later version.
9
+
10
+This library is distributed in the hope that it will be useful,
11
+but WITHOUT ANY WARRANTY; without even the implied warranty of
12
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
13
+Lesser General Public License for more details.
14
+
15
+You should have received a copy of the GNU Lesser General Public
16
+License along with this library; if not, write to the Free Software
17
+Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
18
+*/
19
+
20
+#ifndef ARDUINO_STREAMING
21
+#define ARDUINO_STREAMING
22
+
23
+//#include <WProgram.h>
24
+
25
+#define STREAMING_LIBRARY_VERSION 4
26
+
27
+// Generic template
28
+template<class T> 
29
+inline Print &operator <<(Print &stream, T arg) 
30
+{ stream.print(arg); return stream; }
31
+
32
+struct _BASED 
33
+{ 
34
+  long val; 
35
+  int base;
36
+  _BASED(long v, int b): val(v), base(b) 
37
+  {}
38
+};
39
+
40
+#define _HEX(a)     _BASED(a, HEX)
41
+#define _DEC(a)     _BASED(a, DEC)
42
+#define _OCT(a)     _BASED(a, OCT)
43
+#define _BIN(a)     _BASED(a, BIN)
44
+#define _BYTE(a)    _BASED(a, BYTE)
45
+
46
+// Specialization for class _BASED
47
+// Thanks to Arduino forum user Ben Combee who suggested this 
48
+// clever technique to allow for expressions like
49
+//   Serial << _HEX(a);
50
+
51
+inline Print &operator <<(Print &obj, const _BASED &arg)
52
+{ obj.print(arg.val, arg.base); return obj; } 
53
+
54
+#if ARDUINO >= 18
55
+// Specialization for class _FLOAT
56
+// Thanks to Michael Margolis for suggesting a way
57
+// to accommodate Arduino 0018's floating point precision
58
+// feature like this:
59
+//   Serial << _FLOAT(gps_latitude, 6); // 6 digits of precision
60
+
61
+struct _FLOAT
62
+{
63
+  float val;
64
+  int digits;
65
+  _FLOAT(double v, int d): val(v), digits(d)
66
+  {}
67
+};
68
+
69
+inline Print &operator <<(Print &obj, const _FLOAT &arg)
70
+{ obj.print(arg.val, arg.digits); return obj; }
71
+#endif
72
+
73
+// Specialization for enum _EndLineCode
74
+// Thanks to Arduino forum user Paul V. who suggested this
75
+// clever technique to allow for expressions like
76
+//   Serial << "Hello!" << endl;
77
+
78
+enum _EndLineCode { endl };
79
+
80
+inline Print &operator <<(Print &obj, _EndLineCode arg) 
81
+{ obj.println(); return obj; }
82
+
83
+#endif
84
+

+ 476
- 0
Marlin/temperature.cpp View File

@@ -0,0 +1,476 @@
1
+/*
2
+  temperature.c - temperature control
3
+  Part of Marlin
4
+  
5
+ Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
6
+ 
7
+ This program is free software: you can redistribute it and/or modify
8
+ it under the terms of the GNU General Public License as published by
9
+ the Free Software Foundation, either version 3 of the License, or
10
+ (at your option) any later version.
11
+ 
12
+ This program is distributed in the hope that it will be useful,
13
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
14
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
15
+ GNU General Public License for more details.
16
+ 
17
+ You should have received a copy of the GNU General Public License
18
+ along with this program.  If not, see <http://www.gnu.org/licenses/>.
19
+ */
20
+
21
+/*
22
+ This firmware is a mashup between Sprinter and grbl.
23
+  (https://github.com/kliment/Sprinter)
24
+  (https://github.com/simen/grbl/tree)
25
+ 
26
+ It has preliminary support for Matthew Roberts advance algorithm 
27
+    http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
28
+
29
+ This firmware is optimized for gen6 electronics.
30
+ */
31
+
32
+#include "fastio.h"
33
+#include "Configuration.h"
34
+#include "pins.h"
35
+#include "Marlin.h"
36
+#include "ultralcd.h"
37
+#include "streaming.h"
38
+#include "temperature.h"
39
+
40
+int target_bed_raw = 0;
41
+int current_bed_raw = 0;
42
+
43
+int target_raw[3] = {0, 0, 0};
44
+int current_raw[3] = {0, 0, 0};
45
+unsigned char temp_meas_ready = false;
46
+
47
+unsigned long previous_millis_heater, previous_millis_bed_heater;
48
+
49
+#ifdef PIDTEMP
50
+  double temp_iState = 0;
51
+  double temp_dState = 0;
52
+  double pTerm;
53
+  double iTerm;
54
+  double dTerm;
55
+      //int output;
56
+  double pid_error;
57
+  double temp_iState_min;
58
+  double temp_iState_max;
59
+  double pid_setpoint = 0.0;
60
+  double pid_input;
61
+  double pid_output;
62
+  bool pid_reset;
63
+  float HeaterPower;
64
+  
65
+  float Kp=DEFAULT_Kp;
66
+  float Ki=DEFAULT_Ki;
67
+  float Kd=DEFAULT_Kd;
68
+  float Kc=DEFAULT_Kc;
69
+#endif //PIDTEMP
70
+
71
+#ifdef MINTEMP
72
+int minttemp = temp2analog(MINTEMP);
73
+#endif //MINTEMP
74
+#ifdef MAXTEMP
75
+int maxttemp = temp2analog(MAXTEMP);
76
+#endif //MAXTEMP
77
+
78
+#ifdef BED_MINTEMP
79
+int bed_minttemp = temp2analog(BED_MINTEMP);
80
+#endif //BED_MINTEMP
81
+#ifdef BED_MAXTEMP
82
+int bed_maxttemp = temp2analog(BED_MAXTEMP);
83
+#endif //BED_MAXTEMP
84
+
85
+void manage_heater()
86
+{
87
+#ifdef USE_WATCHDOG
88
+  wd_reset();
89
+#endif
90
+  
91
+  float pid_input;
92
+  float pid_output;
93
+  if(temp_meas_ready == true) {
94
+
95
+CRITICAL_SECTION_START;
96
+    temp_meas_ready = false;
97
+CRITICAL_SECTION_END;
98
+
99
+#ifdef PIDTEMP
100
+    pid_input = analog2temp(current_raw[0]);
101
+
102
+#ifndef PID_OPENLOOP
103
+    pid_error = pid_setpoint - pid_input;
104
+    if(pid_error > 10){
105
+      pid_output = PID_MAX;
106
+      pid_reset = true;
107
+    }
108
+    else if(pid_error < -10) {
109
+      pid_output = 0;
110
+      pid_reset = true;
111
+    }
112
+    else {
113
+      if(pid_reset == true) {
114
+        temp_iState = 0.0;
115
+        pid_reset = false;
116
+      }
117
+      pTerm = Kp * pid_error;
118
+      temp_iState += pid_error;
119
+      temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max);
120
+      iTerm = Ki * temp_iState;
121
+      #define K1 0.95
122
+      #define K2 (1.0-K1)
123
+      dTerm = (Kd * (pid_input - temp_dState))*K2 + (K1 * dTerm);
124
+      temp_dState = pid_input;
125
+      pid_output = constrain(pTerm + iTerm - dTerm, 0, PID_MAX);
126
+    }
127
+#endif //PID_OPENLOOP
128
+#ifdef PID_DEBUG
129
+     Serial.print(" Input ");
130
+     Serial.print(pid_input);
131
+     Serial.print(" Output ");
132
+     Serial.print(pid_output);    
133
+     Serial.print(" pTerm ");
134
+     Serial.print(pTerm); 
135
+     Serial.print(" iTerm ");
136
+     Serial.print(iTerm); 
137
+     Serial.print(" dTerm ");
138
+     Serial.print(dTerm); 
139
+     Serial.println();
140
+#endif //PID_DEBUG
141
+    analogWrite(HEATER_0_PIN, pid_output);
142
+#endif //PIDTEMP
143
+
144
+#ifndef PIDTEMP
145
+    if(current_raw[0] >= target_raw[0])
146
+    {
147
+      WRITE(HEATER_0_PIN,LOW);
148
+    }
149
+    else 
150
+    {
151
+      WRITE(HEATER_0_PIN,HIGH);
152
+    }
153
+#endif
154
+    
155
+  if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
156
+    return;
157
+  previous_millis_bed_heater = millis();
158
+  
159
+  #if TEMP_1_PIN > -1
160
+    if(current_raw[1] >= target_raw[1])
161
+    {
162
+      WRITE(HEATER_1_PIN,LOW);
163
+    }
164
+    else 
165
+    {
166
+      WRITE(HEATER_1_PIN,HIGH);
167
+    }
168
+  #endif
169
+  }
170
+}
171
+
172
+// Takes hot end temperature value as input and returns corresponding raw value. 
173
+// For a thermistor, it uses the RepRap thermistor temp table.
174
+// This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
175
+// This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
176
+float temp2analog(int celsius) {
177
+  #ifdef HEATER_USES_THERMISTOR
178
+    int raw = 0;
179
+    byte i;
180
+    
181
+    for (i=1; i<NUMTEMPS; i++)
182
+    {
183
+      if (temptable[i][1] < celsius)
184
+      {
185
+        raw = temptable[i-1][0] + 
186
+          (celsius - temptable[i-1][1]) * 
187
+          (temptable[i][0] - temptable[i-1][0]) /
188
+          (temptable[i][1] - temptable[i-1][1]);
189
+      
190
+        break;
191
+      }
192
+    }
193
+
194
+    // Overflow: Set to last value in the table
195
+    if (i == NUMTEMPS) raw = temptable[i-1][0];
196
+
197
+    return (1023 * OVERSAMPLENR) - raw;
198
+  #elif defined HEATER_USES_AD595
199
+    return celsius * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
200
+  #endif
201
+}
202
+
203
+// Takes bed temperature value as input and returns corresponding raw value. 
204
+// For a thermistor, it uses the RepRap thermistor temp table.
205
+// This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
206
+// This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
207
+float temp2analogBed(int celsius) {
208
+  #ifdef BED_USES_THERMISTOR
209
+
210
+    int raw = 0;
211
+    byte i;
212
+    
213
+    for (i=1; i<BNUMTEMPS; i++)
214
+    {
215
+      if (bedtemptable[i][1] < celsius)
216
+      {
217
+        raw = bedtemptable[i-1][0] + 
218
+          (celsius - bedtemptable[i-1][1]) * 
219
+          (bedtemptable[i][0] - bedtemptable[i-1][0]) /
220
+          (bedtemptable[i][1] - bedtemptable[i-1][1]);
221
+      
222
+        break;
223
+      }
224
+    }
225
+
226
+    // Overflow: Set to last value in the table
227
+    if (i == BNUMTEMPS) raw = bedtemptable[i-1][0];
228
+
229
+    return (1023 * OVERSAMPLENR) - raw;
230
+  #elif defined BED_USES_AD595
231
+    return celsius * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
232
+  #endif
233
+}
234
+
235
+// Derived from RepRap FiveD extruder::getTemperature()
236
+// For hot end temperature measurement.
237
+float analog2temp(int raw) {
238
+  #ifdef HEATER_USES_THERMISTOR
239
+    int celsius = 0;
240
+    byte i;  
241
+    raw = (1023 * OVERSAMPLENR) - raw;
242
+    for (i=1; i<NUMTEMPS; i++)
243
+    {
244
+      if (temptable[i][0] > raw)
245
+      {
246
+        celsius  = temptable[i-1][1] + 
247
+          (raw - temptable[i-1][0]) * 
248
+          (temptable[i][1] - temptable[i-1][1]) /
249
+          (temptable[i][0] - temptable[i-1][0]);
250
+
251
+        break;
252
+      }
253
+    }
254
+
255
+    // Overflow: Set to last value in the table
256
+    if (i == NUMTEMPS) celsius = temptable[i-1][1];
257
+
258
+    return celsius;
259
+  #elif defined HEATER_USES_AD595
260
+    return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
261
+  #endif
262
+}
263
+
264
+// Derived from RepRap FiveD extruder::getTemperature()
265
+// For bed temperature measurement.
266
+float analog2tempBed(int raw) {
267
+  #ifdef BED_USES_THERMISTOR
268
+    int celsius = 0;
269
+    byte i;
270
+
271
+    raw = (1023 * OVERSAMPLENR) - raw;
272
+
273
+    for (i=1; i<NUMTEMPS; i++)
274
+    {
275
+      if (bedtemptable[i][0] > raw)
276
+      {
277
+        celsius  = bedtemptable[i-1][1] + 
278
+          (raw - bedtemptable[i-1][0]) * 
279
+          (bedtemptable[i][1] - bedtemptable[i-1][1]) /
280
+          (bedtemptable[i][0] - bedtemptable[i-1][0]);
281
+
282
+        break;
283
+      }
284
+    }
285
+
286
+    // Overflow: Set to last value in the table
287
+    if (i == NUMTEMPS) celsius = bedtemptable[i-1][1];
288
+
289
+    return celsius;
290
+    
291
+  #elif defined BED_USES_AD595
292
+    return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
293
+  #endif
294
+}
295
+
296
+void tp_init()
297
+{
298
+#if (HEATER_0_PIN > -1) 
299
+  SET_OUTPUT(HEATER_0_PIN);
300
+#endif  
301
+#if (HEATER_1_PIN > -1) 
302
+  SET_OUTPUT(HEATER_1_PIN);
303
+#endif  
304
+#if (HEATER_2_PIN > -1) 
305
+  SET_OUTPUT(HEATER_2_PIN);
306
+#endif  
307
+
308
+#ifdef PIDTEMP
309
+  temp_iState_min = 0.0;
310
+  temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
311
+#endif //PIDTEMP
312
+
313
+// Set analog inputs
314
+  ADCSRA = 1<<ADEN | 1<<ADSC | 1<<ADIF | 0x07;
315
+  
316
+// Use timer0 for temperature measurement
317
+// Interleave temperature interrupt with millies interrupt
318
+  OCR0B = 128;
319
+  TIMSK0 |= (1<<OCIE0B);  
320
+}
321
+
322
+static unsigned char temp_count = 0;
323
+static unsigned long raw_temp_0_value = 0;
324
+static unsigned long raw_temp_1_value = 0;
325
+static unsigned long raw_temp_2_value = 0;
326
+static unsigned char temp_state = 0;
327
+
328
+// Timer 0 is shared with millies
329
+ISR(TIMER0_COMPB_vect)
330
+{
331
+  switch(temp_state) {
332
+    case 0: // Prepare TEMP_0
333
+            #if (TEMP_0_PIN > -1)
334
+              #if TEMP_0_PIN < 8
335
+                DIDR0 = 1 << TEMP_0_PIN; 
336
+              #else
337
+                DIDR2 = 1<<(TEMP_0_PIN - 8); 
338
+                ADCSRB = 1<<MUX5;
339
+              #endif
340
+              ADMUX = ((1 << REFS0) | (TEMP_0_PIN & 0x07));
341
+              ADCSRA |= 1<<ADSC; // Start conversion
342
+            #endif
343
+            #ifdef ULTIPANEL
344
+              buttons_check();
345
+            #endif
346
+            temp_state = 1;
347
+            break;
348
+    case 1: // Measure TEMP_0
349
+            #if (TEMP_0_PIN > -1)
350
+              raw_temp_0_value += ADC;
351
+            #endif
352
+            temp_state = 2;
353
+            break;
354
+    case 2: // Prepare TEMP_1
355
+            #if (TEMP_1_PIN > -1)
356
+              #if TEMP_1_PIN < 7
357
+                DIDR0 = 1<<TEMP_1_PIN; 
358
+              #else
359
+                DIDR2 = 1<<(TEMP_1_PIN - 8); 
360
+                ADCSRB = 1<<MUX5;
361
+              #endif
362
+              ADMUX = ((1 << REFS0) | (TEMP_1_PIN & 0x07));
363
+              ADCSRA |= 1<<ADSC; // Start conversion
364
+            #endif
365
+            #ifdef ULTIPANEL
366
+              buttons_check();
367
+            #endif
368
+            temp_state = 3;
369
+            break;
370
+    case 3: // Measure TEMP_1
371
+            #if (TEMP_1_PIN > -1)
372
+              raw_temp_1_value += ADC;
373
+            #endif
374
+            temp_state = 4;
375
+            break;
376
+    case 4: // Prepare TEMP_2
377
+            #if (TEMP_2_PIN > -1)
378
+              #if TEMP_2_PIN < 7
379
+                DIDR0 = 1 << TEMP_2_PIN; 
380
+              #else
381
+                DIDR2 = 1<<(TEMP_2_PIN - 8); 
382
+                ADCSRB = 1<<MUX5;
383
+              #endif
384
+              ADMUX = ((1 << REFS0) | (TEMP_2_PIN & 0x07));
385
+              ADCSRA |= 1<<ADSC; // Start conversion
386
+            #endif
387
+            #ifdef ULTIPANEL
388
+              buttons_check();
389
+            #endif
390
+            temp_state = 5;
391
+            break;
392
+    case 5: // Measure TEMP_2
393
+            #if (TEMP_2_PIN > -1)
394
+              raw_temp_2_value += ADC;
395
+            #endif
396
+            temp_state = 0;
397
+            temp_count++;
398
+            break;
399
+    default:
400
+            Serial.println("!! Temp measurement error !!");
401
+            break;
402
+  }
403
+    
404
+  if(temp_count >= 16) // 6 ms * 16 = 96ms.
405
+  {
406
+    #ifdef HEATER_USES_AD595
407
+      current_raw[0] = raw_temp_0_value;
408
+      current_raw[2] = raw_temp_2_value;
409
+    #else
410
+      current_raw[0] = 16383 - raw_temp_0_value;
411
+      current_raw[2] = 16383 - raw_temp_2_value;
412
+    #endif
413
+    
414
+    #ifdef BED_USES_AD595
415
+      current_raw[1] = raw_temp_1_value;
416
+    #else
417
+      current_raw[1] = 16383 - raw_temp_1_value;
418
+    #endif
419
+    
420
+    temp_meas_ready = true;
421
+    temp_count = 0;
422
+    raw_temp_0_value = 0;
423
+    raw_temp_1_value = 0;
424
+    raw_temp_2_value = 0;
425
+#ifdef MAXTEMP
426
+  #if (HEATER_0_PIN > -1)
427
+    if(current_raw[0] >= maxttemp) {
428
+      target_raw[0] = 0;
429
+      analogWrite(HEATER_0_PIN, 0);
430
+      Serial.println("!! Temperature extruder 0 switched off. MAXTEMP triggered !!");
431
+    }
432
+  #endif
433
+  #if (HEATER_2_PIN > -1)
434
+    if(current_raw[2] >= maxttemp) {
435
+      target_raw[2] = 0;
436
+      analogWrite(HEATER_2_PIN, 0);
437
+      Serial.println("!! Temperature extruder 1 switched off. MAXTEMP triggered !!");
438
+    }
439
+  #endif
440
+#endif //MAXTEMP
441
+#ifdef MINTEMP
442
+  #if (HEATER_0_PIN > -1)
443
+    if(current_raw[0] <= minttemp) {
444
+      target_raw[0] = 0;
445
+      analogWrite(HEATER_0_PIN, 0);
446
+      Serial.println("!! Temperature extruder 0 switched off. MINTEMP triggered !!");
447
+    }
448
+  #endif
449
+  #if (HEATER_2_PIN > -1)
450
+    if(current_raw[2] <= minttemp) {
451
+      target_raw[2] = 0;
452
+      analogWrite(HEATER_2_PIN, 0);
453
+      Serial.println("!! Temperature extruder 1 switched off. MINTEMP triggered !!");
454
+    }
455
+  #endif
456
+#endif //MAXTEMP
457
+#ifdef BED_MINTEMP
458
+  #if (HEATER_1_PIN > -1)
459
+    if(current_raw[1] <= bed_minttemp) {
460
+      target_raw[1] = 0;
461
+      WRITE(HEATER_1_PIN, 0);
462
+      Serial.println("!! Temperatur heated bed switched off. MINTEMP triggered !!");
463
+    }
464
+  #endif
465
+#endif
466
+#ifdef BED_MAXTEMP
467
+  #if (HEATER_1_PIN > -1)
468
+    if(current_raw[1] >= bed_maxttemp) {
469
+      target_raw[1] = 0;
470
+      WRITE(HEATER_1_PIN, 0);
471
+      Serial.println("!! Temperature heated bed switched off. MAXTEMP triggered !!");
472
+    }
473
+  #endif
474
+#endif
475
+  }
476
+}

+ 55
- 0
Marlin/temperature.h View File

@@ -0,0 +1,55 @@
1
+/*
2
+  temperature.h - temperature controller
3
+  Part of Marlin
4
+
5
+  Copyright (c) 2011 Erik van der Zalm
6
+
7
+  Grbl is free software: you can redistribute it and/or modify
8
+  it under the terms of the GNU General Public License as published by
9
+  the Free Software Foundation, either version 3 of the License, or
10
+  (at your option) any later version.
11
+
12
+  Grbl is distributed in the hope that it will be useful,
13
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
14
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
15
+  GNU General Public License for more details.
16
+
17
+  You should have received a copy of the GNU General Public License
18
+  along with Grbl.  If not, see <http://www.gnu.org/licenses/>.
19
+*/
20
+
21
+#ifndef temperature_h
22
+#define temperature_h 
23
+
24
+void manage_inactivity(byte debug);
25
+
26
+void tp_init();
27
+void manage_heater();
28
+//int temp2analogu(int celsius, const short table[][2], int numtemps);
29
+//float analog2tempu(int raw, const short table[][2], int numtemps);
30
+float temp2analog(int celsius);
31
+float temp2analogBed(int celsius);
32
+float analog2temp(int raw);
33
+float analog2tempBed(int raw);
34
+
35
+#ifdef HEATER_USES_THERMISTOR
36
+    #define HEATERSOURCE 1
37
+#endif
38
+#ifdef BED_USES_THERMISTOR
39
+    #define BEDSOURCE 1
40
+#endif
41
+
42
+//#define temp2analogh( c ) temp2analogu((c),temptable,NUMTEMPS)
43
+//#define analog2temp( c ) analog2tempu((c),temptable,NUMTEMPS
44
+
45
+
46
+extern float Kp;
47
+extern float Ki;
48
+extern float Kd;
49
+extern float Kc;
50
+
51
+extern int target_raw[3];
52
+extern int current_raw[3];
53
+extern double pid_setpoint;
54
+
55
+#endif

+ 111
- 110
Marlin/thermistortables.h View File

@@ -1,132 +1,133 @@
1 1
 #ifndef THERMISTORTABLES_H_
2 2
 #define THERMISTORTABLES_H_
3 3
 
4
+#define OVERSAMPLENR 16
4 5
 #if (THERMISTORHEATER == 1) || (THERMISTORBED == 1) //100k bed thermistor
5 6
 
6 7
 
7 8
 #define NUMTEMPS_1 61
8 9
 const short temptable_1[NUMTEMPS_1][2] = {
9
-{	(23*16)	,	300	},
10
-{	(25*16)	,	295	},
11
-{	(27*16)	,	290	},
12
-{	(28*16)	,	285	},
13
-{	(31*16)	,	280	},
14
-{	(33*16)	,	275	},
15
-{	(35*16)	,	270	},
16
-{	(38*16)	,	265	},
17
-{	(41*16)	,	260	},
18
-{	(44*16)	,	255	},
19
-{	(48*16)	,	250	},
20
-{	(52*16)	,	245	},
21
-{	(56*16)	,	240	},
22
-{	(61*16)	,	235	},
23
-{	(66*16)	,	230	},
24
-{	(71*16)	,	225	},
25
-{	(78*16)	,	220	},
26
-{	(84*16)	,	215	},
27
-{	(92*16)	,	210	},
28
-{	(100*16),	205	},
29
-{	(109*16),	200	},
30
-{	(120*16),	195	},
31
-{	(131*16),	190	},
32
-{	(143*16),	185	},
33
-{	(156*16),	180	},
34
-{	(171*16),	175	},
35
-{	(187*16),	170	},
36
-{	(205*16),	165	},
37
-{	(224*16),	160	},
38
-{	(245*16),	155	},
39
-{	(268*16),	150	},
40
-{	(293*16),	145	},
41
-{	(320*16),	140	},
42
-{	(348*16),	135	},
43
-{	(379*16),	130	},
44
-{	(411*16),	125	},
45
-{	(445*16),	120	},
46
-{	(480*16),	115	},
47
-{	(516*16),	110	},
48
-{	(553*16),	105	},
49
-{	(591*16),	100	},
50
-{	(628*16),	95	},
51
-{	(665*16),	90	},
52
-{	(702*16),	85	},
53
-{	(737*16),	80	},
54
-{	(770*16),	75	},
55
-{	(801*16),	70	},
56
-{	(830*16),	65	},
57
-{	(857*16),	60	},
58
-{	(881*16),	55	},
59
-{	(903*16),	50	},
60
-{	(922*16),	45	},
61
-{	(939*16),	40	},
62
-{	(954*16),	35	},
63
-{	(966*16),	30	},
64
-{	(977*16),	25	},
65
-{	(985*16),	20	},
66
-{	(993*16),	15	},
67
-{	(999*16),	10	},
68
-{	(1004*16),	5	},
69
-{	(1008*16),	0	} //safety
10
+{	(23*OVERSAMPLENR)	,	300	},
11
+{	(25*OVERSAMPLENR)	,	295	},
12
+{	(27*OVERSAMPLENR)	,	290	},
13
+{	(28*OVERSAMPLENR)	,	285	},
14
+{	(31*OVERSAMPLENR)	,	280	},
15
+{	(33*OVERSAMPLENR)	,	275	},
16
+{	(35*OVERSAMPLENR)	,	270	},
17
+{	(38*OVERSAMPLENR)	,	265	},
18
+{	(41*OVERSAMPLENR)	,	260	},
19
+{	(44*OVERSAMPLENR)	,	255	},
20
+{	(48*OVERSAMPLENR)	,	250	},
21
+{	(52*OVERSAMPLENR)	,	245	},
22
+{	(56*OVERSAMPLENR)	,	240	},
23
+{	(61*OVERSAMPLENR)	,	235	},
24
+{	(66*OVERSAMPLENR)	,	230	},
25
+{	(71*OVERSAMPLENR)	,	225	},
26
+{	(78*OVERSAMPLENR)	,	220	},
27
+{	(84*OVERSAMPLENR)	,	215	},
28
+{	(92*OVERSAMPLENR)	,	210	},
29
+{	(100*OVERSAMPLENR),	205	},
30
+{	(109*OVERSAMPLENR),	200	},
31
+{	(120*OVERSAMPLENR),	195	},
32
+{	(131*OVERSAMPLENR),	190	},
33
+{	(143*OVERSAMPLENR),	185	},
34
+{	(156*OVERSAMPLENR),	180	},
35
+{	(171*OVERSAMPLENR),	175	},
36
+{	(187*OVERSAMPLENR),	170	},
37
+{	(205*OVERSAMPLENR),	165	},
38
+{	(224*OVERSAMPLENR),	160	},
39
+{	(245*OVERSAMPLENR),	155	},
40
+{	(268*OVERSAMPLENR),	150	},
41
+{	(293*OVERSAMPLENR),	145	},
42
+{	(320*OVERSAMPLENR),	140	},
43
+{	(348*OVERSAMPLENR),	135	},
44
+{	(379*OVERSAMPLENR),	130	},
45
+{	(411*OVERSAMPLENR),	125	},
46
+{	(445*OVERSAMPLENR),	120	},
47
+{	(480*OVERSAMPLENR),	115	},
48
+{	(516*OVERSAMPLENR),	110	},
49
+{	(553*OVERSAMPLENR),	105	},
50
+{	(591*OVERSAMPLENR),	100	},
51
+{	(628*OVERSAMPLENR),	95	},
52
+{	(665*OVERSAMPLENR),	90	},
53
+{	(702*OVERSAMPLENR),	85	},
54
+{	(737*OVERSAMPLENR),	80	},
55
+{	(770*OVERSAMPLENR),	75	},
56
+{	(801*OVERSAMPLENR),	70	},
57
+{	(830*OVERSAMPLENR),	65	},
58
+{	(857*OVERSAMPLENR),	60	},
59
+{	(881*OVERSAMPLENR),	55	},
60
+{	(903*OVERSAMPLENR),	50	},
61
+{	(922*OVERSAMPLENR),	45	},
62
+{	(939*OVERSAMPLENR),	40	},
63
+{	(954*OVERSAMPLENR),	35	},
64
+{	(966*OVERSAMPLENR),	30	},
65
+{	(977*OVERSAMPLENR),	25	},
66
+{	(985*OVERSAMPLENR),	20	},
67
+{	(993*OVERSAMPLENR),	15	},
68
+{	(999*OVERSAMPLENR),	10	},
69
+{	(1004*OVERSAMPLENR),	5	},
70
+{	(1008*OVERSAMPLENR),	0	} //safety
70 71
 };
71 72
 #endif
72 73
 #if (THERMISTORHEATER == 2) || (THERMISTORBED == 2) //200k bed thermistor
73 74
 #define NUMTEMPS_2 21
74 75
 const short temptable_2[NUMTEMPS_2][2] = {
75
-   {(1*16), 848},
76
-   {(54*16), 275},
77
-   {(107*16), 228},
78
-   {(160*16), 202},
79
-   {(213*16), 185},
80
-   {(266*16), 171},
81
-   {(319*16), 160},
82
-   {(372*16), 150},
83
-   {(425*16), 141},
84
-   {(478*16), 133},
85
-   {(531*16), 125},
86
-   {(584*16), 118},
87
-   {(637*16), 110},
88
-   {(690*16), 103},
89
-   {(743*16), 95},
90
-   {(796*16), 86},
91
-   {(849*16), 77},
92
-   {(902*16), 65},
93
-   {(955*16), 49},
94
-   {(1008*16), 17},
95
-   {(1020*16), 0} //safety
76
+   {(1*OVERSAMPLENR), 848},
77
+   {(54*OVERSAMPLENR), 275},
78
+   {(107*OVERSAMPLENR), 228},
79
+   {(160*OVERSAMPLENR), 202},
80
+   {(213*OVERSAMPLENR), 185},
81
+   {(266*OVERSAMPLENR), 171},
82
+   {(319*OVERSAMPLENR), 160},
83
+   {(372*OVERSAMPLENR), 150},
84
+   {(425*OVERSAMPLENR), 141},
85
+   {(478*OVERSAMPLENR), 133},
86
+   {(531*OVERSAMPLENR), 125},
87
+   {(584*OVERSAMPLENR), 118},
88
+   {(637*OVERSAMPLENR), 110},
89
+   {(690*OVERSAMPLENR), 103},
90
+   {(743*OVERSAMPLENR), 95},
91
+   {(796*OVERSAMPLENR), 86},
92
+   {(849*OVERSAMPLENR), 77},
93
+   {(902*OVERSAMPLENR), 65},
94
+   {(955*OVERSAMPLENR), 49},
95
+   {(1008*OVERSAMPLENR), 17},
96
+   {(1020*OVERSAMPLENR), 0} //safety
96 97
 };
97 98
 
98 99
 #endif
99 100
 #if (THERMISTORHEATER == 3) || (THERMISTORBED == 3) //mendel-parts
100 101
 #define NUMTEMPS_3 28
101 102
 const short temptable_3[NUMTEMPS_3][2] = {
102
-		{(1*16),864},
103
-		{(21*16),300},
104
-		{(25*16),290},
105
-		{(29*16),280},
106
-		{(33*16),270},
107
-		{(39*16),260},
108
-		{(46*16),250},
109
-		{(54*16),240},
110
-		{(64*16),230},
111
-		{(75*16),220},
112
-		{(90*16),210},
113
-		{(107*16),200},
114
-		{(128*16),190},
115
-		{(154*16),180},
116
-		{(184*16),170},
117
-		{(221*16),160},
118
-		{(265*16),150},
119
-		{(316*16),140},
120
-		{(375*16),130},
121
-		{(441*16),120},
122
-		{(513*16),110},
123
-		{(588*16),100},
124
-		{(734*16),80},
125
-		{(856*16),60},
126
-		{(938*16),40},
127
-		{(986*16),20},
128
-		{(1008*16),0},
129
-		{(1018*16),-20}
103
+		{(1*OVERSAMPLENR),864},
104
+		{(21*OVERSAMPLENR),300},
105
+		{(25*OVERSAMPLENR),290},
106
+		{(29*OVERSAMPLENR),280},
107
+		{(33*OVERSAMPLENR),270},
108
+		{(39*OVERSAMPLENR),260},
109
+		{(46*OVERSAMPLENR),250},
110
+		{(54*OVERSAMPLENR),240},
111
+		{(64*OVERSAMPLENR),230},
112
+		{(75*OVERSAMPLENR),220},
113
+		{(90*OVERSAMPLENR),210},
114
+		{(107*OVERSAMPLENR),200},
115
+		{(128*OVERSAMPLENR),190},
116
+		{(154*OVERSAMPLENR),180},
117
+		{(184*OVERSAMPLENR),170},
118
+		{(221*OVERSAMPLENR),160},
119
+		{(265*OVERSAMPLENR),150},
120
+		{(316*OVERSAMPLENR),140},
121
+		{(375*OVERSAMPLENR),130},
122
+		{(441*OVERSAMPLENR),120},
123
+		{(513*OVERSAMPLENR),110},
124
+		{(588*OVERSAMPLENR),100},
125
+		{(734*OVERSAMPLENR),80},
126
+		{(856*OVERSAMPLENR),60},
127
+		{(938*OVERSAMPLENR),40},
128
+		{(986*OVERSAMPLENR),20},
129
+		{(1008*OVERSAMPLENR),0},
130
+		{(1018*OVERSAMPLENR),-20}
130 131
 	};
131 132
 
132 133
 #endif

+ 156
- 0
Marlin/ultralcd.h View File

@@ -0,0 +1,156 @@
1
+#ifndef __ULTRALCDH
2
+#define __ULTRALCDH
3
+#include "Configuration.h"
4
+
5
+#ifdef ULTRA_LCD
6
+
7
+  void lcd_status();
8
+  void lcd_init();
9
+  void lcd_status(const char* message);
10
+  void beep();
11
+  void buttons_check();
12
+  #define LCDSTATUSRIGHT
13
+
14
+  #define LCD_UPDATE_INTERVAL 100
15
+  #define STATUSTIMEOUT 15000
16
+
17
+  #include "Configuration.h"
18
+
19
+  #include <LiquidCrystal.h>
20
+  extern LiquidCrystal lcd;
21
+
22
+  //lcd display size
23
+
24
+#ifdef NEWPANEL
25
+ //arduino pin witch triggers an piezzo beeper
26
+  #define BEEPER 18
27
+
28
+  #define LCD_PINS_RS 20 
29
+  #define LCD_PINS_ENABLE 17
30
+  #define LCD_PINS_D4 16
31
+  #define LCD_PINS_D5 21 
32
+  #define LCD_PINS_D6 5
33
+  #define LCD_PINS_D7 6
34
+  
35
+  //buttons are directly attached
36
+  #define BTN_EN1 40
37
+  #define BTN_EN2 42
38
+  #define BTN_ENC 19  //the click
39
+  
40
+  #define BLEN_C 2
41
+  #define BLEN_B 1
42
+  #define BLEN_A 0
43
+  
44
+  #define SDCARDDETECT 38
45
+  
46
+  #define EN_C (1<<BLEN_C)
47
+  #define EN_B (1<<BLEN_B)
48
+  #define EN_A (1<<BLEN_A)
49
+  
50
+   //encoder rotation values
51
+  #define encrot0 0
52
+  #define encrot1 2
53
+  #define encrot2 3
54
+  #define encrot3 1
55
+
56
+  
57
+  #define CLICKED (buttons&EN_C)
58
+  #define BLOCK {blocking=millis()+blocktime;}
59
+  #define CARDINSERTED (READ(SDCARDDETECT)==0)
60
+  
61
+#else
62
+  //arduino pin witch triggers an piezzo beeper
63
+  #define BEEPER 18
64
+
65
+  //buttons are attached to a shift register
66
+  #define SHIFT_CLK 38
67
+  #define SHIFT_LD 42
68
+  #define SHIFT_OUT 40
69
+  #define SHIFT_EN 17
70
+  
71
+  #define LCD_PINS_RS 16 
72
+  #define LCD_PINS_ENABLE 5
73
+  #define LCD_PINS_D4 6
74
+  #define LCD_PINS_D5 21 
75
+  #define LCD_PINS_D6 20
76
+  #define LCD_PINS_D7 19
77
+  
78
+   //bits in the shift register that carry the buttons for:
79
+  // left up center down right red
80
+  #define BL_LE 7
81
+  #define BL_UP 6
82
+  #define BL_MI 5
83
+  #define BL_DW 4
84
+  #define BL_RI 3
85
+  #define BL_ST 2
86
+
87
+  #define BLEN_B 1
88
+  #define BLEN_A 0
89
+
90
+  //encoder rotation values
91
+  #define encrot0 0
92
+  #define encrot1 2
93
+  #define encrot2 3
94
+  #define encrot3 1
95
+
96
+  //atomatic, do not change
97
+  #define B_LE (1<<BL_LE)
98
+  #define B_UP (1<<BL_UP)
99
+  #define B_MI (1<<BL_MI)
100
+  #define B_DW (1<<BL_DW)
101
+  #define B_RI (1<<BL_RI)
102
+  #define B_ST (1<<BL_ST)
103
+  #define EN_B (1<<BLEN_B)
104
+  #define EN_A (1<<BLEN_A)
105
+  
106
+  #define CLICKED ((buttons&B_MI)||(buttons&B_ST))
107
+  #define BLOCK {blocking[BL_MI]=millis()+blocktime;blocking[BL_ST]=millis()+blocktime;}
108
+  
109
+#endif
110
+  // blocking time for recognizing a new keypress of one key, ms
111
+#define blocktime 500
112
+#define lcdslow 5
113
+  enum MainStatus{Main_Status, Main_Menu, Main_Prepare, Main_Control, Main_SD};
114
+
115
+  class MainMenu{
116
+  public:
117
+    MainMenu();
118
+    void update();
119
+    void getfilename(const uint8_t nr);
120
+    uint8_t activeline;
121
+    MainStatus status;
122
+    uint8_t displayStartingRow;
123
+    
124
+    void showStatus();
125
+    void showMainMenu();
126
+    void showPrepare();
127
+    void showControl();
128
+    void showSD();
129
+    bool force_lcd_update;
130
+    int lastencoderpos;
131
+    int8_t lineoffset;
132
+    int8_t lastlineoffset;
133
+    char filename[11];
134
+    bool linechanging;
135
+  };
136
+
137
+  char *fillto(int8_t n,char *c);
138
+  char *ftostr51(const float &x);
139
+  char *ftostr31(const float &x);
140
+  char *ftostr3(const float &x);
141
+
142
+
143
+
144
+  #define LCD_MESSAGE(x) lcd_status(x);
145
+  #define LCD_STATUS lcd_status()
146
+#else //no lcd
147
+  #define LCD_STATUS
148
+  #define LCD_MESSAGE(x)
149
+#endif
150
+  
151
+#ifndef ULTIPANEL  
152
+ #define CLICKED false
153
+#define BLOCK ;
154
+#endif 
155
+#endif //ULTRALCD
156
+

+ 1593
- 0
Marlin/ultralcd.pde
File diff suppressed because it is too large
View File


+ 0
- 176
Marlin/wiring.c View File

@@ -1,176 +0,0 @@
1
-/*
2
-  wiring.c - Partial implementation of the Wiring API for the ATmega8.
3
-  Part of Arduino - http://www.arduino.cc/
4
-
5
-  Copyright (c) 2005-2006 David A. Mellis
6
-
7
-  This library is free software; you can redistribute it and/or
8
-  modify it under the terms of the GNU Lesser General Public
9
-  License as published by the Free Software Foundation; either
10
-  version 2.1 of the License, or (at your option) any later version.
11
-
12
-  This library is distributed in the hope that it will be useful,
13
-  but WITHOUT ANY WARRANTY; without even the implied warranty of
14
-  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
15
-  Lesser General Public License for more details.
16
-
17
-  You should have received a copy of the GNU Lesser General
18
-  Public License along with this library; if not, write to the
19
-  Free Software Foundation, Inc., 59 Temple Place, Suite 330,
20
-  Boston, MA  02111-1307  USA
21
-
22
-  $Id: wiring.c 388 2008-03-08 22:05:23Z mellis $
23
-*/
24
-
25
-#include "wiring_private.h"
26
-
27
-volatile unsigned long timer0_millis = 0;
28
-
29
-SIGNAL(TIMER0_OVF_vect)
30
-{
31
-	// timer 0 prescale factor is 64 and the timer overflows at 256
32
-        timer0_millis++;
33
-}
34
-
35
-unsigned long millis()
36
-{
37
-	unsigned long m;
38
-	uint8_t oldSREG = SREG;
39
-	
40
-	// disable interrupts while we read timer0_millis or we might get an
41
-	// inconsistent value (e.g. in the middle of the timer0_millis++)
42
-	cli();
43
-	m = timer0_millis;
44
-	SREG = oldSREG;
45
-	
46
-	return m;
47
-}
48
-
49
-void delay(unsigned long ms)
50
-{
51
-	unsigned long start = millis();
52
-	
53
-	while (millis() - start <= ms)
54
-		;
55
-}
56
-
57
-/* Delay for the given number of microseconds.  Assumes a 8 or 16 MHz clock. 
58
- * Disables interrupts, which will disrupt the millis() function if used
59
- * too frequently. */
60
-void delayMicroseconds(unsigned int us)
61
-{
62
-	uint8_t oldSREG;
63
-
64
-	// calling avrlib's delay_us() function with low values (e.g. 1 or
65
-	// 2 microseconds) gives delays longer than desired.
66
-	//delay_us(us);
67
-
68
-#if F_CPU >= 16000000L
69
-	// for the 16 MHz clock on most Arduino boards
70
-
71
-	// for a one-microsecond delay, simply return.  the overhead
72
-	// of the function call yields a delay of approximately 1 1/8 us.
73
-	if (--us == 0)
74
-		return;
75
-
76
-	// the following loop takes a quarter of a microsecond (4 cycles)
77
-	// per iteration, so execute it four times for each microsecond of
78
-	// delay requested.
79
-	us <<= 2;
80
-
81
-	// account for the time taken in the preceeding commands.
82
-	us -= 2;
83
-#else
84
-	// for the 8 MHz internal clock on the ATmega168
85
-
86
-	// for a one- or two-microsecond delay, simply return.  the overhead of
87
-	// the function calls takes more than two microseconds.  can't just
88
-	// subtract two, since us is unsigned; we'd overflow.
89
-	if (--us == 0)
90
-		return;
91
-	if (--us == 0)
92
-		return;
93
-
94
-	// the following loop takes half of a microsecond (4 cycles)
95
-	// per iteration, so execute it twice for each microsecond of
96
-	// delay requested.
97
-	us <<= 1;
98
-
99
-	// partially compensate for the time taken by the preceeding commands.
100
-	// we can't subtract any more than this or we'd overflow w/ small delays.
101
-	us--;
102
-#endif
103
-
104
-	// disable interrupts, otherwise the timer 0 overflow interrupt that
105
-	// tracks milliseconds will make us delay longer than we want.
106
-	oldSREG = SREG;
107
-	cli();
108
-
109
-	// busy wait
110
-	__asm__ __volatile__ (
111
-		"1: sbiw %0,1" "\n\t" // 2 cycles
112
-		"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
113
-	);
114
-
115
-	// reenable interrupts.
116
-	SREG = oldSREG;
117
-}
118
-
119
-void init()
120
-{
121
-	// this needs to be called before setup() or some functions won't
122
-	// work there
123
-	sei();
124
-	
125
-	// on the ATmega168, timer 0 is also used for fast hardware pwm
126
-	// (using phase-correct PWM would mean that timer 0 overflowed half as often
127
-	// resulting in different millis() behavior on the ATmega8 and ATmega168)
128
-	sbi(TCCR0A, WGM01);
129
-	sbi(TCCR0A, WGM00);
130
-
131
-	// set timer 0 prescale factor to 64
132
-	sbi(TCCR0B, CS01);
133
-	sbi(TCCR0B, CS00);
134
-
135
-	// enable timer 0 overflow interrupt
136
-	sbi(TIMSK0, TOIE0);
137
-
138
-	// timers 1 and 2 are used for phase-correct hardware pwm
139
-	// this is better for motors as it ensures an even waveform
140
-	// note, however, that fast pwm mode can achieve a frequency of up
141
-	// 8 MHz (with a 16 MHz clock) at 50% duty cycle
142
-#if 0
143
-	// set timer 1 prescale factor to 64
144
-	sbi(TCCR1B, CS11);
145
-	sbi(TCCR1B, CS10);
146
-
147
-	// put timer 1 in 8-bit phase correct pwm mode
148
-	sbi(TCCR1A, WGM10);
149
-
150
-	// set timer 2 prescale factor to 64
151
-	sbi(TCCR2B, CS22);
152
-
153
-	// configure timer 2 for phase correct pwm (8-bit)
154
-	sbi(TCCR2A, WGM20);
155
-
156
-	// set a2d prescale factor to 128
157
-	// 16 MHz / 128 = 125 KHz, inside the desired 50-200 KHz range.
158
-	// XXX: this will not work properly for other clock speeds, and
159
-	// this code should use F_CPU to determine the prescale factor.
160
-	sbi(ADCSRA, ADPS2);
161
-	sbi(ADCSRA, ADPS1);
162
-	sbi(ADCSRA, ADPS0);
163
-
164
-	// enable a2d conversions
165
-	sbi(ADCSRA, ADEN);
166
-
167
-	// the bootloader connects pins 0 and 1 to the USART; disconnect them
168
-	// here so they can be used as normal digital i/o; they will be
169
-	// reconnected in Serial.begin()
170
-	UCSR0B = 0;
171
-	#if defined(__AVR_ATmega644P__)
172
-	//TODO: test to see if disabling this helps?
173
-	//UCSR1B = 0;
174
-	#endif
175
-#endif
176
-}

+ 0
- 139
Marlin/wiring_serial.c View File

@@ -1,139 +0,0 @@
1
-/*
2
-  wiring_serial.c - serial functions.
3
-  Part of Arduino - http://www.arduino.cc/
4
-
5
-  Copyright (c) 2005-2006 David A. Mellis
6
-  Modified 29 January 2009, Marius Kintel for Sanguino - http://www.sanguino.cc/
7
-
8
-  This library is free software; you can redistribute it and/or
9
-  modify it under the terms of the GNU Lesser General Public
10
-  License as published by the Free Software Foundation; either
11
-  version 2.1 of the License, or (at your option) any later version.
12
-
13
-  This library is distributed in the hope that it will be useful,
14
-  but WITHOUT ANY WARRANTY; without even the implied warranty of
15
-  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
16
-  Lesser General Public License for more details.
17
-
18
-  You should have received a copy of the GNU Lesser General
19
-  Public License along with this library; if not, write to the
20
-  Free Software Foundation, Inc., 59 Temple Place, Suite 330,
21
-  Boston, MA  02111-1307  USA
22
-
23
-  $Id: wiring.c 248 2007-02-03 15:36:30Z mellis $
24
-*/
25
-
26
-
27
-#include "wiring_private.h"
28
-
29
-// Define constants and variables for buffering incoming serial data.  We're
30
-// using a ring buffer (I think), in which rx_buffer_head is the index of the
31
-// location to which to write the next incoming character and rx_buffer_tail
32
-// is the index of the location from which to read.
33
-#define RX_BUFFER_SIZE 128
34
-#define RX_BUFFER_MASK 0x7f
35
-
36
-#if defined(__AVR_ATmega644P__)
37
-unsigned char rx_buffer[2][RX_BUFFER_SIZE];
38
-int rx_buffer_head[2] = {0, 0};
39
-int rx_buffer_tail[2] = {0, 0};
40
-#else
41
-unsigned char rx_buffer[1][RX_BUFFER_SIZE];
42
-int rx_buffer_head[1] = {0};
43
-int rx_buffer_tail[1] = {0};
44
-#endif
45
-
46
-
47
-#define BEGIN_SERIAL(uart_, baud_) \
48
-{ \
49
-    UBRR##uart_##H = ((F_CPU / 16 + baud / 2) / baud - 1) >> 8; \
50
-    UBRR##uart_##L = ((F_CPU / 16 + baud / 2) / baud - 1); \
51
-    \
52
-    /* reset config for UART */ \
53
-    UCSR##uart_##A = 0; \
54
-    UCSR##uart_##B = 0; \
55
-    UCSR##uart_##C = 0; \
56
-    \
57
-    /* enable rx and tx */ \
58
-    sbi(UCSR##uart_##B, RXEN##uart_);\
59
-    sbi(UCSR##uart_##B, TXEN##uart_);\
60
-    \
61
-    /* enable interrupt on complete reception of a byte */ \
62
-    sbi(UCSR##uart_##B, RXCIE##uart_); \
63
-    UCSR##uart_##C = _BV(UCSZ##uart_##1)|_BV(UCSZ##uart_##0); \
64
-    /* defaults to 8-bit, no parity, 1 stop bit */ \
65
-}
66
-
67
-void beginSerial(uint8_t uart, long baud)
68
-{
69
-  if (uart == 0) BEGIN_SERIAL(0, baud)
70
-#if defined(__AVR_ATmega644P__)
71
-  else BEGIN_SERIAL(1, baud)
72
-#endif
73
-}
74
-
75
-#define SERIAL_WRITE(uart_, c_) \
76
-    while (!(UCSR##uart_##A & (1 << UDRE##uart_))) \
77
-      ; \
78
-    UDR##uart_ = c
79
-
80
-void serialWrite(uint8_t uart, unsigned char c)
81
-{
82
-  if (uart == 0) {
83
-    SERIAL_WRITE(0, c);
84
-  }
85
-#if defined(__AVR_ATmega644P__)
86
-  else {
87
-    SERIAL_WRITE(1, c);
88
-  }
89
-#endif
90
-}
91
-
92
-int serialAvailable(uint8_t uart)
93
-{
94
-  return (RX_BUFFER_SIZE + rx_buffer_head[uart] - rx_buffer_tail[uart]) & RX_BUFFER_MASK;
95
-}
96
-
97
-int serialRead(uint8_t uart)
98
-{
99
-  // if the head isn't ahead of the tail, we don't have any characters
100
-  if (rx_buffer_head[uart] == rx_buffer_tail[uart]) {
101
-    return -1;
102
-  } else {
103
-    unsigned char c = rx_buffer[uart][rx_buffer_tail[uart]];
104
-    rx_buffer_tail[uart] = (rx_buffer_tail[uart] + 1) & RX_BUFFER_MASK;
105
-    return c;
106
-  }
107
-}
108
-
109
-void serialFlush(uint8_t uart)
110
-{
111
-  // don't reverse this or there may be problems if the RX interrupt
112
-  // occurs after reading the value of rx_buffer_head but before writing
113
-  // the value to rx_buffer_tail; the previous value of rx_buffer_head
114
-  // may be written to rx_buffer_tail, making it appear as if the buffer
115
-  // were full, not empty.
116
-  rx_buffer_head[uart] = rx_buffer_tail[uart];
117
-}
118
-
119
-#define UART_ISR(uart_) \
120
-ISR(USART##uart_##_RX_vect) \
121
-{ \
122
-  unsigned char c = UDR##uart_; \
123
-  \
124
-  int i = (rx_buffer_head[uart_] + 1) & RX_BUFFER_MASK; \
125
-  \  
126
-  /* if we should be storing the received character into the location \
127
-     just before the tail (meaning that the head would advance to the \
128
-     current location of the tail), we're about to overflow the buffer \
129
-     and so we don't write the character or advance the head. */ \
130
-  if (i != rx_buffer_tail[uart_]) { \
131
-    rx_buffer[uart_][rx_buffer_head[uart_]] = c; \
132
-    rx_buffer_head[uart_] = i; \
133
-  } \
134
-}
135
-
136
-UART_ISR(0)
137
-#if defined(__AVR_ATmega644P__) 
138
-UART_ISR(1)
139
-#endif

Loading…
Cancel
Save