瀏覽代碼

restore Branch from Backup

sorry for that
cocktailyogi 11 年之前
父節點
當前提交
512f2a3136

+ 7
- 1
Marlin/Configuration.h 查看文件

@@ -12,6 +12,13 @@
12 12
 // example_configurations/delta directory.
13 13
 //
14 14
 
15
+//===========================================================================
16
+//============================= SCARA Printer ===============================
17
+//===========================================================================
18
+// For a Delta printer replace the configuration files with the files in the
19
+// example_configurations/SCARA directory.
20
+//
21
+
15 22
 // User-specified version info of this build to display in [Pronterface, etc] terminal window during
16 23
 // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
17 24
 // build by the user have been successfully uploaded into firmware.
@@ -132,7 +139,6 @@
132 139
 // 1010 is Pt1000 with 1k pullup (non standard)
133 140
 // 147 is Pt100 with 4k7 pullup
134 141
 // 110 is Pt100 with 1k pullup (non standard)
135
-// 70 is 500C thermistor for Pico hot end
136 142
 
137 143
 #define TEMP_SENSOR_0 -1
138 144
 #define TEMP_SENSOR_1 -1

+ 29
- 5
Marlin/ConfigurationStore.cpp 查看文件

@@ -37,10 +37,15 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size)
37 37
 // the default values are used whenever there is a change to the data, to prevent
38 38
 // wrong data being written to the variables.
39 39
 // ALSO:  always make sure the variables in the Store and retrieve sections are in the same order.
40
-#ifdef DELTA
41
-#define EEPROM_VERSION "V11"
42
-#else
40
+
43 41
 #define EEPROM_VERSION "V10"
42
+#ifdef DELTA
43
+	#undef EEPROM_VERSION
44
+	#define EEPROM_VERSION "V11"
45
+#endif
46
+#ifdef SCARA
47
+	#undef EEPROM_VERSION
48
+	#define EEPROM_VERSION "V12"
44 49
 #endif
45 50
 
46 51
 #ifdef EEPROM_SETTINGS
@@ -49,7 +54,7 @@ void Config_StoreSettings()
49 54
   char ver[4]= "000";
50 55
   int i=EEPROM_OFFSET;
51 56
   EEPROM_WRITE_VAR(i,ver); // invalidate data first 
52
-  EEPROM_WRITE_VAR(i,axis_steps_per_unit);  
57
+  EEPROM_WRITE_VAR(i,axis_steps_per_unit);
53 58
   EEPROM_WRITE_VAR(i,max_feedrate);  
54 59
   EEPROM_WRITE_VAR(i,max_acceleration_units_per_sq_second);
55 60
   EEPROM_WRITE_VAR(i,acceleration);
@@ -93,6 +98,9 @@ void Config_StoreSettings()
93 98
     int lcd_contrast = 32;
94 99
   #endif
95 100
   EEPROM_WRITE_VAR(i,lcd_contrast);
101
+  #ifdef SCARA
102
+  EEPROM_WRITE_VAR(i,axis_scaling);        // Add scaling for SCARA
103
+  #endif
96 104
   char ver2[4]=EEPROM_VERSION;
97 105
   i=EEPROM_OFFSET;
98 106
   EEPROM_WRITE_VAR(i,ver2); // validate data
@@ -115,6 +123,16 @@ void Config_PrintSettings()
115 123
     SERIAL_ECHOLN("");
116 124
       
117 125
     SERIAL_ECHO_START;
126
+#ifdef SCARA
127
+SERIAL_ECHOLNPGM("Scaling factors:");
128
+    SERIAL_ECHO_START;
129
+    SERIAL_ECHOPAIR("  M365 X",axis_scaling[0]);
130
+    SERIAL_ECHOPAIR(" Y",axis_scaling[1]);
131
+    SERIAL_ECHOPAIR(" Z",axis_scaling[2]);
132
+    SERIAL_ECHOLN("");
133
+      
134
+    SERIAL_ECHO_START;
135
+#endif
118 136
     SERIAL_ECHOLNPGM("Maximum feedrates (mm/s):");
119 137
     SERIAL_ECHO_START;
120 138
     SERIAL_ECHOPAIR("  M203 X",max_feedrate[0]);
@@ -196,7 +214,7 @@ void Config_RetrieveSettings()
196 214
     if (strncmp(ver,stored_ver,3) == 0)
197 215
     {
198 216
         // version number match
199
-        EEPROM_READ_VAR(i,axis_steps_per_unit);  
217
+        EEPROM_READ_VAR(i,axis_steps_per_unit);
200 218
         EEPROM_READ_VAR(i,max_feedrate);  
201 219
         EEPROM_READ_VAR(i,max_acceleration_units_per_sq_second);
202 220
         
@@ -240,6 +258,9 @@ void Config_RetrieveSettings()
240 258
         int lcd_contrast;
241 259
         #endif
242 260
         EEPROM_READ_VAR(i,lcd_contrast);
261
+		#ifdef SCARA
262
+		EEPROM_READ_VAR(i,axis_scaling);
263
+		#endif
243 264
 
244 265
 		// Call updatePID (similar to when we have processed M301)
245 266
 		updatePID();
@@ -266,6 +287,9 @@ void Config_ResetDefault()
266 287
         axis_steps_per_unit[i]=tmp1[i];  
267 288
         max_feedrate[i]=tmp2[i];  
268 289
         max_acceleration_units_per_sq_second[i]=tmp3[i];
290
+		#ifdef SCARA
291
+		axis_scaling[i]=1;
292
+		#endif
269 293
     }
270 294
     
271 295
     // steps per sq second need to be updated to agree with the units per sq second

+ 7
- 0
Marlin/Marlin.h 查看文件

@@ -178,6 +178,10 @@ void get_coordinates();
178 178
 void calculate_delta(float cartesian[3]);
179 179
 extern float delta[3];
180 180
 #endif
181
+#ifdef SCARA
182
+void calculate_delta(float cartesian[3]);
183
+void calculate_SCARA_forward_Transform(float f_scara[3]);
184
+#endif
181 185
 void prepare_move();
182 186
 void kill();
183 187
 void Stop();
@@ -215,6 +219,9 @@ extern float delta_diagonal_rod;
215 219
 extern float delta_segments_per_second;
216 220
 void recalc_delta_settings(float radius, float diagonal_rod);
217 221
 #endif
222
+#ifdef SCARA
223
+extern float axis_scaling[3];  // Build size scaling
224
+#endif
218 225
 extern float min_pos[3];
219 226
 extern float max_pos[3];
220 227
 extern bool axis_known_position[3];

+ 357
- 11
Marlin/Marlin_main.cpp 查看文件

@@ -170,6 +170,16 @@
170 170
 // M908 - Control digital trimpot directly.
171 171
 // M350 - Set microstepping mode.
172 172
 // M351 - Toggle MS1 MS2 pins directly.
173
+
174
+// ************ SCARA Specific - This can change to suit future G-code regulations
175
+// M360 - SCARA calibration: Move to cal-position ThetaA (0 deg calibration)
176
+// M361 - SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree)
177
+// M362 - SCARA calibration: Move to cal-position PsiA (0 deg calibration)
178
+// M363 - SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree)
179
+// M364 - SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position)
180
+// M365 - SCARA calibration: Scaling factor, X, Y, Z axis
181
+//************* SCARA End ***************
182
+
173 183
 // M928 - Start SD logging (M928 filename.g) - ended by M29
174 184
 // M999 - Restart after being stopped by error
175 185
 
@@ -212,6 +222,7 @@ float add_homeing[3]={0,0,0};
212 222
 #ifdef DELTA
213 223
 float endstop_adj[3]={0,0,0};
214 224
 #endif
225
+
215 226
 float min_pos[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS };
216 227
 float max_pos[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS };
217 228
 bool axis_known_position[3] = {false, false, false};
@@ -274,13 +285,18 @@ int EtoPPressure=0;
274 285
   float delta_diagonal_rod= DELTA_DIAGONAL_ROD;
275 286
   float delta_diagonal_rod_2= sq(delta_diagonal_rod);
276 287
   float delta_segments_per_second= DELTA_SEGMENTS_PER_SECOND;
277
-#endif					
288
+#endif
289
+
290
+#ifdef SCARA                              // Build size scaling
291
+float axis_scaling[3]={1,1,1};  // Build size scaling, default to 1
292
+#endif				
278 293
 
279 294
 //===========================================================================
280 295
 //=============================Private Variables=============================
281 296
 //===========================================================================
282 297
 const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
283 298
 static float destination[NUM_AXIS] = {  0.0, 0.0, 0.0, 0.0};
299
+static float delta[3] = {0.0, 0.0, 0.0};
284 300
 static float offset[3] = {0.0, 0.0, 0.0};
285 301
 static bool home_all_axis = true;
286 302
 static float feedrate = 1500.0, next_feedrate, saved_feedrate;
@@ -850,9 +866,59 @@ static void axis_is_at_home(int axis) {
850 866
     }
851 867
   }
852 868
 #endif
869
+#ifdef SCARA
870
+   float homeposition[3];
871
+   char i;
872
+   
873
+   if (axis < 2)
874
+   {
875
+   
876
+     for (i=0; i<3; i++)
877
+     {
878
+        homeposition[i] = base_home_pos(i); 
879
+     }  
880
+	// SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]);
881
+   //  SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]);
882
+   // Works out real Homeposition angles using inverse kinematics, 
883
+   // and calculates homing offset using forward kinematics
884
+     calculate_delta(homeposition);
885
+     
886
+    // SERIAL_ECHOPGM("base Theta= "); SERIAL_ECHO(delta[X_AXIS]);
887
+    // SERIAL_ECHOPGM(" base Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
888
+     
889
+     for (i=0; i<2; i++)
890
+     {
891
+        delta[i] -= add_homeing[i];
892
+     } 
893
+     
894
+    // SERIAL_ECHOPGM("addhome X="); SERIAL_ECHO(add_homeing[X_AXIS]);
895
+	// SERIAL_ECHOPGM(" addhome Y="); SERIAL_ECHO(add_homeing[Y_AXIS]);
896
+    // SERIAL_ECHOPGM(" addhome Theta="); SERIAL_ECHO(delta[X_AXIS]);
897
+    // SERIAL_ECHOPGM(" addhome Psi+Theta="); SERIAL_ECHOLN(delta[Y_AXIS]);
898
+      
899
+     calculate_SCARA_forward_Transform(delta);
900
+     
901
+    // SERIAL_ECHOPGM("Delta X="); SERIAL_ECHO(delta[X_AXIS]);
902
+    // SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]);
903
+     
904
+    current_position[axis] = delta[axis];
905
+    
906
+    // SCARA home positions are based on configuration since the actual limits are determined by the 
907
+    // inverse kinematic transform.
908
+    min_pos[axis] =          base_min_pos(axis); // + (delta[axis] - base_home_pos(axis));
909
+    max_pos[axis] =          base_max_pos(axis); // + (delta[axis] - base_home_pos(axis));
910
+   } 
911
+   else
912
+   {
913
+      current_position[axis] = base_home_pos(axis) + add_homeing[axis];
914
+      min_pos[axis] =          base_min_pos(axis) + add_homeing[axis];
915
+      max_pos[axis] =          base_max_pos(axis) + add_homeing[axis];
916
+   }
917
+#else
853 918
   current_position[axis] = base_home_pos(axis) + add_homeing[axis];
854 919
   min_pos[axis] =          base_min_pos(axis) + add_homeing[axis];
855 920
   max_pos[axis] =          base_max_pos(axis) + add_homeing[axis];
921
+#endif
856 922
 }
857 923
 
858 924
 #ifdef ENABLE_AUTO_BED_LEVELING
@@ -1111,6 +1177,7 @@ static void homeaxis(int axis) {
1111 1177
   }
1112 1178
 }
1113 1179
 #define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
1180
+
1114 1181
 void refresh_cmd_timeout(void)
1115 1182
 {
1116 1183
   previous_millis_cmd = millis();
@@ -1184,6 +1251,7 @@ void process_commands()
1184 1251
         return;
1185 1252
       }
1186 1253
       break;
1254
+#ifdef SCARA //disable arc support
1187 1255
     case 2: // G2  - CW ARC
1188 1256
       if(Stopped == false) {
1189 1257
         get_arc_coordinates();
@@ -1198,6 +1266,7 @@ void process_commands()
1198 1266
         return;
1199 1267
       }
1200 1268
       break;
1269
+#endif
1201 1270
     case 4: // G4 dwell
1202 1271
       LCD_MESSAGEPGM(MSG_DWELL);
1203 1272
       codenum = 0;
@@ -1267,12 +1336,12 @@ void process_commands()
1267 1336
           HOMEAXIS(Z);
1268 1337
 
1269 1338
           calculate_delta(current_position);
1270
-          plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
1271
-
1339
+          plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);		  
1340
+		  
1272 1341
 #else // NOT DELTA
1273 1342
 
1274 1343
       home_all_axis = !((code_seen(axis_codes[X_AXIS])) || (code_seen(axis_codes[Y_AXIS])) || (code_seen(axis_codes[Z_AXIS])));
1275
-
1344
+	  
1276 1345
       #if Z_HOME_DIR > 0                      // If homing away from BED do Z first
1277 1346
       if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
1278 1347
         HOMEAXIS(Z);
@@ -1316,7 +1385,9 @@ void process_commands()
1316 1385
 
1317 1386
         current_position[X_AXIS] = destination[X_AXIS];
1318 1387
         current_position[Y_AXIS] = destination[Y_AXIS];
1388
+		#ifndef SCARA
1319 1389
         current_position[Z_AXIS] = destination[Z_AXIS];
1390
+		#endif
1320 1391
       }
1321 1392
       #endif
1322 1393
 
@@ -1346,13 +1417,21 @@ void process_commands()
1346 1417
       if(code_seen(axis_codes[X_AXIS]))
1347 1418
       {
1348 1419
         if(code_value_long() != 0) {
1349
-          current_position[X_AXIS]=code_value()+add_homeing[0];
1420
+		#ifdef SCARA
1421
+		   current_position[X_AXIS]=code_value();
1422
+		#else
1423
+		   current_position[X_AXIS]=code_value()+add_homeing[0];
1424
+		#endif
1350 1425
         }
1351 1426
       }
1352 1427
 
1353 1428
       if(code_seen(axis_codes[Y_AXIS])) {
1354 1429
         if(code_value_long() != 0) {
1355
-          current_position[Y_AXIS]=code_value()+add_homeing[1];
1430
+         #ifdef SCARA
1431
+		   current_position[Y_AXIS]=code_value();
1432
+		#else
1433
+		   current_position[Y_AXIS]=code_value()+add_homeing[1];
1434
+		#endif
1356 1435
         }
1357 1436
       }
1358 1437
 
@@ -1427,6 +1506,11 @@ void process_commands()
1427 1506
       plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
1428 1507
 #endif // else DELTA
1429 1508
 
1509
+#ifdef SCARA
1510
+	  calculate_delta(current_position);
1511
+      plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
1512
+#endif SCARA
1513
+
1430 1514
       #ifdef ENDSTOPS_ONLY_FOR_HOMING
1431 1515
         enable_endstops(false);
1432 1516
       #endif
@@ -1623,8 +1707,17 @@ void process_commands()
1623 1707
              plan_set_e_position(current_position[E_AXIS]);
1624 1708
            }
1625 1709
            else {
1626
-             current_position[i] = code_value()+add_homeing[i];
1627
-             plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
1710
+#ifdef SCARA
1711
+		if (i == X_AXIS || i == Y_AXIS) {
1712
+                	current_position[i] = code_value();  
1713
+		}
1714
+		else {
1715
+                current_position[i] = code_value()+add_homeing[i];  
1716
+            	}  
1717
+#else
1718
+		current_position[i] = code_value()+add_homeing[i];
1719
+#endif
1720
+            plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
1628 1721
            }
1629 1722
         }
1630 1723
       }
@@ -2214,6 +2307,26 @@ void process_commands()
2214 2307
       SERIAL_PROTOCOL(float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]);
2215 2308
 
2216 2309
       SERIAL_PROTOCOLLN("");
2310
+#ifdef SCARA
2311
+	  SERIAL_PROTOCOLPGM("SCARA Theta:");
2312
+      SERIAL_PROTOCOL(delta[X_AXIS]);
2313
+      SERIAL_PROTOCOLPGM("   Psi+Theta:");
2314
+      SERIAL_PROTOCOL(delta[Y_AXIS]);
2315
+      SERIAL_PROTOCOLLN("");
2316
+      
2317
+      SERIAL_PROTOCOLPGM("SCARA Cal - Theta:");
2318
+      SERIAL_PROTOCOL(delta[X_AXIS]+add_homeing[0]);
2319
+      SERIAL_PROTOCOLPGM("   Psi+Theta (90):");
2320
+      SERIAL_PROTOCOL(delta[Y_AXIS]-delta[X_AXIS]-90+add_homeing[1]);
2321
+      SERIAL_PROTOCOLLN("");
2322
+      
2323
+      SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:");
2324
+      SERIAL_PROTOCOL(delta[X_AXIS]/90*axis_steps_per_unit[X_AXIS]);
2325
+      SERIAL_PROTOCOLPGM("   Psi+Theta:");
2326
+      SERIAL_PROTOCOL((delta[Y_AXIS]-delta[X_AXIS])/90*axis_steps_per_unit[Y_AXIS]);
2327
+      SERIAL_PROTOCOLLN("");
2328
+      SERIAL_PROTOCOLLN("");
2329
+#endif
2217 2330
       break;
2218 2331
     case 120: // M120
2219 2332
       enable_endstops(false) ;
@@ -2335,6 +2448,16 @@ void process_commands()
2335 2448
       {
2336 2449
         if(code_seen(axis_codes[i])) add_homeing[i] = code_value();
2337 2450
       }
2451
+	  #ifdef SCARA
2452
+	   if(code_seen('T'))       // Theta
2453
+      {
2454
+        add_homeing[0] = code_value() ;
2455
+      }
2456
+      if(code_seen('P'))       // Psi
2457
+      {
2458
+        add_homeing[1] = code_value() ;
2459
+      }
2460
+	  #endif
2338 2461
       break;
2339 2462
     #ifdef DELTA
2340 2463
 	case 665: // M665 set delta configurations L<diagonal_rod> R<delta_radius> S<segments_per_sec>
@@ -2693,6 +2816,105 @@ void process_commands()
2693 2816
       PID_autotune(temp, e, c);
2694 2817
     }
2695 2818
     break;
2819
+	#ifdef SCARA
2820
+	case 360:  // M360 SCARA Theta pos1
2821
+      SERIAL_ECHOLN(" Cal: Theta 0 ");
2822
+      //SoftEndsEnabled = false;              // Ignore soft endstops during calibration
2823
+      //SERIAL_ECHOLN(" Soft endstops disabled ");
2824
+      if(Stopped == false) {
2825
+        //get_coordinates(); // For X Y Z E F
2826
+        delta[0] = 0;
2827
+        delta[1] = 120;
2828
+        calculate_SCARA_forward_Transform(delta);
2829
+        destination[0] = delta[0]/axis_scaling[X_AXIS];
2830
+        destination[1] = delta[1]/axis_scaling[Y_AXIS];
2831
+        
2832
+        prepare_move();
2833
+        //ClearToSend();
2834
+        return;
2835
+      }
2836
+    break;
2837
+
2838
+    case 361:  // SCARA Theta pos2
2839
+      SERIAL_ECHOLN(" Cal: Theta 90 ");
2840
+      //SoftEndsEnabled = false;              // Ignore soft endstops during calibration
2841
+      //SERIAL_ECHOLN(" Soft endstops disabled ");
2842
+      if(Stopped == false) {
2843
+        //get_coordinates(); // For X Y Z E F
2844
+        delta[0] = 90;
2845
+        delta[1] = 130;
2846
+        calculate_SCARA_forward_Transform(delta);
2847
+        destination[0] = delta[0]/axis_scaling[X_AXIS];
2848
+        destination[1] = delta[1]/axis_scaling[Y_AXIS];
2849
+        
2850
+        prepare_move();
2851
+        //ClearToSend();
2852
+        return;
2853
+      }
2854
+    break;
2855
+    case 362:  // SCARA Psi pos1
2856
+      SERIAL_ECHOLN(" Cal: Psi 0 ");
2857
+      //SoftEndsEnabled = false;              // Ignore soft endstops during calibration
2858
+      //SERIAL_ECHOLN(" Soft endstops disabled ");
2859
+      if(Stopped == false) {
2860
+        //get_coordinates(); // For X Y Z E F
2861
+        delta[0] = 60;
2862
+        delta[1] = 180;
2863
+        calculate_SCARA_forward_Transform(delta);
2864
+        destination[0] = delta[0]/axis_scaling[X_AXIS];
2865
+        destination[1] = delta[1]/axis_scaling[Y_AXIS];
2866
+        
2867
+        prepare_move();
2868
+        //ClearToSend();
2869
+        return;
2870
+      }
2871
+    break;
2872
+    case 363:  // SCARA Psi pos2
2873
+      SERIAL_ECHOLN(" Cal: Psi 90 ");
2874
+      //SoftEndsEnabled = false;              // Ignore soft endstops during calibration
2875
+      //SERIAL_ECHOLN(" Soft endstops disabled ");
2876
+      if(Stopped == false) {
2877
+        //get_coordinates(); // For X Y Z E F
2878
+        delta[0] = 50;
2879
+        delta[1] = 90;
2880
+        calculate_SCARA_forward_Transform(delta);
2881
+        destination[0] = delta[0]/axis_scaling[X_AXIS];
2882
+        destination[1] = delta[1]/axis_scaling[Y_AXIS];
2883
+        
2884
+        prepare_move();
2885
+        //ClearToSend();
2886
+        return;
2887
+      }
2888
+    break;
2889
+    case 364:  // SCARA Psi pos3 (90 deg to Theta)
2890
+      SERIAL_ECHOLN(" Cal: Theta-Psi 90 ");
2891
+     // SoftEndsEnabled = false;              // Ignore soft endstops during calibration
2892
+      //SERIAL_ECHOLN(" Soft endstops disabled ");
2893
+      if(Stopped == false) {
2894
+        //get_coordinates(); // For X Y Z E F
2895
+        delta[0] = 45;
2896
+        delta[1] = 135;
2897
+        calculate_SCARA_forward_Transform(delta);
2898
+        destination[0] = delta[0]/axis_scaling[X_AXIS];
2899
+        destination[1] = delta[1]/axis_scaling[Y_AXIS]; 
2900
+        
2901
+        prepare_move();
2902
+        //ClearToSend();
2903
+        return;
2904
+      }
2905
+    break;
2906
+    case 365: // M364  Set SCARA scaling for X Y Z
2907
+      for(int8_t i=0; i < 3; i++) 
2908
+      {
2909
+        if(code_seen(axis_codes[i])) 
2910
+        {
2911
+          
2912
+            axis_scaling[i] = code_value();
2913
+          
2914
+        }
2915
+      }
2916
+      break;
2917
+	#endif
2696 2918
     case 400: // M400 finish all moves
2697 2919
     {
2698 2920
       st_synchronize();
@@ -3255,8 +3477,46 @@ void calculate_delta(float cartesian[3])
3255 3477
 void prepare_move()
3256 3478
 {
3257 3479
   clamp_to_software_endstops(destination);
3258
-
3259 3480
   previous_millis_cmd = millis();
3481
+  
3482
+  #ifdef SCARA //for now same as delta-code
3483
+
3484
+float difference[NUM_AXIS];
3485
+for (int8_t i=0; i < NUM_AXIS; i++) {
3486
+	difference[i] = destination[i] - current_position[i];
3487
+}
3488
+
3489
+float cartesian_mm = sqrt(	sq(difference[X_AXIS]) +
3490
+							sq(difference[Y_AXIS]) +
3491
+							sq(difference[Z_AXIS]));
3492
+if (cartesian_mm < 0.000001) { cartesian_mm = abs(difference[E_AXIS]); }
3493
+if (cartesian_mm < 0.000001) { return; }
3494
+float seconds = 6000 * cartesian_mm / feedrate / feedmultiply;
3495
+int steps = max(1, int(scara_segments_per_second * seconds));
3496
+ //SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
3497
+ //SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
3498
+ //SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
3499
+for (int s = 1; s <= steps; s++) {
3500
+	float fraction = float(s) / float(steps);
3501
+	for(int8_t i=0; i < NUM_AXIS; i++) {
3502
+		destination[i] = current_position[i] + difference[i] * fraction;
3503
+	}
3504
+
3505
+	
3506
+	calculate_delta(destination);
3507
+         //SERIAL_ECHOPGM("destination[0]="); SERIAL_ECHOLN(destination[0]);
3508
+         //SERIAL_ECHOPGM("destination[1]="); SERIAL_ECHOLN(destination[1]);
3509
+         //SERIAL_ECHOPGM("destination[2]="); SERIAL_ECHOLN(destination[2]);
3510
+         //SERIAL_ECHOPGM("delta[X_AXIS]="); SERIAL_ECHOLN(delta[X_AXIS]);
3511
+         //SERIAL_ECHOPGM("delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
3512
+         //SERIAL_ECHOPGM("delta[Z_AXIS]="); SERIAL_ECHOLN(delta[Z_AXIS]);
3513
+         
3514
+	plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS],
3515
+	destination[E_AXIS], feedrate*feedmultiply/60/100.0,
3516
+	active_extruder);
3517
+}
3518
+#endif // SCARA
3519
+  
3260 3520
 #ifdef DELTA
3261 3521
   float difference[NUM_AXIS];
3262 3522
   for (int8_t i=0; i < NUM_AXIS; i++) {
@@ -3282,7 +3542,8 @@ void prepare_move()
3282 3542
                      destination[E_AXIS], feedrate*feedmultiply/60/100.0,
3283 3543
                      active_extruder);
3284 3544
   }
3285
-#else
3545
+  
3546
+#endif // DELTA
3286 3547
 
3287 3548
 #ifdef DUAL_X_CARRIAGE
3288 3549
   if (active_extruder_parked)
@@ -3325,6 +3586,7 @@ void prepare_move()
3325 3586
   }
3326 3587
 #endif //DUAL_X_CARRIAGE
3327 3588
 
3589
+#if ! (defined DELTA || defined SCARA)
3328 3590
   // Do not use feedmultiply for E or Z only moves
3329 3591
   if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) {
3330 3592
       plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
@@ -3332,7 +3594,8 @@ void prepare_move()
3332 3594
   else {
3333 3595
     plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0, active_extruder);
3334 3596
   }
3335
-#endif //else DELTA
3597
+#endif // !(DELTA || SCARA)
3598
+
3336 3599
   for(int8_t i=0; i < NUM_AXIS; i++) {
3337 3600
     current_position[i] = destination[i];
3338 3601
   }
@@ -3400,6 +3663,89 @@ void controllerFan()
3400 3663
 }
3401 3664
 #endif
3402 3665
 
3666
+#ifdef SCARA
3667
+void calculate_SCARA_forward_Transform(float f_scara[3])
3668
+{
3669
+  // Perform forward kinematics, and place results in delta[3]
3670
+  // The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
3671
+  
3672
+  float x_sin, x_cos, y_sin, y_cos;
3673
+  
3674
+    //SERIAL_ECHOPGM("f_delta x="); SERIAL_ECHO(f_scara[X_AXIS]);
3675
+    //SERIAL_ECHOPGM(" y="); SERIAL_ECHO(f_scara[Y_AXIS]);
3676
+  
3677
+    x_sin = sin(f_scara[X_AXIS]/SCARA_RAD2DEG) * Linkage_1/1000;
3678
+    x_cos = cos(f_scara[X_AXIS]/SCARA_RAD2DEG) * Linkage_1/1000;
3679
+    y_sin = sin(f_scara[Y_AXIS]/SCARA_RAD2DEG) * Linkage_2/1000;
3680
+    y_cos = cos(f_scara[Y_AXIS]/SCARA_RAD2DEG) * Linkage_2/1000;
3681
+   
3682
+  //  SERIAL_ECHOPGM(" x_sin="); SERIAL_ECHO(x_sin);
3683
+  //  SERIAL_ECHOPGM(" x_cos="); SERIAL_ECHO(x_cos);
3684
+  //  SERIAL_ECHOPGM(" y_sin="); SERIAL_ECHO(y_sin);
3685
+  //  SERIAL_ECHOPGM(" y_cos="); SERIAL_ECHOLN(y_cos);
3686
+  
3687
+    delta[X_AXIS] = x_cos + y_cos + SCARA_offset_x;  //theta
3688
+    delta[Y_AXIS] = x_sin + y_sin + SCARA_offset_y;  //theta+phi
3689
+	
3690
+    //SERIAL_ECHOPGM(" delta[X_AXIS]="); SERIAL_ECHO(delta[X_AXIS]);
3691
+    //SERIAL_ECHOPGM(" delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]);
3692
+}  
3693
+
3694
+void calculate_delta(float cartesian[3]){
3695
+  //reverse kinematics.
3696
+  // Perform reversed kinematics, and place results in delta[3]
3697
+  // The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014
3698
+  
3699
+  float SCARA_pos[2];
3700
+  static float L1_2, L2_2, SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi; 
3701
+  
3702
+  SCARA_pos[X_AXIS] = cartesian[X_AXIS] * axis_scaling[X_AXIS] - SCARA_offset_x;  //Translate SCARA to standard X Y
3703
+  SCARA_pos[Y_AXIS] = cartesian[Y_AXIS] * axis_scaling[Y_AXIS] - SCARA_offset_y;  // With scaling factor.
3704
+  
3705
+  L1_2 = pow(Linkage_1/1000,2);
3706
+  L2_2 = pow(Linkage_2/1000,2);
3707
+  
3708
+  #if (Linkage_1 == Linkage_2)
3709
+    SCARA_C2 = ( ( pow(SCARA_pos[X_AXIS],2) + pow(SCARA_pos[Y_AXIS],2) ) / (2 * L1_2) ) - 1;
3710
+  #else
3711
+    SCARA_C2 =   ( pow(SCARA_pos[X_AXIS],2) + pow(SCARA_pos[Y_AXIS],2) - L1_2 - L2_2 ) / 45000; 
3712
+  #endif
3713
+  
3714
+  SCARA_S2 = sqrt( 1 - pow(SCARA_C2,2) );
3715
+  
3716
+  SCARA_K1 = Linkage_1/1000+Linkage_2/1000*SCARA_C2;
3717
+  SCARA_K2 = Linkage_2/1000*SCARA_S2;
3718
+  
3719
+  SCARA_theta = (atan2(SCARA_pos[X_AXIS],SCARA_pos[Y_AXIS])-atan2(SCARA_K1, SCARA_K2))*-1;
3720
+  SCARA_psi = atan2(SCARA_S2,SCARA_C2);
3721
+  
3722
+  delta[X_AXIS] = SCARA_theta * SCARA_RAD2DEG;  // Multiply by 180/Pi  -  theta is support arm angle
3723
+  delta[Y_AXIS] = (SCARA_theta + SCARA_psi) * SCARA_RAD2DEG;  //       -  equal to sub arm angle (inverted motor)
3724
+  delta[Z_AXIS] = cartesian[Z_AXIS];
3725
+  
3726
+  
3727
+  /*
3728
+  SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
3729
+  SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
3730
+  SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
3731
+  
3732
+  SERIAL_ECHOPGM("scara x="); SERIAL_ECHO(SCARA_pos[X_AXIS]);
3733
+  SERIAL_ECHOPGM(" y="); SERIAL_ECHOLN(SCARA_pos[Y_AXIS]);
3734
+  
3735
+  SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]);
3736
+  SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]);
3737
+  SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]);
3738
+  
3739
+  SERIAL_ECHOPGM("C2="); SERIAL_ECHO(SCARA_C2);
3740
+  SERIAL_ECHOPGM(" S2="); SERIAL_ECHO(SCARA_S2);
3741
+  SERIAL_ECHOPGM(" Theta="); SERIAL_ECHO(SCARA_theta);
3742
+  SERIAL_ECHOPGM(" Psi="); SERIAL_ECHOLN(SCARA_psi);
3743
+  SERIAL_ECHOLN(" ");
3744
+  */
3745
+}
3746
+
3747
+#endif
3748
+
3403 3749
 #ifdef TEMP_STAT_LEDS
3404 3750
 static bool blue_led = false;
3405 3751
 static bool red_led = false;

+ 743
- 0
Marlin/example_configurations/SCARA/Configuration.h 查看文件

@@ -0,0 +1,743 @@
1
+#ifndef CONFIGURATION_H
2
+#define CONFIGURATION_H
3
+
4
+// This configuration file contains the basic settings.
5
+// Advanced settings can be found in Configuration_adv.h
6
+// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
7
+
8
+//===========================================================================
9
+//========================= SCARA Settings ==================================
10
+//===========================================================================
11
+// SCARA-mode for Marlin has been developed by QHARLEY in ZA in 2012/2013. Implemented
12
+// and slightly reworked by JCERNY in 06/2014 with the goal to bring it into Master-Branch
13
+// QHARLEYS Autobedlevelling has not been ported, because Marlin has now Bed-levelling
14
+// You might need Z-Min endstop on SCARA-Printer to use this feature. Actually untested!
15
+// Uncomment to use Morgan scara mode
16
+#define SCARA  
17
+#define scara_segments_per_second 200
18
+// Length of inner support arm
19
+#define Linkage_1 150000 //um      Preprocessor cannot handle decimal point...
20
+// Length of outer support arm     Measure arm lengths precisely, and enter 
21
+#define Linkage_2 150000 //um      define in micrometer
22
+
23
+// SCARA tower offset (position of Tower relative to bed zero position) 
24
+// This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
25
+#define SCARA_offset_x 100 //mm   
26
+#define SCARA_offset_y -56 //mm
27
+#define SCARA_RAD2DEG 57.2957795  // to convert RAD to degrees
28
+
29
+//===========================================================================
30
+//========================= SCARA Settings end ==================================
31
+//===========================================================================
32
+
33
+// User-specified version info of this build to display in [Pronterface, etc] terminal window during
34
+// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
35
+// build by the user have been successfully uploaded into firmware.
36
+#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
37
+#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
38
+
39
+// SERIAL_PORT selects which serial port should be used for communication with the host.
40
+// This allows the connection of wireless adapters (for instance) to non-default port pins.
41
+// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
42
+#define SERIAL_PORT 0
43
+
44
+// This determines the communication speed of the printer
45
+// This determines the communication speed of the printer
46
+#define BAUDRATE 250000
47
+
48
+// This enables the serial port associated to the Bluetooth interface
49
+//#define BTENABLED              // Enable BT interface on AT90USB devices
50
+
51
+
52
+//// The following define selects which electronics board you have. Please choose the one that matches your setup
53
+// 10 = Gen7 custom (Alfons3 Version) "https://github.com/Alfons3/Generation_7_Electronics"
54
+// 11 = Gen7 v1.1, v1.2 = 11
55
+// 12 = Gen7 v1.3
56
+// 13 = Gen7 v1.4
57
+// 131 = OpenHardware.co.za custom Gen7 electronics
58
+// 2  = Cheaptronic v1.0
59
+// 20 = Sethi 3D_1
60
+// 3  = MEGA/RAMPS up to 1.2 = 3
61
+// 33 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Bed)
62
+// 34 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed)
63
+// 35 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Fan)
64
+// 4  = Duemilanove w/ ATMega328P pin assignment
65
+// 5  = Gen6
66
+// 51 = Gen6 deluxe
67
+// 6  = Sanguinololu < 1.2
68
+// 62 = Sanguinololu 1.2 and above
69
+// 63 = Melzi
70
+// 64 = STB V1.1
71
+// 65 = Azteeg X1
72
+// 66 = Melzi with ATmega1284 (MaKr3d version)
73
+// 67 = Azteeg X3
74
+// 68 = Azteeg X3 Pro
75
+// 7  = Ultimaker
76
+// 71 = Ultimaker (Older electronics. Pre 1.5.4. This is rare)
77
+// 72 = Ultimainboard 2.x (Uses TEMP_SENSOR 20)
78
+// 77 = 3Drag Controller
79
+// 8  = Teensylu
80
+// 80 = Rumba
81
+// 81 = Printrboard (AT90USB1286)
82
+// 82 = Brainwave (AT90USB646)
83
+// 83 = SAV Mk-I (AT90USB1286)
84
+// 84 = Teensy++2.0 (AT90USB1286) // CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84  make
85
+// 9  = Gen3+
86
+// 70 = Megatronics
87
+// 701= Megatronics v2.0
88
+// 702= Minitronics v1.0
89
+// 90 = Alpha OMCA board
90
+// 91 = Final OMCA board
91
+// 301= Rambo
92
+// 21 = Elefu Ra Board (v3)
93
+// 88 = 5DPrint D8 Driver Board
94
+
95
+#ifndef MOTHERBOARD
96
+#define MOTHERBOARD 33
97
+#endif
98
+
99
+// Define this to set a custom name for your generic Mendel,
100
+// #define CUSTOM_MENDEL_NAME "This Mendel"
101
+
102
+// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
103
+// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
104
+// #define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
105
+
106
+// This defines the number of extruders
107
+#define EXTRUDERS 1
108
+
109
+//// The following define selects which power supply you have. Please choose the one that matches your setup
110
+// 1 = ATX
111
+// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
112
+
113
+#define POWER_SUPPLY 1
114
+
115
+// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
116
+// #define PS_DEFAULT_OFF
117
+
118
+//===========================================================================
119
+//=============================Thermal Settings  ============================
120
+//===========================================================================
121
+//
122
+//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
123
+//
124
+//// Temperature sensor settings:
125
+// -2 is thermocouple with MAX6675 (only for sensor 0)
126
+// -1 is thermocouple with AD595
127
+// 0 is not used
128
+// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
129
+// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
130
+// 3 is Mendel-parts thermistor (4.7k pullup)
131
+// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
132
+// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
133
+// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
134
+// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
135
+// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
136
+// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
137
+// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
138
+// 10 is 100k RS thermistor 198-961 (4.7k pullup)
139
+// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
140
+// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
141
+// 20 is the PT100 circuit found in the Ultimainboard V2.x
142
+// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
143
+//
144
+//    1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
145
+//                          (but gives greater accuracy and more stable PID)
146
+// 51 is 100k thermistor - EPCOS (1k pullup)
147
+// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
148
+// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
149
+//
150
+// 1047 is Pt1000 with 4k7 pullup
151
+// 1010 is Pt1000 with 1k pullup (non standard)
152
+// 147 is Pt100 with 4k7 pullup
153
+// 110 is Pt100 with 1k pullup (non standard)
154
+
155
+#define TEMP_SENSOR_0 1
156
+#define TEMP_SENSOR_1 0
157
+#define TEMP_SENSOR_2 0
158
+#define TEMP_SENSOR_BED 1
159
+
160
+// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
161
+//#define TEMP_SENSOR_1_AS_REDUNDANT
162
+#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
163
+
164
+// Actual temperature must be close to target for this long before M109 returns success
165
+#define TEMP_RESIDENCY_TIME 10  // (seconds)
166
+#define TEMP_HYSTERESIS 3       // (degC) range of +/- temperatures considered "close" to the target one
167
+#define TEMP_WINDOW     1       // (degC) Window around target to start the residency timer x degC early.
168
+
169
+// The minimal temperature defines the temperature below which the heater will not be enabled It is used
170
+// to check that the wiring to the thermistor is not broken.
171
+// Otherwise this would lead to the heater being powered on all the time.
172
+#define HEATER_0_MINTEMP 5
173
+#define HEATER_1_MINTEMP 5
174
+#define HEATER_2_MINTEMP 5
175
+#define BED_MINTEMP 5
176
+
177
+// When temperature exceeds max temp, your heater will be switched off.
178
+// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
179
+// You should use MINTEMP for thermistor short/failure protection.
180
+#define HEATER_0_MAXTEMP 275
181
+#define HEATER_1_MAXTEMP 275
182
+#define HEATER_2_MAXTEMP 275
183
+#define BED_MAXTEMP 150
184
+
185
+// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
186
+// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
187
+// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
188
+//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
189
+
190
+// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
191
+//#define EXTRUDER_WATTS (12.0*12.0/6.7) //  P=I^2/R
192
+//#define BED_WATTS (12.0*12.0/1.1)      // P=I^2/R
193
+
194
+// PID settings:
195
+// Comment the following line to disable PID and enable bang-bang.
196
+#define PIDTEMP
197
+#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
198
+#define PID_MAX 255 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
199
+#ifdef PIDTEMP
200
+  //#define PID_DEBUG // Sends debug data to the serial port.
201
+  //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
202
+  #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
203
+                                  // is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
204
+  #define PID_INTEGRAL_DRIVE_MAX 255  //limit for the integral term
205
+  #define K1 0.95 //smoothing factor within the PID
206
+  #define PID_dT ((OVERSAMPLENR * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
207
+
208
+// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
209
+// Ultimaker
210
+    #define  DEFAULT_Kp 22.2
211
+    #define  DEFAULT_Ki 1.08
212
+    #define  DEFAULT_Kd 114
213
+
214
+// MakerGear
215
+//    #define  DEFAULT_Kp 7.0
216
+//    #define  DEFAULT_Ki 0.1
217
+//    #define  DEFAULT_Kd 12
218
+
219
+// Mendel Parts V9 on 12V
220
+//    #define  DEFAULT_Kp 63.0
221
+//    #define  DEFAULT_Ki 2.25
222
+//    #define  DEFAULT_Kd 440
223
+#endif // PIDTEMP
224
+
225
+// Bed Temperature Control
226
+// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
227
+//
228
+// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
229
+// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
230
+// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
231
+// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
232
+// If your configuration is significantly different than this and you don't understand the issues involved, you probably
233
+// shouldn't use bed PID until someone else verifies your hardware works.
234
+// If this is enabled, find your own PID constants below.
235
+//#define PIDTEMPBED
236
+//
237
+//#define BED_LIMIT_SWITCHING
238
+
239
+// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
240
+// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
241
+// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
242
+// so you shouldn't use it unless you are OK with PWM on your bed.  (see the comment on enabling PIDTEMPBED)
243
+#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
244
+
245
+#ifdef PIDTEMPBED
246
+//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
247
+//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
248
+    #define  DEFAULT_bedKp 10.00
249
+    #define  DEFAULT_bedKi .023
250
+    #define  DEFAULT_bedKd 305.4
251
+
252
+//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
253
+//from pidautotune
254
+//    #define  DEFAULT_bedKp 97.1
255
+//    #define  DEFAULT_bedKi 1.41
256
+//    #define  DEFAULT_bedKd 1675.16
257
+
258
+// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
259
+#endif // PIDTEMPBED
260
+
261
+
262
+
263
+//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
264
+//can be software-disabled for whatever purposes by
265
+#define PREVENT_DANGEROUS_EXTRUDE
266
+//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
267
+#define PREVENT_LENGTHY_EXTRUDE
268
+
269
+#define EXTRUDE_MINTEMP 170
270
+#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
271
+
272
+//===========================================================================
273
+//=============================Mechanical Settings===========================
274
+//===========================================================================
275
+
276
+// Uncomment the following line to enable CoreXY kinematics
277
+// #define COREXY
278
+
279
+// coarse Endstop Settings
280
+//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
281
+
282
+#ifndef ENDSTOPPULLUPS
283
+  // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
284
+  // #define ENDSTOPPULLUP_XMAX
285
+  // #define ENDSTOPPULLUP_YMAX
286
+   #define ENDSTOPPULLUP_ZMAX  // open pin, inverted
287
+   #define ENDSTOPPULLUP_XMIN  // open pin, inverted
288
+   #define ENDSTOPPULLUP_YMIN  // open pin, inverted
289
+  // #define ENDSTOPPULLUP_ZMIN
290
+#endif
291
+
292
+#ifdef ENDSTOPPULLUPS
293
+  #define ENDSTOPPULLUP_XMAX
294
+  #define ENDSTOPPULLUP_YMAX
295
+  #define ENDSTOPPULLUP_ZMAX
296
+  #define ENDSTOPPULLUP_XMIN
297
+  #define ENDSTOPPULLUP_YMIN
298
+  #define ENDSTOPPULLUP_ZMIN
299
+#endif
300
+
301
+// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
302
+const bool X_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
303
+const bool Y_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
304
+const bool Z_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
305
+const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
306
+const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
307
+const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
308
+//#define DISABLE_MAX_ENDSTOPS
309
+//#define DISABLE_MIN_ENDSTOPS
310
+
311
+// Disable max endstops for compatibility with endstop checking routine
312
+#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
313
+  #define DISABLE_MAX_ENDSTOPS
314
+#endif
315
+
316
+// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
317
+#define X_ENABLE_ON 0
318
+#define Y_ENABLE_ON 0
319
+#define Z_ENABLE_ON 0
320
+#define E_ENABLE_ON 0 // For all extruders
321
+
322
+// Disables axis when it's not being used.
323
+#define DISABLE_X false
324
+#define DISABLE_Y false
325
+#define DISABLE_Z false
326
+#define DISABLE_E false // For all extruders
327
+#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
328
+
329
+#define INVERT_X_DIR false    // for Mendel set to false, for Orca set to true
330
+#define INVERT_Y_DIR false    // for Mendel set to true, for Orca set to false
331
+#define INVERT_Z_DIR true     // for Mendel set to false, for Orca set to true
332
+#define INVERT_E0_DIR true   // for direct drive extruder v9 set to true, for geared extruder set to false
333
+#define INVERT_E1_DIR false    // for direct drive extruder v9 set to true, for geared extruder set to false
334
+#define INVERT_E2_DIR false   // for direct drive extruder v9 set to true, for geared extruder set to false
335
+
336
+// ENDSTOP SETTINGS:
337
+// Sets direction of endstop	s when homing; 1=MAX, -1=MIN
338
+#define X_HOME_DIR 1
339
+#define Y_HOME_DIR 1
340
+#define Z_HOME_DIR -1
341
+
342
+#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
343
+#define max_software_endstops true  // If true, axis won't move to coordinates greater than the defined lengths below.
344
+
345
+// Travel limits after homing
346
+#define X_MAX_POS 200
347
+#define X_MIN_POS 0
348
+#define Y_MAX_POS 200
349
+#define Y_MIN_POS 0
350
+#define Z_MAX_POS 225
351
+#define Z_MIN_POS MANUAL_Z_HOME_POS
352
+
353
+#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
354
+#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
355
+#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
356
+//============================= Bed Auto Leveling ===========================
357
+
358
+//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
359
+
360
+#ifdef ENABLE_AUTO_BED_LEVELING
361
+
362
+// There are 2 different ways to pick the X and Y locations to probe:
363
+
364
+//  - "grid" mode
365
+//    Probe every point in a rectangular grid
366
+//    You must specify the rectangle, and the density of sample points
367
+//    This mode is preferred because there are more measurements.
368
+//    It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
369
+
370
+//  - "3-point" mode
371
+//    Probe 3 arbitrary points on the bed (that aren't colinear)
372
+//    You must specify the X & Y coordinates of all 3 points
373
+
374
+  #define AUTO_BED_LEVELING_GRID
375
+  // with AUTO_BED_LEVELING_GRID, the bed is sampled in a
376
+  // AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
377
+  // and least squares solution is calculated
378
+  // Note: this feature occupies 10'206 byte
379
+  #ifdef AUTO_BED_LEVELING_GRID
380
+
381
+    // set the rectangle in which to probe
382
+    #define LEFT_PROBE_BED_POSITION 15
383
+    #define RIGHT_PROBE_BED_POSITION 170
384
+    #define BACK_PROBE_BED_POSITION 180
385
+    #define FRONT_PROBE_BED_POSITION 20
386
+
387
+     // set the number of grid points per dimension
388
+     // I wouldn't see a reason to go above 3 (=9 probing points on the bed)
389
+    #define AUTO_BED_LEVELING_GRID_POINTS 2
390
+
391
+
392
+  #else  // not AUTO_BED_LEVELING_GRID
393
+    // with no grid, just probe 3 arbitrary points.  A simple cross-product
394
+    // is used to esimate the plane of the print bed
395
+
396
+      #define ABL_PROBE_PT_1_X 15
397
+      #define ABL_PROBE_PT_1_Y 180
398
+      #define ABL_PROBE_PT_2_X 15
399
+      #define ABL_PROBE_PT_2_Y 20
400
+      #define ABL_PROBE_PT_3_X 170
401
+      #define ABL_PROBE_PT_3_Y 20
402
+
403
+  #endif // AUTO_BED_LEVELING_GRID
404
+
405
+
406
+  // these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
407
+  #define X_PROBE_OFFSET_FROM_EXTRUDER -25
408
+  #define Y_PROBE_OFFSET_FROM_EXTRUDER -29
409
+  #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
410
+
411
+  //#define Z_RAISE_BEFORE_HOMING 4       // (in mm) Raise Z before homing (G28) for Probe Clearance.
412
+                                        // Be sure you have this distance over your Z_MAX_POS in case
413
+
414
+  #define XY_TRAVEL_SPEED 8000         // X and Y axis travel speed between probes, in mm/min
415
+
416
+  #define Z_RAISE_BEFORE_PROBING 15    //How much the extruder will be raised before traveling to the first probing point.
417
+  #define Z_RAISE_BETWEEN_PROBINGS 5  //How much the extruder will be raised when traveling from between next probing points
418
+
419
+
420
+  //If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk
421
+  //The value is the delay to turn the servo off after powered on - depends on the servo speed; 300ms is good value, but you can try lower it.
422
+  // You MUST HAVE the SERVO_ENDSTOPS defined to use here a value higher than zero otherwise your code will not compile.
423
+
424
+//  #define PROBE_SERVO_DEACTIVATION_DELAY 300
425
+
426
+
427
+//If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing,
428
+//it is highly recommended you let this Z_SAFE_HOMING enabled!!!
429
+
430
+ // #define Z_SAFE_HOMING   // This feature is meant to avoid Z homing with probe outside the bed area.
431
+                          // When defined, it will:
432
+                          // - Allow Z homing only after X and Y homing AND stepper drivers still enabled
433
+                          // - If stepper drivers timeout, it will need X and Y homing again before Z homing
434
+                          // - Position the probe in a defined XY point before Z Homing when homing all axis (G28)
435
+                          // - Block Z homing only when the probe is outside bed area.
436
+
437
+  #ifdef Z_SAFE_HOMING
438
+
439
+    #define Z_SAFE_HOMING_X_POINT (X_MAX_LENGTH/2)    // X point for Z homing when homing all axis (G28)
440
+    #define Z_SAFE_HOMING_Y_POINT (Y_MAX_LENGTH/2)    // Y point for Z homing when homing all axis (G28)
441
+
442
+  #endif
443
+
444
+#endif // ENABLE_AUTO_BED_LEVELING
445
+
446
+
447
+// The position of the homing switches
448
+#define MANUAL_HOME_POSITIONS  // If defined, MANUAL_*_HOME_POS below will be used
449
+//#define BED_CENTER_AT_0_0  // If defined, the center of the bed is at (X=0, Y=0)
450
+
451
+//Manual homing switch locations:
452
+// For deltabots this means top and center of the Cartesian print volume.
453
+// For SCARA: Offset between HomingPosition and Bed X=0 / Y=0
454
+#define MANUAL_X_HOME_POS -20
455
+#define MANUAL_Y_HOME_POS -48
456
+#define MANUAL_Z_HOME_POS 0.1  // Distance between nozzle and print surface after homing.
457
+
458
+
459
+//// MOVEMENT SETTINGS
460
+#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
461
+#define HOMING_FEEDRATE {40*60, 40*60, 10*60, 0}  // set the homing speeds (mm/min)
462
+
463
+// default settings
464
+
465
+//#define DEFAULT_AXIS_STEPS_PER_UNIT   {85.6,85.6,200/1.25,970}  // default steps per unit for Ultimaker
466
+#define DEFAULT_AXIS_STEPS_PER_UNIT   {109,109,200/1.25,970}  // default steps per unit for Ultimaker
467
+#define DEFAULT_MAX_FEEDRATE          {200, 200, 30, 45}    // (mm/sec)
468
+#define DEFAULT_MAX_ACCELERATION      {300,300,30,1500}    // 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.
469
+
470
+#define DEFAULT_ACCELERATION          300    // X, Y, Z and E max acceleration in mm/s^2 for printing moves
471
+#define DEFAULT_RETRACT_ACCELERATION  3000   // X, Y, Z and E max acceleration in mm/s^2 for retracts
472
+
473
+// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
474
+// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
475
+// For the other hotends it is their distance from the extruder 0 hotend.
476
+// #define EXTRUDER_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
477
+// #define EXTRUDER_OFFSET_Y {0.0, 5.00}  // (in mm) for each extruder, offset of the hotend on the Y axis
478
+
479
+// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
480
+#define DEFAULT_XYJERK                10.0    // (mm/sec)
481
+#define DEFAULT_ZJERK                 10.0     // (mm/sec)
482
+#define DEFAULT_EJERK                 5.0    // (mm/sec)
483
+
484
+//===========================================================================
485
+//=============================Additional Features===========================
486
+//===========================================================================
487
+
488
+// Custom M code points
489
+//#define CUSTOM_M_CODES
490
+#ifdef CUSTOM_M_CODES
491
+  #define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
492
+  #define Z_PROBE_OFFSET_RANGE_MIN -15
493
+  #define Z_PROBE_OFFSET_RANGE_MAX -5
494
+#endif
495
+
496
+
497
+// EEPROM
498
+// The microcontroller can store settings in the EEPROM, e.g. max velocity...
499
+// M500 - stores parameters in EEPROM
500
+// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
501
+// M502 - reverts to the default "factory settings".  You still need to store them in EEPROM afterwards if you want to.
502
+//define this to enable EEPROM support
503
+#define EEPROM_SETTINGS
504
+//to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
505
+// please keep turned on if you can.
506
+#define EEPROM_CHITCHAT
507
+
508
+// Preheat Constants
509
+#define PLA_PREHEAT_HOTEND_TEMP 180
510
+#define PLA_PREHEAT_HPB_TEMP 70
511
+#define PLA_PREHEAT_FAN_SPEED 255   // Insert Value between 0 and 255
512
+
513
+#define ABS_PREHEAT_HOTEND_TEMP 240
514
+#define ABS_PREHEAT_HPB_TEMP 100
515
+#define ABS_PREHEAT_FAN_SPEED 255   // Insert Value between 0 and 255
516
+
517
+//LCD and SD support
518
+//#define ULTRA_LCD  //general LCD support, also 16x2
519
+//#define DOGLCD  // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
520
+//#define SDSUPPORT // Enable SD Card Support in Hardware Console
521
+//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
522
+//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
523
+//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
524
+//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
525
+//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
526
+//#define ULTIPANEL  //the UltiPanel as on Thingiverse
527
+//#define LCD_FEEDBACK_FREQUENCY_HZ 1000	// this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
528
+//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
529
+
530
+// The MaKr3d Makr-Panel with graphic controller and SD support
531
+// http://reprap.org/wiki/MaKr3d_MaKrPanel
532
+//#define MAKRPANEL
533
+
534
+// The RepRapDiscount Smart Controller (white PCB)
535
+// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
536
+//#define REPRAP_DISCOUNT_SMART_CONTROLLER
537
+
538
+// The GADGETS3D G3D LCD/SD Controller (blue PCB)
539
+// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
540
+//#define G3D_PANEL
541
+
542
+// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
543
+// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
544
+//
545
+// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
546
+//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
547
+
548
+// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
549
+// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
550
+//#define REPRAPWORLD_KEYPAD
551
+//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click
552
+
553
+// The Elefu RA Board Control Panel
554
+// http://www.elefu.com/index.php?route=product/product&product_id=53
555
+// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARUDINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
556
+//#define RA_CONTROL_PANEL
557
+
558
+//automatic expansion
559
+#if defined (MAKRPANEL)
560
+ #define DOGLCD
561
+ #define SDSUPPORT
562
+ #define ULTIPANEL
563
+ #define NEWPANEL
564
+ #define DEFAULT_LCD_CONTRAST 17
565
+#endif
566
+
567
+#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
568
+ #define DOGLCD
569
+ #define U8GLIB_ST7920
570
+ #define REPRAP_DISCOUNT_SMART_CONTROLLER
571
+#endif
572
+
573
+#if defined(ULTIMAKERCONTROLLER) || defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL)
574
+ #define ULTIPANEL
575
+ #define NEWPANEL
576
+#endif
577
+
578
+#if defined(REPRAPWORLD_KEYPAD)
579
+  #define NEWPANEL
580
+  #define ULTIPANEL
581
+#endif
582
+#if defined(RA_CONTROL_PANEL)
583
+ #define ULTIPANEL
584
+ #define NEWPANEL
585
+ #define LCD_I2C_TYPE_PCA8574
586
+ #define LCD_I2C_ADDRESS 0x27   // I2C Address of the port expander
587
+#endif
588
+
589
+//I2C PANELS
590
+
591
+//#define LCD_I2C_SAINSMART_YWROBOT
592
+#ifdef LCD_I2C_SAINSMART_YWROBOT
593
+  // This uses the LiquidCrystal_I2C library ( https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home )
594
+  // Make sure it is placed in the Arduino libraries directory.
595
+  #define LCD_I2C_TYPE_PCF8575
596
+  #define LCD_I2C_ADDRESS 0x27   // I2C Address of the port expander
597
+  #define NEWPANEL
598
+  #define ULTIPANEL
599
+#endif
600
+
601
+// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
602
+//#define LCD_I2C_PANELOLU2
603
+#ifdef LCD_I2C_PANELOLU2
604
+  // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
605
+  // Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
606
+  // (v1.2.3 no longer requires you to define PANELOLU in the LiquidTWI2.h library header file)
607
+  // Note: The PANELOLU2 encoder click input can either be directly connected to a pin
608
+  //       (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1).
609
+  #define LCD_I2C_TYPE_MCP23017
610
+  #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
611
+  #define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
612
+  #define NEWPANEL
613
+  #define ULTIPANEL
614
+
615
+  #ifndef ENCODER_PULSES_PER_STEP
616
+	#define ENCODER_PULSES_PER_STEP 4
617
+  #endif
618
+
619
+  #ifndef ENCODER_STEPS_PER_MENU_ITEM
620
+	#define ENCODER_STEPS_PER_MENU_ITEM 1
621
+  #endif
622
+
623
+
624
+  #ifdef LCD_USE_I2C_BUZZER
625
+	#define LCD_FEEDBACK_FREQUENCY_HZ 1000
626
+	#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
627
+  #endif
628
+
629
+#endif
630
+
631
+// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
632
+//#define LCD_I2C_VIKI
633
+#ifdef LCD_I2C_VIKI
634
+  // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
635
+  // Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
636
+  // Note: The pause/stop/resume LCD button pin should be connected to the Arduino
637
+  //       BTN_ENC pin (or set BTN_ENC to -1 if not used)
638
+  #define LCD_I2C_TYPE_MCP23017
639
+  #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
640
+  #define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
641
+  #define NEWPANEL
642
+  #define ULTIPANEL
643
+#endif
644
+
645
+// Shift register panels
646
+// ---------------------
647
+// 2 wire Non-latching LCD SR from:
648
+// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
649
+//#define SR_LCD
650
+#ifdef SR_LCD
651
+   #define SR_LCD_2W_NL    // Non latching 2 wire shift register
652
+   //#define NEWPANEL
653
+#endif
654
+
655
+
656
+#ifdef ULTIPANEL
657
+//  #define NEWPANEL  //enable this if you have a click-encoder panel
658
+  #define SDSUPPORT
659
+  #define ULTRA_LCD
660
+  #ifdef DOGLCD // Change number of lines to match the DOG graphic display
661
+    #define LCD_WIDTH 20
662
+    #define LCD_HEIGHT 5
663
+  #else
664
+    #define LCD_WIDTH 20
665
+    #define LCD_HEIGHT 4
666
+  #endif
667
+#else //no panel but just LCD
668
+  #ifdef ULTRA_LCD
669
+  #ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
670
+    #define LCD_WIDTH 20
671
+    #define LCD_HEIGHT 5
672
+  #else
673
+    #define LCD_WIDTH 16
674
+    #define LCD_HEIGHT 2
675
+  #endif
676
+  #endif
677
+#endif
678
+
679
+// default LCD contrast for dogm-like LCD displays
680
+#ifdef DOGLCD
681
+# ifndef DEFAULT_LCD_CONTRAST
682
+#  define DEFAULT_LCD_CONTRAST 32
683
+# endif
684
+#endif
685
+
686
+// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
687
+//#define FAST_PWM_FAN
688
+
689
+// Temperature status LEDs that display the hotend and bet temperature.
690
+// If all hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on.
691
+// Otherwise the RED led is on. There is 1C hysteresis.
692
+//#define TEMP_STAT_LEDS
693
+
694
+// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
695
+// which is not ass annoying as with the hardware PWM. On the other hand, if this frequency
696
+// is too low, you should also increment SOFT_PWM_SCALE.
697
+//#define FAN_SOFT_PWM
698
+
699
+// Incrementing this by 1 will double the software PWM frequency,
700
+// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
701
+// However, control resolution will be halved for each increment;
702
+// at zero value, there are 128 effective control positions.
703
+#define SOFT_PWM_SCALE 0
704
+
705
+// M240  Triggers a camera by emulating a Canon RC-1 Remote
706
+// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
707
+// #define PHOTOGRAPH_PIN     23
708
+
709
+// SF send wrong arc g-codes when using Arc Point as fillet procedure
710
+//#define SF_ARC_FIX
711
+
712
+// Support for the BariCUDA Paste Extruder.
713
+//#define BARICUDA
714
+
715
+//define BlinkM/CyzRgb Support
716
+//#define BLINKM
717
+
718
+/*********************************************************************\
719
+* R/C SERVO support
720
+* Sponsored by TrinityLabs, Reworked by codexmas
721
+**********************************************************************/
722
+
723
+// Number of servos
724
+//
725
+// If you select a configuration below, this will receive a default value and does not need to be set manually
726
+// set it manually if you have more servos than extruders and wish to manually control some
727
+// leaving it undefined or defining as 0 will disable the servo subsystem
728
+// If unsure, leave commented / disabled
729
+//
730
+//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
731
+
732
+// Servo Endstops
733
+//
734
+// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
735
+// Use M206 command to correct for switch height offset to actual nozzle height. Store that setting with M500.
736
+//
737
+//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
738
+//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles
739
+
740
+#include "Configuration_adv.h"
741
+#include "thermistortables.h"
742
+
743
+#endif //__CONFIGURATION_H

+ 507
- 0
Marlin/example_configurations/SCARA/Configuration_adv.h 查看文件

@@ -0,0 +1,507 @@
1
+#ifndef CONFIGURATION_ADV_H
2
+#define CONFIGURATION_ADV_H
3
+
4
+//===========================================================================
5
+//=============================Thermal Settings  ============================
6
+//===========================================================================
7
+
8
+#ifdef BED_LIMIT_SWITCHING
9
+  #define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
10
+#endif
11
+#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
12
+
13
+//// Heating sanity check:
14
+// This waits for the watch period in milliseconds whenever an M104 or M109 increases the target temperature
15
+// If the temperature has not increased at the end of that period, the target temperature is set to zero.
16
+// It can be reset with another M104/M109. This check is also only triggered if the target temperature and the current temperature
17
+//  differ by at least 2x WATCH_TEMP_INCREASE
18
+//#define WATCH_TEMP_PERIOD 40000 //40 seconds
19
+//#define WATCH_TEMP_INCREASE 10  //Heat up at least 10 degree in 20 seconds
20
+
21
+#ifdef PIDTEMP
22
+  // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
23
+  // if Kc is chosen well, the additional required power due to increased melting should be compensated.
24
+  #define PID_ADD_EXTRUSION_RATE
25
+  #ifdef PID_ADD_EXTRUSION_RATE
26
+    #define  DEFAULT_Kc (1) //heating power=Kc*(e_speed)
27
+  #endif
28
+#endif
29
+
30
+
31
+//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
32
+//The maximum buffered steps/sec of the extruder motor are called "se".
33
+//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
34
+// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
35
+// you exit the value by any M109 without F*
36
+// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
37
+// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
38
+#define AUTOTEMP
39
+#ifdef AUTOTEMP
40
+  #define AUTOTEMP_OLDWEIGHT 0.98
41
+#endif
42
+
43
+//Show Temperature ADC value
44
+//The M105 command return, besides traditional information, the ADC value read from temperature sensors.
45
+//#define SHOW_TEMP_ADC_VALUES
46
+
47
+//  extruder run-out prevention.
48
+//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
49
+//#define EXTRUDER_RUNOUT_PREVENT
50
+#define EXTRUDER_RUNOUT_MINTEMP 190
51
+#define EXTRUDER_RUNOUT_SECONDS 30.
52
+#define EXTRUDER_RUNOUT_ESTEPS 14. //mm filament
53
+#define EXTRUDER_RUNOUT_SPEED 1500.  //extrusion speed
54
+#define EXTRUDER_RUNOUT_EXTRUDE 100
55
+
56
+//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
57
+//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
58
+#define TEMP_SENSOR_AD595_OFFSET 0.0
59
+#define TEMP_SENSOR_AD595_GAIN   1.0
60
+
61
+//This is for controlling a fan to cool down the stepper drivers
62
+//it will turn on when any driver is enabled
63
+//and turn off after the set amount of seconds from last driver being disabled again
64
+#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable)
65
+#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run
66
+#define CONTROLLERFAN_SPEED 255  // == full speed
67
+
68
+// When first starting the main fan, run it at full speed for the
69
+// given number of milliseconds.  This gets the fan spinning reliably
70
+// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
71
+//#define FAN_KICKSTART_TIME 100
72
+
73
+// Extruder cooling fans
74
+// Configure fan pin outputs to automatically turn on/off when the associated
75
+// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
76
+// Multiple extruders can be assigned to the same pin in which case
77
+// the fan will turn on when any selected extruder is above the threshold.
78
+#define EXTRUDER_0_AUTO_FAN_PIN   -1
79
+#define EXTRUDER_1_AUTO_FAN_PIN   -1
80
+#define EXTRUDER_2_AUTO_FAN_PIN   -1
81
+#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
82
+#define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
83
+
84
+
85
+//===========================================================================
86
+//=============================Mechanical Settings===========================
87
+//===========================================================================
88
+
89
+#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
90
+
91
+
92
+//// AUTOSET LOCATIONS OF LIMIT SWITCHES
93
+//// Added by ZetaPhoenix 09-15-2012
94
+#ifdef MANUAL_HOME_POSITIONS  // Use manual limit switch locations
95
+  #define X_HOME_POS MANUAL_X_HOME_POS
96
+  #define Y_HOME_POS MANUAL_Y_HOME_POS
97
+  #define Z_HOME_POS MANUAL_Z_HOME_POS
98
+#else //Set min/max homing switch positions based upon homing direction and min/max travel limits
99
+  //X axis
100
+  #if X_HOME_DIR == -1
101
+    #ifdef BED_CENTER_AT_0_0
102
+      #define X_HOME_POS X_MAX_LENGTH * -0.5
103
+    #else
104
+      #define X_HOME_POS X_MIN_POS
105
+    #endif //BED_CENTER_AT_0_0
106
+  #else
107
+    #ifdef BED_CENTER_AT_0_0
108
+      #define X_HOME_POS X_MAX_LENGTH * 0.5
109
+    #else
110
+      #define X_HOME_POS X_MAX_POS
111
+    #endif //BED_CENTER_AT_0_0
112
+  #endif //X_HOME_DIR == -1
113
+
114
+  //Y axis
115
+  #if Y_HOME_DIR == -1
116
+    #ifdef BED_CENTER_AT_0_0
117
+      #define Y_HOME_POS Y_MAX_LENGTH * -0.5
118
+    #else
119
+      #define Y_HOME_POS Y_MIN_POS
120
+    #endif //BED_CENTER_AT_0_0
121
+  #else
122
+    #ifdef BED_CENTER_AT_0_0
123
+      #define Y_HOME_POS Y_MAX_LENGTH * 0.5
124
+    #else
125
+      #define Y_HOME_POS Y_MAX_POS
126
+    #endif //BED_CENTER_AT_0_0
127
+  #endif //Y_HOME_DIR == -1
128
+
129
+  // Z axis
130
+  #if Z_HOME_DIR == -1 //BED_CENTER_AT_0_0 not used
131
+    #define Z_HOME_POS Z_MIN_POS
132
+  #else
133
+    #define Z_HOME_POS Z_MAX_POS
134
+  #endif //Z_HOME_DIR == -1
135
+#endif //End auto min/max positions
136
+//END AUTOSET LOCATIONS OF LIMIT SWITCHES -ZP
137
+
138
+
139
+//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
140
+
141
+// A single Z stepper driver is usually used to drive 2 stepper motors.
142
+// Uncomment this define to utilize a separate stepper driver for each Z axis motor.
143
+// Only a few motherboards support this, like RAMPS, which have dual extruder support (the 2nd, often unused, extruder driver is used
144
+// to control the 2nd Z axis stepper motor). The pins are currently only defined for a RAMPS motherboards.
145
+// On a RAMPS (or other 5 driver) motherboard, using this feature will limit you to using 1 extruder.
146
+//#define Z_DUAL_STEPPER_DRIVERS
147
+
148
+#ifdef Z_DUAL_STEPPER_DRIVERS
149
+  #undef EXTRUDERS
150
+  #define EXTRUDERS 1
151
+#endif
152
+
153
+// Same again but for Y Axis.
154
+//#define Y_DUAL_STEPPER_DRIVERS
155
+
156
+// Define if the two Y drives need to rotate in opposite directions
157
+#define INVERT_Y2_VS_Y_DIR true
158
+
159
+#ifdef Y_DUAL_STEPPER_DRIVERS
160
+  #undef EXTRUDERS
161
+  #define EXTRUDERS 1
162
+#endif
163
+
164
+#if defined (Z_DUAL_STEPPER_DRIVERS) && defined (Y_DUAL_STEPPER_DRIVERS)
165
+  #error "You cannot have dual drivers for both Y and Z"
166
+#endif
167
+
168
+// Enable this for dual x-carriage printers.
169
+// A dual x-carriage design has the advantage that the inactive extruder can be parked which
170
+// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
171
+// allowing faster printing speeds.
172
+//#define DUAL_X_CARRIAGE
173
+#ifdef DUAL_X_CARRIAGE
174
+// Configuration for second X-carriage
175
+// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
176
+// the second x-carriage always homes to the maximum endstop.
177
+#define X2_MIN_POS 80     // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
178
+#define X2_MAX_POS 353    // set maximum to the distance between toolheads when both heads are homed
179
+#define X2_HOME_DIR 1     // the second X-carriage always homes to the maximum endstop position
180
+#define X2_HOME_POS X2_MAX_POS // default home position is the maximum carriage position
181
+    // However: In this mode the EXTRUDER_OFFSET_X value for the second extruder provides a software
182
+    // override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops
183
+    // without modifying the firmware (through the "M218 T1 X???" command).
184
+    // Remember: you should set the second extruder x-offset to 0 in your slicer.
185
+
186
+// Pins for second x-carriage stepper driver (defined here to avoid further complicating pins.h)
187
+#define X2_ENABLE_PIN 29
188
+#define X2_STEP_PIN 25
189
+#define X2_DIR_PIN 23
190
+
191
+// There are a few selectable movement modes for dual x-carriages using M605 S<mode>
192
+//    Mode 0: Full control. The slicer has full control over both x-carriages and can achieve optimal travel results
193
+//                           as long as it supports dual x-carriages. (M605 S0)
194
+//    Mode 1: Auto-park mode. The firmware will automatically park and unpark the x-carriages on tool changes so
195
+//                           that additional slicer support is not required. (M605 S1)
196
+//    Mode 2: Duplication mode. The firmware will transparently make the second x-carriage and extruder copy all
197
+//                           actions of the first x-carriage. This allows the printer to print 2 arbitrary items at
198
+//                           once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
199
+
200
+// This is the default power-up mode which can be later using M605.
201
+#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
202
+
203
+// As the x-carriages are independent we can now account for any relative Z offset
204
+#define EXTRUDER1_Z_OFFSET 0.0           // z offset relative to extruder 0
205
+
206
+// Default settings in "Auto-park Mode"
207
+#define TOOLCHANGE_PARK_ZLIFT   0.2      // the distance to raise Z axis when parking an extruder
208
+#define TOOLCHANGE_UNPARK_ZLIFT 1        // the distance to raise Z axis when unparking an extruder
209
+
210
+// Default x offset in duplication mode (typically set to half print bed width)
211
+#define DEFAULT_DUPLICATION_X_OFFSET 100
212
+
213
+#endif //DUAL_X_CARRIAGE
214
+
215
+//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
216
+#define X_HOME_RETRACT_MM 3
217
+#define Y_HOME_RETRACT_MM 3
218
+#define Z_HOME_RETRACT_MM 3
219
+//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
220
+#ifdef SCARA
221
+	#define QUICK_HOME //SCARA needs Quickhome
222
+#endif
223
+
224
+#define AXIS_RELATIVE_MODES {false, false, false, false}
225
+
226
+#define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step)
227
+
228
+//By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step.
229
+#define INVERT_X_STEP_PIN false
230
+#define INVERT_Y_STEP_PIN false
231
+#define INVERT_Z_STEP_PIN false
232
+#define INVERT_E_STEP_PIN false
233
+
234
+//default stepper release if idle
235
+#define DEFAULT_STEPPER_DEACTIVE_TIME 240
236
+
237
+#define DEFAULT_MINIMUMFEEDRATE       0.0     // minimum feedrate
238
+#define DEFAULT_MINTRAVELFEEDRATE     0.0
239
+
240
+// Feedrates for manual moves along X, Y, Z, E from panel
241
+#ifdef ULTIPANEL
242
+#define MANUAL_FEEDRATE {50*60, 50*60, 10*60, 60}  // set the speeds for manual moves (mm/min)
243
+#endif
244
+
245
+//Comment to disable setting feedrate multiplier via encoder
246
+#ifdef ULTIPANEL
247
+    #define ULTIPANEL_FEEDMULTIPLY
248
+#endif
249
+
250
+// minimum time in microseconds that a movement needs to take if the buffer is emptied.
251
+#define DEFAULT_MINSEGMENTTIME        20000
252
+
253
+// If defined the movements slow down when the look ahead buffer is only half full
254
+//#define SLOWDOWN
255
+#ifdef SCARA
256
+ #undef SLOWDOWN
257
+#endif
258
+// Frequency limit
259
+// See nophead's blog for more info
260
+// Not working O
261
+//#define XY_FREQUENCY_LIMIT  15
262
+
263
+// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
264
+// of the buffer and all stops. This should not be much greater than zero and should only be changed
265
+// if unwanted behavior is observed on a user's machine when running at very slow speeds.
266
+#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
267
+
268
+// MS1 MS2 Stepper Driver Microstepping mode table
269
+#define MICROSTEP1 LOW,LOW
270
+#define MICROSTEP2 HIGH,LOW
271
+#define MICROSTEP4 LOW,HIGH
272
+#define MICROSTEP8 HIGH,HIGH
273
+#define MICROSTEP16 HIGH,HIGH
274
+
275
+// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
276
+#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
277
+
278
+// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
279
+#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
280
+
281
+// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
282
+//#define DIGIPOT_I2C
283
+// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
284
+#define DIGIPOT_I2C_NUM_CHANNELS 8
285
+// actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
286
+#define DIGIPOT_I2C_MOTOR_CURRENTS {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0}
287
+
288
+//===========================================================================
289
+//=============================Additional Features===========================
290
+//===========================================================================
291
+
292
+//#define CHDK 4        //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
293
+#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
294
+
295
+#define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
296
+#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
297
+
298
+#define SDCARD_RATHERRECENTFIRST  //reverse file order of sd card menu display. Its sorted practically after the file system block order.
299
+// if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
300
+// using:
301
+//#define MENU_ADDAUTOSTART
302
+
303
+// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
304
+//#define USE_WATCHDOG
305
+
306
+#ifdef USE_WATCHDOG
307
+// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
308
+// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
309
+//  However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
310
+//#define WATCHDOG_RESET_MANUAL
311
+#endif
312
+
313
+// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
314
+//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
315
+
316
+// Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
317
+// it can e.g. be used to change z-positions in the print startup phase in real-time
318
+// does not respect endstops!
319
+//#define BABYSTEPPING
320
+#ifdef BABYSTEPPING
321
+  #define BABYSTEP_XY  //not only z, but also XY in the menu. more clutter, more functions
322
+  #define BABYSTEP_INVERT_Z false  //true for inverse movements in Z
323
+  #define BABYSTEP_Z_MULTIPLICATOR 2 //faster z movements
324
+
325
+  #ifdef COREXY
326
+    #error BABYSTEPPING not implemented for COREXY yet.
327
+  #endif
328
+
329
+  #ifdef DELTA
330
+    #ifdef BABYSTEP_XY
331
+      #error BABYSTEPPING only implemented for Z axis on deltabots.
332
+    #endif
333
+  #endif
334
+  
335
+  #ifdef SCARA
336
+    #error BABYSTEPPING not implemented for SCARA yet.
337
+  #endif
338
+  
339
+#endif
340
+
341
+// extruder advance constant (s2/mm3)
342
+//
343
+// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTUDER_ADVANCE_K * cubic mm per second ^ 2
344
+//
345
+// Hooke's law says:		force = k * distance
346
+// Bernoulli's principle says:	v ^ 2 / 2 + g . h + pressure / density = constant
347
+// so: v ^ 2 is proportional to number of steps we advance the extruder
348
+//#define ADVANCE
349
+
350
+#ifdef ADVANCE
351
+  #define EXTRUDER_ADVANCE_K .0
352
+
353
+  #define D_FILAMENT 1.75
354
+  #define STEPS_MM_E 836
355
+  #define EXTRUTION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
356
+  #define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUTION_AREA)
357
+
358
+#endif // ADVANCE
359
+
360
+// Arc interpretation settings:
361
+#define MM_PER_ARC_SEGMENT 1
362
+#define N_ARC_CORRECTION 25
363
+
364
+const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
365
+
366
+// If you are using a RAMPS board or cheap E-bay purchased boards that do not detect when an SD card is inserted
367
+// You can get round this by connecting a push button or single throw switch to the pin defined as SDCARDCARDDETECT
368
+// in the pins.h file.  When using a push button pulling the pin to ground this will need inverted.  This setting should
369
+// be commented out otherwise
370
+#define SDCARDDETECTINVERTED
371
+
372
+#ifdef ULTIPANEL
373
+ #undef SDCARDDETECTINVERTED
374
+#endif
375
+
376
+// Power Signal Control Definitions
377
+// By default use ATX definition
378
+#ifndef POWER_SUPPLY
379
+  #define POWER_SUPPLY 1
380
+#endif
381
+// 1 = ATX
382
+#if (POWER_SUPPLY == 1)
383
+  #define PS_ON_AWAKE  LOW
384
+  #define PS_ON_ASLEEP HIGH
385
+#endif
386
+// 2 = X-Box 360 203W
387
+#if (POWER_SUPPLY == 2)
388
+  #define PS_ON_AWAKE  HIGH
389
+  #define PS_ON_ASLEEP LOW
390
+#endif
391
+
392
+// Control heater 0 and heater 1 in parallel.
393
+//#define HEATERS_PARALLEL
394
+
395
+//===========================================================================
396
+//=============================Buffers           ============================
397
+//===========================================================================
398
+
399
+// The number of linear motions that can be in the plan at any give time.
400
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
401
+#if defined SDSUPPORT
402
+  #define BLOCK_BUFFER_SIZE 16   // SD,LCD,Buttons take more memory, block buffer needs to be smaller
403
+#else
404
+  #define BLOCK_BUFFER_SIZE 16 // maximize block buffer
405
+#endif
406
+
407
+
408
+//The ASCII buffer for receiving from the serial:
409
+#define MAX_CMD_SIZE 96
410
+#define BUFSIZE 4
411
+
412
+
413
+// Firmware based and LCD controlled retract
414
+// M207 and M208 can be used to define parameters for the retraction.
415
+// The retraction can be called by the slicer using G10 and G11
416
+// until then, intended retractions can be detected by moves that only extrude and the direction.
417
+// the moves are than replaced by the firmware controlled ones.
418
+
419
+// #define FWRETRACT  //ONLY PARTIALLY TESTED
420
+#ifdef FWRETRACT
421
+  #define MIN_RETRACT 0.1                //minimum extruded mm to accept a automatic gcode retraction attempt
422
+  #define RETRACT_LENGTH 3               //default retract length (positive mm)
423
+  #define RETRACT_FEEDRATE 30            //default feedrate for retracting (mm/s)
424
+  #define RETRACT_ZLIFT 0                //default retract Z-lift
425
+  #define RETRACT_RECOVER_LENGTH 0       //default additional recover length (mm, added to retract length when recovering)
426
+  #define RETRACT_RECOVER_FEEDRATE 8     //default feedrate for recovering from retraction (mm/s)
427
+#endif
428
+
429
+//adds support for experimental filament exchange support M600; requires display
430
+#ifdef ULTIPANEL
431
+  #define FILAMENTCHANGEENABLE
432
+  #ifdef FILAMENTCHANGEENABLE
433
+    #define FILAMENTCHANGE_XPOS 3
434
+    #define FILAMENTCHANGE_YPOS 3
435
+    #define FILAMENTCHANGE_ZADD 10
436
+    #define FILAMENTCHANGE_FIRSTRETRACT -2
437
+    #define FILAMENTCHANGE_FINALRETRACT -100
438
+  #endif
439
+#endif
440
+
441
+#ifdef FILAMENTCHANGEENABLE
442
+  #ifdef EXTRUDER_RUNOUT_PREVENT
443
+    #error EXTRUDER_RUNOUT_PREVENT currently incompatible with FILAMENTCHANGE
444
+  #endif
445
+#endif
446
+
447
+//===========================================================================
448
+//=============================  Define Defines  ============================
449
+//===========================================================================
450
+#if EXTRUDERS > 1 && defined TEMP_SENSOR_1_AS_REDUNDANT
451
+  #error "You cannot use TEMP_SENSOR_1_AS_REDUNDANT if EXTRUDERS > 1"
452
+#endif
453
+
454
+#if EXTRUDERS > 1 && defined HEATERS_PARALLEL
455
+  #error "You cannot use HEATERS_PARALLEL if EXTRUDERS > 1"
456
+#endif
457
+
458
+#if TEMP_SENSOR_0 > 0
459
+  #define THERMISTORHEATER_0 TEMP_SENSOR_0
460
+  #define HEATER_0_USES_THERMISTOR
461
+#endif
462
+#if TEMP_SENSOR_1 > 0
463
+  #define THERMISTORHEATER_1 TEMP_SENSOR_1
464
+  #define HEATER_1_USES_THERMISTOR
465
+#endif
466
+#if TEMP_SENSOR_2 > 0
467
+  #define THERMISTORHEATER_2 TEMP_SENSOR_2
468
+  #define HEATER_2_USES_THERMISTOR
469
+#endif
470
+#if TEMP_SENSOR_BED > 0
471
+  #define THERMISTORBED TEMP_SENSOR_BED
472
+  #define BED_USES_THERMISTOR
473
+#endif
474
+#if TEMP_SENSOR_0 == -1
475
+  #define HEATER_0_USES_AD595
476
+#endif
477
+#if TEMP_SENSOR_1 == -1
478
+  #define HEATER_1_USES_AD595
479
+#endif
480
+#if TEMP_SENSOR_2 == -1
481
+  #define HEATER_2_USES_AD595
482
+#endif
483
+#if TEMP_SENSOR_BED == -1
484
+  #define BED_USES_AD595
485
+#endif
486
+#if TEMP_SENSOR_0 == -2
487
+  #define HEATER_0_USES_MAX6675
488
+#endif
489
+#if TEMP_SENSOR_0 == 0
490
+  #undef HEATER_0_MINTEMP
491
+  #undef HEATER_0_MAXTEMP
492
+#endif
493
+#if TEMP_SENSOR_1 == 0
494
+  #undef HEATER_1_MINTEMP
495
+  #undef HEATER_1_MAXTEMP
496
+#endif
497
+#if TEMP_SENSOR_2 == 0
498
+  #undef HEATER_2_MINTEMP
499
+  #undef HEATER_2_MAXTEMP
500
+#endif
501
+#if TEMP_SENSOR_BED == 0
502
+  #undef BED_MINTEMP
503
+  #undef BED_MAXTEMP
504
+#endif
505
+
506
+
507
+#endif //__CONFIGURATION_ADV_H

+ 0
- 75
Marlin/thermistortables.h 查看文件

@@ -1021,81 +1021,6 @@ const short temptable_1047[][2] PROGMEM = {
1021 1021
   PtLine(300,1000,4700)
1022 1022
 };
1023 1023
 #endif
1024
-#if (THERMISTORHEATER_0 == 70) || (THERMISTORHEATER_1 == 70) || (THERMISTORHEATER_2 == 70) || (THERMISTORBED == 70) // 500C thermistor for Pico hot end
1025
-const short temptable_70[][2] PROGMEM = {
1026
-  {  110.774119598719*OVERSAMPLENR ,  350 },
1027
-  {  118.214386957249*OVERSAMPLENR ,  345 },
1028
-  {  126.211418543166*OVERSAMPLENR ,  340 },
1029
-  {  134.789559066223*OVERSAMPLENR ,  335 },
1030
-  {  144.004513869701*OVERSAMPLENR ,  330 },
1031
-  {  153.884483790827*OVERSAMPLENR ,  325 },
1032
-  {  164.484880793637*OVERSAMPLENR ,  320 },
1033
-  {  175.848885102724*OVERSAMPLENR ,  315 },
1034
-  {  188.006799079015*OVERSAMPLENR ,  310 },
1035
-  {  201.008072969044*OVERSAMPLENR ,  305 },
1036
-  {  214.83716032276*OVERSAMPLENR ,  300 },
1037
-  {  229.784739779664*OVERSAMPLENR ,  295 },
1038
-  {  245.499466045473*OVERSAMPLENR ,  290 },
1039
-  {  262.2766342096*OVERSAMPLENR ,  285 },
1040
-  {  280.073883176433*OVERSAMPLENR ,  280 },
1041
-  {  298.952693467726*OVERSAMPLENR ,  275 },
1042
-  {  318.808251051674*OVERSAMPLENR ,  270 },
1043
-  {  337.490932563222*OVERSAMPLENR ,  265 },
1044
-  {  361.683649122745*OVERSAMPLENR ,  260 },
1045
-  {  384.717024083981*OVERSAMPLENR ,  255 },
1046
-  {  408.659301759076*OVERSAMPLENR ,  250 },
1047
-  {  433.471659455884*OVERSAMPLENR ,  245 },
1048
-  {  459.199039926034*OVERSAMPLENR ,  240 },
1049
-  {  485.566500982316*OVERSAMPLENR ,  235 },
1050
-  {  512.538918631075*OVERSAMPLENR ,  230 },
1051
-  {  539.980999544838*OVERSAMPLENR ,  225 },
1052
-  {  567.783095549935*OVERSAMPLENR ,  220 },
1053
-  {  595.698041673552*OVERSAMPLENR ,  215 },
1054
-  {  623.633922319597*OVERSAMPLENR ,  210 },
1055
-  {  651.356162750829*OVERSAMPLENR ,  205 },
1056
-  {  678.700901620956*OVERSAMPLENR ,  200 },
1057
-  {  705.528145361264*OVERSAMPLENR ,  195 },
1058
-  {  731.61267976339*OVERSAMPLENR ,  190 },
1059
-  {  756.786212184365*OVERSAMPLENR ,  185 },
1060
-  {  780.950223357761*OVERSAMPLENR ,  180 },
1061
-  {  804.012961595082*OVERSAMPLENR ,  175 },
1062
-  {  825.904975939166*OVERSAMPLENR ,  170 },
1063
-  {  846.403941639008*OVERSAMPLENR ,  165 },
1064
-  {  865.52326974895*OVERSAMPLENR ,  160 },
1065
-  {  883.246145367727*OVERSAMPLENR ,  155 },
1066
-  {  899.5821946515*OVERSAMPLENR ,  150 },
1067
-  {  914.544289228582*OVERSAMPLENR ,  145 },
1068
-  {  928.145628221761*OVERSAMPLENR ,  140 },
1069
-  {  940.422208546562*OVERSAMPLENR ,  135 },
1070
-  {  951.456922916497*OVERSAMPLENR ,  130 },
1071
-  {  961.303500633788*OVERSAMPLENR ,  125 },
1072
-  {  970.044756889055*OVERSAMPLENR ,  120 },
1073
-  {  977.761456230051*OVERSAMPLENR ,  115 },
1074
-  {  984.540978083453*OVERSAMPLENR ,  110 },
1075
-  {  990.440780765757*OVERSAMPLENR ,  105 },
1076
-  {  995.589621465301*OVERSAMPLENR ,  100 },
1077
-  {  1000.02514280144*OVERSAMPLENR ,  95 },
1078
-  {  1003.84429789876*OVERSAMPLENR ,  90 },
1079
-  {  1007.10199009318*OVERSAMPLENR ,  85 },
1080
-  {  1009.87151698323*OVERSAMPLENR ,  80 },
1081
-  {  1012.21633594237*OVERSAMPLENR ,  75 },
1082
-  {  1014.18959892949*OVERSAMPLENR ,  70 },
1083
-  {  1015.84079162998*OVERSAMPLENR ,  65 },
1084
-  {  1017.21555915335*OVERSAMPLENR ,  60 },
1085
-  {  1018.35284662863*OVERSAMPLENR ,  55 },
1086
-  {  1019.28926921888*OVERSAMPLENR ,  50 },
1087
-  {  1020.05398015669*OVERSAMPLENR ,  45 },
1088
-  {  1020.67737496272*OVERSAMPLENR ,  40 },
1089
-  {  1021.1802909627*OVERSAMPLENR ,  35 },
1090
-  {  1021.58459281248*OVERSAMPLENR ,  30 },
1091
-  {  1021.90701441192*OVERSAMPLENR ,  25 },
1092
-  {  1022.16215103698*OVERSAMPLENR ,  20 },
1093
-  {  1022.36275529549*OVERSAMPLENR ,  15 },
1094
-  {  1022.51930392497*OVERSAMPLENR ,  10 },
1095
-  {  1022.64051573734*OVERSAMPLENR ,  5 },
1096
-  {  1022.73355805611*OVERSAMPLENR ,  0 }
1097
-};
1098
-#endif
1099 1024
 
1100 1025
 #define _TT_NAME(_N) temptable_ ## _N
1101 1026
 #define TT_NAME(_N) _TT_NAME(_N)

+ 1629
- 1625
Marlin/ultralcd.cpp
文件差異過大導致無法顯示
查看文件


+ 6
- 5
README.md 查看文件

@@ -1,8 +1,8 @@
1 1
 ==========================
2 2
 Marlin 3D Printer Firmware
3 3
 ==========================
4
-[![Coverity Scan Build Status](https://scan.coverity.com/projects/2224/badge.svg)](https://scan.coverity.com/projects/2224)
5
-
4
+[![Coverity Scan Build Status](https://scan.coverity.com/projects/2224/badge.svg)](https://scan.coverity.com/projects/2224)
5
+
6 6
 Marlin has a GPL license because I believe in open development.
7 7
 Please do not use this code in products (3D printers, CNC etc) that are closed source or are crippled by a patent.
8 8
 
@@ -47,6 +47,7 @@ Features:
47 47
 *   PID tuning
48 48
 *   CoreXY kinematics (www.corexy.com/theory.html)
49 49
 *   Delta kinematics
50
+*   SCARA kinematics
50 51
 *   Dual X-carriage support for multiple extruder systems
51 52
 *   Configurable serial port to support connection of wireless adaptors.
52 53
 *   Automatic operation of extruder/cold-end cooling fans based on nozzle temperature
@@ -207,15 +208,15 @@ M Codes
207 208
 *  M140 - Set bed target temp
208 209
 *  M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
209 210
 *         Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
210
-*  M200 D<millimeters>- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
211
+*  M200 D<millimeters>- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
211 212
 *  M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
212 213
 *  M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
213 214
 *  M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
214 215
 *  M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2  also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
215 216
 *  M205 -  advanced settings:  minimum travel speed S=while printing T=travel only,  B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E=maximum E jerk
216 217
 *  M206 - set additional homeing offset
217
-*  M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting
218
-*  M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/min]
218
+*  M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting
219
+*  M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/min]
219 220
 *  M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction.
220 221
 *  M218 - set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
221 222
 *  M220 S<factor in percent>- set speed factor override percentage

Loading…
取消
儲存