Bläddra i källkod

Merge branch 'Marlin_v1' into thinkyhead

Conflicts:
	Marlin/Configuration.h
	Marlin/Configuration_adv.h
	Marlin/Marlin.h
	Marlin/Marlin_main.cpp
	Marlin/Servo.cpp
	Marlin/language.h
	Marlin/pins.h
	Marlin/planner.cpp
	Marlin/ultralcd_implementation_hitachi_HD44780.h
	README.md
Erik van der Zalm 11 år sedan
förälder
incheckning
bd96d22bfb

+ 80
- 5
Marlin/Configuration.h Visa fil

@@ -48,6 +48,7 @@
48 48
 // 90 = Alpha OMCA board
49 49
 // 91 = Final OMCA board
50 50
 // 301 = Rambo
51
+// 21 = Elefu Ra Board (v3)
51 52
 
52 53
 #ifndef MOTHERBOARD
53 54
 #define MOTHERBOARD 7
@@ -65,6 +66,43 @@
65 66
 
66 67
 #define POWER_SUPPLY 1
67 68
 
69
+
70
+//===========================================================================
71
+//============================== Delta Settings =============================
72
+//===========================================================================
73
+// Enable DELTA kinematics
74
+#define DELTA
75
+
76
+// Make delta curves from many straight lines (linear interpolation).
77
+// This is a trade-off between visible corners (not enough segments)
78
+// and processor overload (too many expensive sqrt calls).
79
+#define DELTA_SEGMENTS_PER_SECOND 200
80
+
81
+// Center-to-center distance of the holes in the diagonal push rods.
82
+#define DELTA_DIAGONAL_ROD 250.0 // mm
83
+
84
+// Horizontal offset from middle of printer to smooth rod center.
85
+#define DELTA_SMOOTH_ROD_OFFSET 175.0 // mm
86
+
87
+// Horizontal offset of the universal joints on the end effector.
88
+#define DELTA_EFFECTOR_OFFSET 33.0 // mm
89
+
90
+// Horizontal offset of the universal joints on the carriages.
91
+#define DELTA_CARRIAGE_OFFSET 18.0 // mm
92
+
93
+// Effective horizontal distance bridged by diagonal push rods.
94
+#define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET-DELTA_EFFECTOR_OFFSET-DELTA_CARRIAGE_OFFSET)
95
+
96
+// Effective X/Y positions of the three vertical towers.
97
+#define SIN_60 0.8660254037844386
98
+#define COS_60 0.5
99
+#define DELTA_TOWER1_X -SIN_60*DELTA_RADIUS // front left tower
100
+#define DELTA_TOWER1_Y -COS_60*DELTA_RADIUS
101
+#define DELTA_TOWER2_X SIN_60*DELTA_RADIUS // front right tower
102
+#define DELTA_TOWER2_Y -COS_60*DELTA_RADIUS
103
+#define DELTA_TOWER3_X 0.0 // back middle tower
104
+#define DELTA_TOWER3_Y DELTA_RADIUS
105
+
68 106
 //===========================================================================
69 107
 //=============================Thermal Settings  ============================
70 108
 //===========================================================================
@@ -130,8 +168,8 @@
130 168
 // PID settings:
131 169
 // Comment the following line to disable PID and enable bang-bang.
132 170
 #define PIDTEMP
133
-#define BANG_MAX 256 // limits current to nozzle while in bang-bang mode; 256=full current
134
-#define PID_MAX 256 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 256=full current
171
+#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
172
+#define PID_MAX 255 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
135 173
 #ifdef PIDTEMP
136 174
   //#define PID_DEBUG // Sends debug data to the serial port.
137 175
   //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
@@ -174,9 +212,9 @@
174 212
 
175 213
 // This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
176 214
 // all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
177
-// setting this to anything other than 256 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
215
+// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
178 216
 // so you shouldn't use it unless you are OK with PWM on your bed.  (see the comment on enabling PIDTEMPBED)
179
-#define MAX_BED_POWER 256 // limits duty cycle to bed; 256=full current
217
+#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
180 218
 
181 219
 #ifdef PIDTEMPBED
182 220
 //120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
@@ -240,6 +278,11 @@ const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
240 278
 const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
241 279
 //#define DISABLE_MAX_ENDSTOPS
242 280
 
281
+// Disable max endstops for compatibility with endstop checking routine
282
+#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
283
+  #define DISABLE_MAX_ENDSTOPS
284
+#endif
285
+
243 286
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
244 287
 #define X_ENABLE_ON 0
245 288
 #define Y_ENABLE_ON 0
@@ -284,9 +327,11 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
284 327
 //#define BED_CENTER_AT_0_0  // If defined, the center of the bed is at (X=0, Y=0)
285 328
 
286 329
 //Manual homing switch locations:
330
+// For deltabots this means top and center of the cartesian print volume.
287 331
 #define MANUAL_X_HOME_POS 0
288 332
 #define MANUAL_Y_HOME_POS 0
289 333
 #define MANUAL_Z_HOME_POS 0
334
+//#define MANUAL_Z_HOME_POS 402 // For delta: Distance between nozzle and print surface after homing.
290 335
 
291 336
 //// MOVEMENT SETTINGS
292 337
 #define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
@@ -364,6 +409,11 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
364 409
 //#define REPRAPWORLD_KEYPAD
365 410
 //#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click
366 411
 
412
+// The Elefu RA Board Control Panel
413
+// http://www.elefu.com/index.php?route=product/product&product_id=53
414
+// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARUDINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
415
+//#define RA_CONTROL_PANEL
416
+
367 417
 //automatic expansion
368 418
 #if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
369 419
  #define DOGLCD
@@ -380,6 +430,12 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
380 430
   #define NEWPANEL
381 431
   #define ULTIPANEL
382 432
 #endif
433
+#if defined(RA_CONTROL_PANEL)
434
+ #define ULTIPANEL
435
+ #define NEWPANEL
436
+ #define LCD_I2C_TYPE_PCA8574
437
+ #define LCD_I2C_ADDRESS 0x27   // I2C Address of the port expander
438
+#endif
383 439
 
384 440
 //I2C PANELS
385 441
 
@@ -448,6 +504,17 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
448 504
 // Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
449 505
 //#define FAST_PWM_FAN
450 506
 
507
+// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
508
+// which is not ass annoying as with the hardware PWM. On the other hand, if this frequency
509
+// is too low, you should also increment SOFT_PWM_SCALE.
510
+//#define FAN_SOFT_PWM
511
+
512
+// Incrementing this by 1 will double the software PWM frequency,
513
+// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
514
+// However, control resolution will be halved for each increment;
515
+// at zero value, there are 128 effective control positions.
516
+#define SOFT_PWM_SCALE 0
517
+
451 518
 // M240  Triggers a camera by emulating a Canon RC-1 Remote
452 519
 // Data from: http://www.doc-diy.net/photo/rc-1_hacked/
453 520
 // #define PHOTOGRAPH_PIN     23
@@ -473,7 +540,15 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
473 540
 // leaving it undefined or defining as 0 will disable the servo subsystem
474 541
 // If unsure, leave commented / disabled
475 542
 //
476
-// #define NUM_SERVOS 3
543
+//#define NUM_SERVOS 3 // Servo index starts with 0
544
+
545
+// Servo Endstops
546
+// 
547
+// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
548
+// Use M206 command to correct for switch height offset to actual nozzle height. Store that setting with M500.
549
+// 
550
+//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
551
+//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles
477 552
 
478 553
 #include "Configuration_adv.h"
479 554
 #include "thermistortables.h"

+ 7
- 0
Marlin/Marlin.h Visa fil

@@ -157,6 +157,9 @@ void FlushSerialRequestResend();
157 157
 void ClearToSend();
158 158
 
159 159
 void get_coordinates();
160
+#ifdef DELTA
161
+void calculate_delta(float cartesian[3]);
162
+#endif
160 163
 void prepare_move();
161 164
 void kill();
162 165
 void Stop();
@@ -191,6 +194,10 @@ extern int ValvePressure;
191 194
 extern int EtoPPressure;
192 195
 #endif
193 196
 
197
+#ifdef FAN_SOFT_PWM
198
+extern unsigned char fanSpeedSoftPwm;
199
+#endif
200
+
194 201
 #ifdef FWRETRACT
195 202
 extern bool autoretract_enabled;
196 203
 extern bool retracted;

+ 96
- 7
Marlin/Marlin_main.cpp Visa fil

@@ -177,6 +177,10 @@ float extruder_offset[2][EXTRUDERS] = {
177 177
 #endif
178 178
 uint8_t active_extruder = 0;
179 179
 int fanSpeed=0;
180
+#ifdef SERVO_ENDSTOPS
181
+  int servo_endstops[] = SERVO_ENDSTOPS;
182
+  int servo_endstop_angles[] = SERVO_ENDSTOP_ANGLES;
183
+#endif
180 184
 #ifdef BARICUDA
181 185
 int ValvePressure=0;
182 186
 int EtoPPressure=0;
@@ -194,6 +198,9 @@ int EtoPPressure=0;
194 198
 //===========================================================================
195 199
 const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
196 200
 static float destination[NUM_AXIS] = {  0.0, 0.0, 0.0, 0.0};
201
+#ifdef DELTA
202
+static float delta[3] = {0.0, 0.0, 0.0};
203
+#endif
197 204
 static float offset[3] = {0.0, 0.0, 0.0};
198 205
 static bool home_all_axis = true;
199 206
 static float feedrate = 1500.0, next_feedrate, saved_feedrate;
@@ -351,6 +358,16 @@ void servo_init()
351 358
   #if (NUM_SERVOS >= 5)
352 359
     #error "TODO: enter initalisation code for more servos"
353 360
   #endif
361
+
362
+  // Set position of Servo Endstops that are defined
363
+  #ifdef SERVO_ENDSTOPS
364
+  for(int8_t i = 0; i < 3; i++)
365
+  {
366
+    if(servo_endstops[i] > -1) {
367
+      servos[servo_endstops[i]].write(servo_endstop_angles[i * 2 + 1]);
368
+    }
369
+  }
370
+  #endif
354 371
 }
355 372
 
356 373
 void setup()
@@ -404,10 +421,10 @@ void setup()
404 421
   servo_init();
405 422
 
406 423
   lcd_init();
407
-
424
+  
408 425
   #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
409 426
     SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
410
-  #endif
427
+  #endif 
411 428
 }
412 429
 
413 430
 
@@ -664,11 +681,16 @@ static void axis_is_at_home(int axis) {
664 681
 static void homeaxis(int axis) {
665 682
 #define HOMEAXIS_DO(LETTER) \
666 683
   ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))
667
-
668 684
   if (axis==X_AXIS ? HOMEAXIS_DO(X) :
669 685
       axis==Y_AXIS ? HOMEAXIS_DO(Y) :
670 686
       axis==Z_AXIS ? HOMEAXIS_DO(Z) :
671 687
       0) {
688
+
689
+    // Engage Servo endstop if enabled
690
+    #ifdef SERVO_ENDSTOPS[axis] > -1
691
+      servos[servo_endstops[axis]].write(servo_endstop_angles[axis * 2]);
692
+    #endif
693
+
672 694
     current_position[axis] = 0;
673 695
     plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
674 696
     destination[axis] = 1.5 * max_length(axis) * home_dir(axis);
@@ -691,6 +713,11 @@ static void homeaxis(int axis) {
691 713
     destination[axis] = current_position[axis];
692 714
     feedrate = 0.0;
693 715
     endstops_hit_on_purpose();
716
+
717
+    // Retract Servo endstop if enabled
718
+    #ifdef SERVO_ENDSTOPS[axis] > -1
719
+      servos[servo_endstops[axis]].write(servo_endstop_angles[axis * 2 + 1]);
720
+    #endif
694 721
   }
695 722
 }
696 723
 #define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
@@ -782,8 +809,8 @@ void process_commands()
782 809
         destination[i] = current_position[i];
783 810
       }
784 811
       feedrate = 0.0;
785
-      home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
786
-
812
+      home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])))
813
+                    || ((code_seen(axis_codes[0])) && (code_seen(axis_codes[1])) && (code_seen(axis_codes[2])));
787 814
       #if Z_HOME_DIR > 0                      // If homing away from BED do Z first
788 815
       if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
789 816
         HOMEAXIS(Z);
@@ -812,6 +839,10 @@ void process_commands()
812 839
         feedrate = 0.0;
813 840
         st_synchronize();
814 841
         endstops_hit_on_purpose();
842
+
843
+        current_position[X_AXIS] = destination[X_AXIS];
844
+        current_position[Y_AXIS] = destination[Y_AXIS];
845
+        current_position[Z_AXIS] = destination[Z_AXIS];
815 846
       }
816 847
       #endif
817 848
 
@@ -848,8 +879,12 @@ void process_commands()
848 879
           current_position[Z_AXIS]=code_value()+add_homeing[2];
849 880
         }
850 881
       }
851
-      plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
852
-
882
+      #ifdef DELTA
883
+        calculate_delta(current_position);
884
+        plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
885
+      #else
886
+        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
887
+      #endif
853 888
       #ifdef ENDSTOPS_ONLY_FOR_HOMING
854 889
         enable_endstops(false);
855 890
       #endif
@@ -2032,11 +2067,64 @@ void clamp_to_software_endstops(float target[3])
2032 2067
   }
2033 2068
 }
2034 2069
 
2070
+#ifdef DELTA
2071
+void calculate_delta(float cartesian[3])
2072
+{
2073
+  delta[X_AXIS] = sqrt(sq(DELTA_DIAGONAL_ROD)
2074
+                       - sq(DELTA_TOWER1_X-cartesian[X_AXIS])
2075
+                       - sq(DELTA_TOWER1_Y-cartesian[Y_AXIS])
2076
+                       ) + cartesian[Z_AXIS];
2077
+  delta[Y_AXIS] = sqrt(sq(DELTA_DIAGONAL_ROD)
2078
+                       - sq(DELTA_TOWER2_X-cartesian[X_AXIS])
2079
+                       - sq(DELTA_TOWER2_Y-cartesian[Y_AXIS])
2080
+                       ) + cartesian[Z_AXIS];
2081
+  delta[Z_AXIS] = sqrt(sq(DELTA_DIAGONAL_ROD)
2082
+                       - sq(DELTA_TOWER3_X-cartesian[X_AXIS])
2083
+                       - sq(DELTA_TOWER3_Y-cartesian[Y_AXIS])
2084
+                       ) + cartesian[Z_AXIS];
2085
+  /*
2086
+  SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
2087
+  SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
2088
+  SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
2089
+
2090
+  SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]);
2091
+  SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]);
2092
+  SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]);
2093
+  */
2094
+}
2095
+#endif
2096
+
2035 2097
 void prepare_move()
2036 2098
 {
2037 2099
   clamp_to_software_endstops(destination);
2038 2100
 
2039 2101
   previous_millis_cmd = millis();
2102
+#ifdef DELTA
2103
+  float difference[NUM_AXIS];
2104
+  for (int8_t i=0; i < NUM_AXIS; i++) {
2105
+    difference[i] = destination[i] - current_position[i];
2106
+  }
2107
+  float cartesian_mm = sqrt(sq(difference[X_AXIS]) +
2108
+                            sq(difference[Y_AXIS]) +
2109
+                            sq(difference[Z_AXIS]));
2110
+  if (cartesian_mm < 0.000001) { cartesian_mm = abs(difference[E_AXIS]); }
2111
+  if (cartesian_mm < 0.000001) { return; }
2112
+  float seconds = 6000 * cartesian_mm / feedrate / feedmultiply;
2113
+  int steps = max(1, int(DELTA_SEGMENTS_PER_SECOND * seconds));
2114
+  // SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
2115
+  // SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
2116
+  // SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
2117
+  for (int s = 1; s <= steps; s++) {
2118
+    float fraction = float(s) / float(steps);
2119
+    for(int8_t i=0; i < NUM_AXIS; i++) {
2120
+      destination[i] = current_position[i] + difference[i] * fraction;
2121
+    }
2122
+    calculate_delta(destination);
2123
+    plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS],
2124
+                     destination[E_AXIS], feedrate*feedmultiply/60/100.0,
2125
+                     active_extruder);
2126
+  }
2127
+#else
2040 2128
   // Do not use feedmultiply for E or Z only moves
2041 2129
   if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) {
2042 2130
       plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
@@ -2044,6 +2132,7 @@ void prepare_move()
2044 2132
   else {
2045 2133
     plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0, active_extruder);
2046 2134
   }
2135
+#endif
2047 2136
   for(int8_t i=0; i < NUM_AXIS; i++) {
2048 2137
     current_position[i] = destination[i];
2049 2138
   }

+ 2
- 0
Marlin/Servo.cpp Visa fil

@@ -41,6 +41,8 @@
41 41
  detach()    - Stops an attached servos from pulsing its i/o pin.
42 42
 
43 43
 */
44
+#include "Configuration.h" 
45
+
44 46
 #ifdef NUM_SERVOS
45 47
 #include <avr/interrupt.h>
46 48
 #include <Arduino.h>

+ 25
- 25
Marlin/language.h Visa fil

@@ -9,7 +9,7 @@
9 9
 // Languages
10 10
 // 1  English
11 11
 // 2  Polish
12
-// 3  French	(awaiting translation!)
12
+// 3  French
13 13
 // 4  German
14 14
 // 5  Spanish
15 15
 // 6  Russian
@@ -79,9 +79,9 @@
79 79
 	#define MSG_PID_D "PID-D"
80 80
 	#define MSG_PID_C "PID-C"
81 81
 	#define MSG_ACC  "Accel"
82
-	#define MSG_VXY_JERK "Vxy-jerk"
83
-	#define MSG_VZ_JERK "Vz-jerk"
84
-	#define MSG_VE_JERK "Ve-jerk"
82
+	#define MSG_VXY_JERK "Vxy-jerk"
83
+	#define MSG_VZ_JERK "Vz-jerk"
84
+	#define MSG_VE_JERK "Ve-jerk"
85 85
 	#define MSG_VMAX "Vmax "
86 86
 	#define MSG_X "x"
87 87
 	#define MSG_Y "y"
@@ -239,8 +239,8 @@
239 239
 	#define MSG_PID_C "PID-C"
240 240
 	#define MSG_ACC  "Acc"
241 241
 	#define MSG_VXY_JERK "Zryw Vxy"
242
-	#define MSG_VZ_JERK "Zryw Vz"
243
-	#define MSG_VE_JERK "Zryw Ve"
242
+	#define MSG_VZ_JERK "Zryw Vz"
243
+	#define MSG_VE_JERK "Zryw Ve"
244 244
 	#define MSG_VMAX "Vmax"
245 245
 	#define MSG_X "x"
246 246
 	#define MSG_Y "y"
@@ -400,8 +400,8 @@
400 400
 #define MSG_PID_C " PID-C: "
401 401
 #define MSG_ACC " Acc:"
402 402
 #define MSG_VXY_JERK "Vxy-jerk"
403
-#define MSG_VZ_JERK "Vz-jerk"
404
-#define MSG_VE_JERK "Ve-jerk"
403
+#define MSG_VZ_JERK "Vz-jerk"
404
+#define MSG_VE_JERK "Ve-jerk"
405 405
 #define MSG_VMAX " Vmax "
406 406
 #define MSG_X "x:"
407 407
 #define MSG_Y "y:"
@@ -565,8 +565,8 @@
565 565
 	#define MSG_PID_C            "PID-C"
566 566
 	#define MSG_ACC              "Acc"
567 567
 	#define MSG_VXY_JERK         "Vxy-jerk"
568
-	#define MSG_VZ_JERK          "Vz-jerk"
569
-	#define MSG_VE_JERK          "Ve-jerk"
568
+	#define MSG_VZ_JERK          "Vz-jerk"
569
+	#define MSG_VE_JERK          "Ve-jerk"
570 570
 	#define MSG_VMAX             "Vmax "
571 571
 	#define MSG_X                "x"
572 572
 	#define MSG_Y                "y"
@@ -706,9 +706,9 @@
706 706
 #define MSG_PREHEAT_ABS_SETTINGS " Ajustar temp. ABS"
707 707
 #define MSG_MOVE_AXIS " Mover Ejes      \x7E"
708 708
 #define MSG_SPEED " Velocidad:"
709
-#define MSG_NOZZLE " \002Nozzle:"
710
-#define MSG_NOZZLE1 " \002Nozzle2:"
711
-#define MSG_NOZZLE2 " \002Nozzle3:"
709
+#define MSG_NOZZLE " \002Fusor:"
710
+#define MSG_NOZZLE1 " \002Fusor2:"
711
+#define MSG_NOZZLE2 " \002Fusor3:"
712 712
 #define MSG_BED " \002Base:"
713 713
 #define MSG_FAN_SPEED " Ventilador:"
714 714
 #define MSG_FLOW " Flujo:"
@@ -724,9 +724,9 @@
724 724
 #define MSG_PID_D " PID-D: "
725 725
 #define MSG_PID_C " PID-C: "
726 726
 #define MSG_ACC  " Acc:"
727
-#define MSG_VXY_JERK " Vxy-jerk: "
728
-#define MSG_VZ_JERK "Vz-jerk"
729
-#define MSG_VE_JERK "Ve-jerk"
727
+#define MSG_VXY_JERK " Vxy-agit: "
728
+#define MSG_VZ_JERK "Vz-agit"
729
+#define MSG_VE_JERK "Ve-agit"
730 730
 #define MSG_VMAX " Vmax "
731 731
 #define MSG_X "x:"
732 732
 #define MSG_Y "y:"
@@ -821,7 +821,7 @@
821 821
 #define MSG_M119_REPORT "Comprobando fines de carrera."
822 822
 #define MSG_ENDSTOP_HIT "PULSADO"
823 823
 #define MSG_ENDSTOP_OPEN "abierto"
824
-#define MSG_HOTEND_OFFSET "Hotend offsets:"
824
+#define MSG_HOTEND_OFFSET "Despl. Hotend:"
825 825
         
826 826
 #define MSG_SD_CANT_OPEN_SUBDIR "No se pudo abrir la subcarpeta."
827 827
 #define MSG_SD_INIT_FAIL "Fallo al iniciar la SD"
@@ -885,8 +885,8 @@
885 885
 #define MSG_PID_C							" PID-C: "
886 886
 #define MSG_ACC								" Acc:"
887 887
 #define MSG_VXY_JERK						" Vxy-jerk: "
888
-#define MSG_VZ_JERK                         "Vz-jerk"
889
-#define MSG_VE_JERK                         "Ve-jerk"
888
+#define MSG_VZ_JERK                         "Vz-jerk"
889
+#define MSG_VE_JERK                         "Ve-jerk"
890 890
 #define MSG_VMAX							" Vmax "
891 891
 #define MSG_X								"x:"
892 892
 #define MSG_Y								"y:"
@@ -1040,8 +1040,8 @@
1040 1040
 	#define MSG_PID_C                "PID-C"
1041 1041
 	#define MSG_ACC                  "Accel"
1042 1042
 	#define MSG_VXY_JERK             "Vxy-jerk"
1043
-	#define MSG_VZ_JERK              "Vz-jerk"
1044
-	#define MSG_VE_JERK              "Ve-jerk"
1043
+	#define MSG_VZ_JERK              "Vz-jerk"
1044
+	#define MSG_VE_JERK              "Ve-jerk"
1045 1045
 	#define MSG_VMAX                 "Vmax"
1046 1046
 	#define MSG_X                    "x"
1047 1047
 	#define MSG_Y                    "y"
@@ -1202,8 +1202,8 @@
1202 1202
 	#define MSG_PID_C " PID-C: "
1203 1203
 	#define MSG_ACC  " Acc:"
1204 1204
 	#define MSG_VXY_JERK " Vxy-jerk: "
1205
-	#define MSG_VZ_JERK "Vz-jerk"
1206
-	#define MSG_VE_JERK "Ve-jerk"
1205
+	#define MSG_VZ_JERK "Vz-jerk"
1206
+	#define MSG_VE_JERK "Ve-jerk"
1207 1207
 	#define MSG_VMAX " Vmax "
1208 1208
 	#define MSG_X "x:"
1209 1209
 	#define MSG_Y "y:"
@@ -1370,8 +1370,8 @@
1370 1370
 	#define MSG_PID_C "PID-C"
1371 1371
 	#define MSG_ACC  "Kiihtyv"
1372 1372
 	#define MSG_VXY_JERK "Vxy-jerk"
1373
-	#define MSG_VZ_JERK "Vz-jerk"
1374
-	#define MSG_VE_JERK "Ve-jerk"
1373
+	#define MSG_VZ_JERK "Vz-jerk"
1374
+	#define MSG_VE_JERK "Ve-jerk"
1375 1375
 	#define MSG_VMAX "Vmax "
1376 1376
 	#define MSG_X "x"
1377 1377
 	#define MSG_Y "y"

+ 127
- 1
Marlin/pins.h Visa fil

@@ -53,6 +53,7 @@
53 53
 
54 54
 #endif /* 99 */
55 55
 
56
+
56 57
 /****************************************************************************************
57 58
 * Gen7 v1.1, v1.2, v1.3 pin assignment
58 59
 *
@@ -391,7 +392,7 @@
391 392
       #define SERVO2_PIN         5
392 393
     #endif
393 394
 
394
-    #if NUM_SERVOS > 2
395
+    #if NUM_SERVOS > 3
395 396
       #define SERVO3_PIN         4
396 397
     #endif
397 398
   #endif
@@ -572,6 +573,131 @@
572 573
 #endif
573 574
 
574 575
 /****************************************************************************************
576
+* Elefu RA Board Pin Assignments
577
+*
578
+****************************************************************************************/
579
+#if MOTHERBOARD == 21
580
+#define	KNOWN_BOARD 1
581
+
582
+#ifndef __AVR_ATmega2560__
583
+ #error Oops!  Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
584
+#endif
585
+
586
+
587
+#define X_STEP_PIN		     49
588
+#define X_DIR_PIN			     13
589
+#define X_ENABLE_PIN		   48
590
+#define X_MIN_PIN			     35
591
+#define X_MAX_PIN			     -1 //34
592
+
593
+#define Y_STEP_PIN         11
594
+#define Y_DIR_PIN          9
595
+#define Y_ENABLE_PIN       12
596
+#define Y_MIN_PIN          33
597
+#define Y_MAX_PIN          -1 //32
598
+
599
+#define Z_STEP_PIN         7
600
+#define Z_DIR_PIN          6
601
+#define Z_ENABLE_PIN       8
602
+#define Z_MIN_PIN          31
603
+#define Z_MAX_PIN          -1 //30
604
+
605
+#define E2_STEP_PIN        43
606
+#define E2_DIR_PIN         47
607
+#define E2_ENABLE_PIN      42
608
+
609
+#define E1_STEP_PIN        18
610
+#define E1_DIR_PIN         19
611
+#define E1_ENABLE_PIN      38
612
+
613
+#define E0_STEP_PIN        40
614
+#define E0_DIR_PIN         41
615
+#define E0_ENABLE_PIN      37
616
+
617
+#define SDPOWER            -1
618
+#define LED_PIN            -1 //Use +12V Aux port for LED Ring
619
+
620
+#define FAN_PIN            16 //5V PWM
621
+
622
+#define PS_ON_PIN          10 //Set to -1 if using a manual switch on the PWRSW Connector
623
+#define SLEEP_WAKE_PIN		 26 //This feature still needs work
624
+
625
+#define HEATER_0_PIN       45	//12V PWM1
626
+#define HEATER_1_PIN       46	//12V PWM2
627
+#define HEATER_2_PIN       17	//12V PWM3
628
+#define HEATER_BED_PIN     44	//DOUBLE 12V PWM
629
+#define TEMP_0_PIN         3	//ANALOG NUMBERING
630
+#define TEMP_1_PIN         2 	//ANALOG NUMBERING
631
+#define TEMP_2_PIN         1 	//ANALOG NUMBERING
632
+#define TEMP_BED_PIN       0	//ANALOG NUMBERING
633
+
634
+#define BEEPER 		         36
635
+
636
+#define KILL_PIN           -1
637
+
638
+// M240  Triggers a camera by emulating a Canon RC-1 Remote
639
+// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
640
+#define PHOTOGRAPH_PIN     29
641
+
642
+#ifdef RA_CONTROL_PANEL
643
+
644
+  #define SDSS             53
645
+  #define SDCARDDETECT     28
646
+
647
+  #define BTN_EN1          14
648
+  #define BTN_EN2          39
649
+  #define BTN_ENC          15  //the click
650
+    
651
+  #define BLEN_C           2
652
+  #define BLEN_B           1
653
+  #define BLEN_A           0
654
+    
655
+  //encoder rotation values
656
+  #define encrot0          0
657
+  #define encrot1          2
658
+  #define encrot2          3
659
+  #define encrot3          1
660
+  
661
+#endif //RA_CONTROL_PANEL
662
+
663
+#ifdef RA_DISCO
664
+  //variables for which pins the TLC5947 is using
665
+  #define TLC_CLOCK_PIN    25
666
+  #define TLC_BLANK_PIN    23
667
+  #define TLC_XLAT_PIN     22
668
+  #define TLC_DATA_PIN     24
669
+
670
+  //We also need to define pin to port number mapping for the 2560 to match the pins listed above. If you change the TLC pins, update this as well per the 2560 datasheet!
671
+  //This currently only works with the RA Board.
672
+  #define TLC_CLOCK_BIT 3 //bit 3 on port A
673
+  #define TLC_CLOCK_PORT &PORTA //bit 3 on port A
674
+  
675
+  #define TLC_BLANK_BIT 1 //bit 1 on port A
676
+  #define TLC_BLANK_PORT &PORTA //bit 1 on port A
677
+
678
+  #define TLC_DATA_BIT 2 //bit 2 on port A
679
+  #define TLC_DATA_PORT &PORTA //bit 2 on port A
680
+
681
+  #define TLC_XLAT_BIT 0 //bit 0 on port A
682
+  #define TLC_XLAT_PORT &PORTA //bit 0 on port A
683
+
684
+  //change this to match your situation. Lots of TLCs takes up the arduino SRAM very quickly, so be careful 
685
+  //Leave it at at least 1 if you have enabled RA_LIGHTING
686
+  //The number of TLC5947 boards chained together for use with the animation, additional ones will repeat the animation on them, but are not individually addressable and mimic those before them. You can leave the default at 2 even if you only have 1 TLC5947 module.
687
+  #define NUM_TLCS 2 
688
+
689
+  //These TRANS_ARRAY values let you change the order the LEDs on the lighting modules will animate for chase functions. 
690
+  //Modify them according to your specific situation.
691
+  //NOTE: the array should be 8 long for every TLC you have. These defaults assume (2) TLCs.
692
+  #define TRANS_ARRAY {0, 1, 2, 3, 4, 5, 6, 7, 15, 14, 13, 12, 11, 10, 9, 8} //forwards
693
+  //#define TRANS_ARRAY {7, 6, 5, 4, 3, 2, 1, 0, 8, 9, 10, 11, 12, 13, 14, 15} //backwards
694
+#endif //RA_LIGHTING
695
+
696
+
697
+#endif /* Ra Board */
698
+
699
+
700
+/****************************************************************************************
575 701
 * Gen6 pin assignment
576 702
 *
577 703
 ****************************************************************************************/

+ 47
- 21
Marlin/planner.cpp Visa fil

@@ -473,22 +473,24 @@ void check_axes_activity()
473 473
     disable_e2(); 
474 474
   }
475 475
 #if defined(FAN_PIN) && FAN_PIN > -1
476
-  #ifndef FAN_SOFT_PWM
477
-    #ifdef FAN_KICKSTART_TIME
478
-      static unsigned long fan_kick_end;
479
-      if (tail_fan_speed) {
480
-        if (fan_kick_end == 0) {
481
-          // Just starting up fan - run at full power.
482
-          fan_kick_end = millis() + FAN_KICKSTART_TIME;
483
-          tail_fan_speed = 255;
484
-        } else if (fan_kick_end > millis())
485
-          // Fan still spinning up.
486
-          tail_fan_speed = 255;
487
-      } else {
488
-        fan_kick_end = 0;
489
-      }
490
-    #endif//FAN_KICKSTART_TIME
491
-    analogWrite(FAN_PIN,tail_fan_speed);
476
+  #ifdef FAN_KICKSTART_TIME
477
+    static unsigned long fan_kick_end;
478
+    if (tail_fan_speed) {
479
+      if (fan_kick_end == 0) {
480
+        // Just starting up fan - run at full power.
481
+        fan_kick_end = millis() + FAN_KICKSTART_TIME;
482
+        tail_fan_speed = 255;
483
+      } else if (fan_kick_end > millis())
484
+        // Fan still spinning up.
485
+        tail_fan_speed = 255;
486
+    } else {
487
+      fan_kick_end = 0;
488
+    }
489
+  #endif//FAN_KICKSTART_TIME
490
+  #ifdef FAN_SOFT_PWM
491
+  fanSpeedSoftPwm = tail_fan_speed;
492
+  #else
493
+  analogWrite(FAN_PIN,tail_fan_speed);
492 494
   #endif//!FAN_SOFT_PWM
493 495
 #endif//FAN_PIN > -1
494 496
 #ifdef AUTOTEMP
@@ -562,8 +564,16 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
562 564
   block->busy = false;
563 565
 
564 566
   // Number of steps for each axis
565
-  block->steps_x = labs(target[X_AXIS]-position[X_AXIS]);
566
-  block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
567
+#ifndef COREXY
568
+// default non-h-bot planning
569
+block->steps_x = labs(target[X_AXIS]-position[X_AXIS]);
570
+block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
571
+#else
572
+// corexy planning
573
+// these equations follow the form of the dA and dB equations on http://www.corexy.com/theory.html
574
+block->steps_x = labs((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]));
575
+block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]));
576
+#endif
567 577
   block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
568 578
   block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
569 579
   block->steps_e *= extrudemultiply;
@@ -584,6 +594,7 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
584 594
 
585 595
   // Compute direction bits for this block 
586 596
   block->direction_bits = 0;
597
+#ifndef COREXY
587 598
   if (target[X_AXIS] < position[X_AXIS])
588 599
   {
589 600
     block->direction_bits |= (1<<X_AXIS); 
@@ -592,6 +603,16 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
592 603
   {
593 604
     block->direction_bits |= (1<<Y_AXIS); 
594 605
   }
606
+#else
607
+  if ((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]) < 0)
608
+  {
609
+    block->direction_bits |= (1<<X_AXIS); 
610
+  }
611
+  if ((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]) < 0)
612
+  {
613
+    block->direction_bits |= (1<<Y_AXIS); 
614
+  }
615
+#endif
595 616
   if (target[Z_AXIS] < position[Z_AXIS])
596 617
   {
597 618
     block->direction_bits |= (1<<Z_AXIS); 
@@ -636,8 +657,13 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
636 657
   } 
637 658
 
638 659
   float delta_mm[4];
639
-  delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
640
-  delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
660
+  #ifndef COREXY
661
+    delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
662
+    delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
663
+  #else
664
+    delta_mm[X_AXIS] = ((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]))/axis_steps_per_unit[X_AXIS];
665
+    delta_mm[Y_AXIS] = ((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]))/axis_steps_per_unit[Y_AXIS];
666
+  #endif
641 667
   delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
642 668
   delta_mm[E_AXIS] = ((target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS])*extrudemultiply/100.0;
643 669
   if ( block->steps_x <=dropsegments && block->steps_y <=dropsegments && block->steps_z <=dropsegments )
@@ -757,7 +783,7 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
757 783
       block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
758 784
   }
759 785
   block->acceleration = block->acceleration_st / steps_per_mm;
760
-  block->acceleration_rate = (long)((float)block->acceleration_st * 8.388608);
786
+  block->acceleration_rate = (long)((float)block->acceleration_st * (16777216.0 / (F_CPU / 8.0)));
761 787
 
762 788
 #if 0  // Use old jerk for now
763 789
   // Compute path unit vector

+ 28
- 89
Marlin/stepper.cpp Visa fil

@@ -345,12 +345,31 @@ ISR(TIMER1_COMPA_vect)
345 345
     // Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
346 346
     out_bits = current_block->direction_bits;
347 347
 
348
+
349
+    // Set the direction bits (X_AXIS=A_AXIS and Y_AXIS=B_AXIS for COREXY)
350
+    if((out_bits & (1<<X_AXIS))!=0){
351
+      WRITE(X_DIR_PIN, INVERT_X_DIR);
352
+      count_direction[X_AXIS]=-1;
353
+    }
354
+    else{
355
+      WRITE(X_DIR_PIN, !INVERT_X_DIR);
356
+      count_direction[X_AXIS]=1;
357
+    }
358
+    if((out_bits & (1<<Y_AXIS))!=0){
359
+      WRITE(Y_DIR_PIN, INVERT_Y_DIR);
360
+      count_direction[Y_AXIS]=-1;
361
+    }
362
+    else{
363
+      WRITE(Y_DIR_PIN, !INVERT_Y_DIR);
364
+      count_direction[Y_AXIS]=1;
365
+    }
366
+    
348 367
     // Set direction en check limit switches
368
+    #ifndef COREXY
349 369
     if ((out_bits & (1<<X_AXIS)) != 0) {   // stepping along -X axis
350
-      #if !defined COREXY  //NOT COREXY
351
-        WRITE(X_DIR_PIN, INVERT_X_DIR);
352
-      #endif
353
-      count_direction[X_AXIS]=-1;
370
+    #else
371
+    if ((((out_bits & (1<<X_AXIS)) != 0)&&(out_bits & (1<<Y_AXIS)) != 0)) {   //-X occurs for -A and -B
372
+    #endif
354 373
       CHECK_ENDSTOPS
355 374
       {
356 375
         #if defined(X_MIN_PIN) && X_MIN_PIN > -1
@@ -365,11 +384,6 @@ ISR(TIMER1_COMPA_vect)
365 384
       }
366 385
     }
367 386
     else { // +direction
368
-      #if !defined COREXY  //NOT COREXY
369
-        WRITE(X_DIR_PIN,!INVERT_X_DIR);
370
-      #endif
371
-      
372
-      count_direction[X_AXIS]=1;
373 387
       CHECK_ENDSTOPS 
374 388
       {
375 389
         #if defined(X_MAX_PIN) && X_MAX_PIN > -1
@@ -384,11 +398,11 @@ ISR(TIMER1_COMPA_vect)
384 398
       }
385 399
     }
386 400
 
401
+    #ifndef COREXY
387 402
     if ((out_bits & (1<<Y_AXIS)) != 0) {   // -direction
388
-      #if !defined COREXY  //NOT COREXY
389
-        WRITE(Y_DIR_PIN,INVERT_Y_DIR);
390
-      #endif
391
-      count_direction[Y_AXIS]=-1;
403
+    #else
404
+    if ((((out_bits & (1<<X_AXIS)) != 0)&&(out_bits & (1<<Y_AXIS)) == 0)) {   // -Y occurs for -A and +B
405
+    #endif
392 406
       CHECK_ENDSTOPS
393 407
       {
394 408
         #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
@@ -403,10 +417,6 @@ ISR(TIMER1_COMPA_vect)
403 417
       }
404 418
     }
405 419
     else { // +direction
406
-      #if !defined COREXY  //NOT COREXY
407
-        WRITE(Y_DIR_PIN,!INVERT_Y_DIR);
408
-      #endif
409
-      count_direction[Y_AXIS]=1;
410 420
       CHECK_ENDSTOPS
411 421
       {
412 422
         #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
@@ -420,28 +430,7 @@ ISR(TIMER1_COMPA_vect)
420 430
         #endif
421 431
       }
422 432
     }
423
-    
424
-    
425
-    #ifdef COREXY  //coreXY kinematics defined
426
-      if((current_block->steps_x >= current_block->steps_y)&&((out_bits & (1<<X_AXIS)) == 0)){  //+X is major axis
427
-        WRITE(X_DIR_PIN, !INVERT_X_DIR);
428
-        WRITE(Y_DIR_PIN, !INVERT_Y_DIR);
429
-      }
430
-      if((current_block->steps_x >= current_block->steps_y)&&((out_bits & (1<<X_AXIS)) != 0)){  //-X is major axis
431
-        WRITE(X_DIR_PIN, INVERT_X_DIR);
432
-        WRITE(Y_DIR_PIN, INVERT_Y_DIR);
433
-      }      
434
-      if((current_block->steps_y > current_block->steps_x)&&((out_bits & (1<<Y_AXIS)) == 0)){  //+Y is major axis
435
-        WRITE(X_DIR_PIN, !INVERT_X_DIR);
436
-        WRITE(Y_DIR_PIN, INVERT_Y_DIR);
437
-      }        
438
-      if((current_block->steps_y > current_block->steps_x)&&((out_bits & (1<<Y_AXIS)) != 0)){  //-Y is major axis
439
-        WRITE(X_DIR_PIN, INVERT_X_DIR);
440
-        WRITE(Y_DIR_PIN, !INVERT_Y_DIR);
441
-      }  
442
-    #endif //coreXY
443
-    
444
-    
433
+
445 434
     if ((out_bits & (1<<Z_AXIS)) != 0) {   // -direction
446 435
       WRITE(Z_DIR_PIN,INVERT_Z_DIR);
447 436
       
@@ -516,7 +505,6 @@ ISR(TIMER1_COMPA_vect)
516 505
       }    
517 506
       #endif //ADVANCE
518 507
 
519
-      #if !defined COREXY      
520 508
         counter_x += current_block->steps_x;
521 509
         if (counter_x > 0) {
522 510
           WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
@@ -532,56 +520,7 @@ ISR(TIMER1_COMPA_vect)
532 520
           count_position[Y_AXIS]+=count_direction[Y_AXIS]; 
533 521
           WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
534 522
         }
535
-      #endif
536 523
   
537
-      #ifdef COREXY
538
-        counter_x += current_block->steps_x;        
539
-        counter_y += current_block->steps_y;
540
-        
541
-        if ((counter_x > 0)&&!(counter_y>0)){  //X step only
542
-          WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
543
-          WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
544
-          counter_x -= current_block->step_event_count; 
545
-          count_position[X_AXIS]+=count_direction[X_AXIS];         
546
-          WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
547
-          WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
548
-        }
549
-        
550
-        if (!(counter_x > 0)&&(counter_y>0)){  //Y step only
551
-          WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
552
-          WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
553
-          counter_y -= current_block->step_event_count; 
554
-          count_position[Y_AXIS]+=count_direction[Y_AXIS];
555
-          WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
556
-          WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
557
-        }        
558
-        
559
-        if ((counter_x > 0)&&(counter_y>0)){  //step in both axes
560
-          if (((out_bits & (1<<X_AXIS)) == 0)^((out_bits & (1<<Y_AXIS)) == 0)){  //X and Y in different directions
561
-            WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
562
-            counter_x -= current_block->step_event_count;             
563
-            WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
564
-            step_wait();
565
-            count_position[X_AXIS]+=count_direction[X_AXIS];
566
-            count_position[Y_AXIS]+=count_direction[Y_AXIS];
567
-            WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
568
-            counter_y -= current_block->step_event_count;
569
-            WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
570
-          }
571
-          else{  //X and Y in same direction
572
-            WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
573
-            counter_x -= current_block->step_event_count;             
574
-            WRITE(X_STEP_PIN, INVERT_X_STEP_PIN) ;
575
-            step_wait();
576
-            count_position[X_AXIS]+=count_direction[X_AXIS];
577
-            count_position[Y_AXIS]+=count_direction[Y_AXIS];
578
-            WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN); 
579
-            counter_y -= current_block->step_event_count;    
580
-            WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);        
581
-          }
582
-        }
583
-      #endif //corexy
584
-      
585 524
       counter_z += current_block->steps_z;
586 525
       if (counter_z > 0) {
587 526
         WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);

+ 12
- 5
Marlin/temperature.cpp Visa fil

@@ -62,6 +62,9 @@ float current_temperature_bed = 0.0;
62 62
   float bedKd=(DEFAULT_bedKd/PID_dT);
63 63
 #endif //PIDTEMPBED
64 64
   
65
+#ifdef FAN_SOFT_PWM
66
+  unsigned char fanSpeedSoftPwm;
67
+#endif
65 68
   
66 69
 //===========================================================================
67 70
 //=============================private variables============================
@@ -145,6 +148,10 @@ int watch_start_temp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
145 148
 unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
146 149
 #endif //WATCH_TEMP_PERIOD
147 150
 
151
+#ifndef SOFT_PWM_SCALE
152
+#define SOFT_PWM_SCALE 0
153
+#endif
154
+
148 155
 //===========================================================================
149 156
 //=============================   functions      ============================
150 157
 //===========================================================================
@@ -720,8 +727,8 @@ void tp_init()
720 727
     setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
721 728
     #endif
722 729
     #ifdef FAN_SOFT_PWM
723
-	soft_pwm_fan=(unsigned char)fanSpeed;
724
-	#endif
730
+    soft_pwm_fan = fanSpeedSoftPwm / 2;
731
+    #endif
725 732
   #endif  
726 733
 
727 734
   #ifdef HEATER_0_USES_MAX6675
@@ -1028,7 +1035,7 @@ ISR(TIMER0_COMPB_vect)
1028 1035
   static unsigned long raw_temp_2_value = 0;
1029 1036
   static unsigned long raw_temp_bed_value = 0;
1030 1037
   static unsigned char temp_state = 0;
1031
-  static unsigned char pwm_count = 1;
1038
+  static unsigned char pwm_count = (1 << SOFT_PWM_SCALE);
1032 1039
   static unsigned char soft_pwm_0;
1033 1040
   #if EXTRUDERS > 1
1034 1041
   static unsigned char soft_pwm_1;
@@ -1056,7 +1063,7 @@ ISR(TIMER0_COMPB_vect)
1056 1063
     if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1);
1057 1064
     #endif
1058 1065
     #ifdef FAN_SOFT_PWM
1059
-    soft_pwm_fan =(unsigned char) fanSpeed;
1066
+    soft_pwm_fan = fanSpeedSoftPwm / 2;
1060 1067
     if(soft_pwm_fan > 0) WRITE(FAN_PIN,1);
1061 1068
     #endif
1062 1069
   }
@@ -1074,7 +1081,7 @@ ISR(TIMER0_COMPB_vect)
1074 1081
   if(soft_pwm_fan <= pwm_count) WRITE(FAN_PIN,0);
1075 1082
   #endif
1076 1083
   
1077
-  pwm_count++;
1084
+  pwm_count += (1 << SOFT_PWM_SCALE);
1078 1085
   pwm_count &= 0x7f;
1079 1086
   
1080 1087
   switch(temp_state) {

+ 12
- 3
Marlin/ultralcd_implementation_hitachi_HD44780.h Visa fil

@@ -13,7 +13,7 @@ extern volatile uint16_t buttons;  //an extended version of the last checked but
13 13
 #endif
14 14
 
15 15
 ////////////////////////////////////
16
-// Setup button and encode mappings for each panel (into 'buttons' variable)
16
+// Setup button and encode mappings for each panel (into 'buttons' variable
17 17
 //
18 18
 // This is just to map common functions (across different panels) onto the same 
19 19
 // macro name. The mapping is independent of whether the button is directly connected or 
@@ -180,6 +180,11 @@ extern volatile uint16_t buttons;  //an extended version of the last checked but
180 180
   #include <LiquidTWI2.h>
181 181
   #define LCD_CLASS LiquidTWI2
182 182
   LCD_CLASS lcd(LCD_I2C_ADDRESS);  
183
+
184
+#elif defined(LCD_I2C_TYPE_PCA8574)
185
+    #include <LiquidCrystal_I2C.h>
186
+    #define LCD_CLASS LiquidCrystal_I2C
187
+    LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_WIDTH, LCD_HEIGHT);
183 188
   
184 189
 #else
185 190
   // Standard directly connected LCD implementations
@@ -305,6 +310,10 @@ static void lcd_implementation_init()
305 310
 #elif defined(LCD_I2C_TYPE_MCP23008)
306 311
     lcd.setMCPType(LTI_TYPE_MCP23008);
307 312
     lcd.begin(LCD_WIDTH, LCD_HEIGHT);
313
+
314
+#elif defined(LCD_I2C_TYPE_PCA8574)
315
+      lcd.init();
316
+      lcd.backlight();
308 317
     
309 318
 #else
310 319
     lcd.begin(LCD_WIDTH, LCD_HEIGHT);
@@ -706,9 +715,9 @@ static void lcd_implementation_quick_feedback()
706 715
     for(int8_t i=0;i<10;i++)
707 716
     {
708 717
       WRITE(BEEPER,HIGH);
709
-      delay(3);
718
+      delayMicroseconds(100);
710 719
       WRITE(BEEPER,LOW);
711
-      delay(3);
720
+      delayMicroseconds(100);
712 721
     }
713 722
 #endif
714 723
 }

Laddar…
Avbryt
Spara