2 Reprap firmware based on Sprinter and grbl.
3 Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
5 This program is free software: you can redistribute it and/or modify
6 it under the terms of the GNU General Public License as published by
7 the Free Software Foundation, either version 3 of the License, or
8 (at your option) any later version.
10 This program is distributed in the hope that it will be useful,
11 but WITHOUT ANY WARRANTY; without even the implied warranty of
12 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 GNU General Public License for more details.
15 You should have received a copy of the GNU General Public License
16 along with this program. If not, see <http://www.gnu.org/licenses/>.
20 This firmware is a mashup between Sprinter and grbl.
21 (https://github.com/kliment/Sprinter)
22 (https://github.com/simen/grbl/tree)
24 It has preliminary support for Matthew Roberts advance algorithm
25 http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
33 #include "temperature.h"
34 #include "motion_control.h"
35 #include "cardreader.h"
37 #include "EEPROMwrite.h"
40 #define VERSION_STRING "1.0.0 RC2"
42 // look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
43 // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
48 // G1 - Coordinated Movement X Y Z E
51 // G4 - Dwell S<seconds> or P<milliseconds>
52 // G28 - Home all Axis
53 // G90 - Use Absolute Coordinates
54 // G91 - Use Relative Coordinates
55 // G92 - Set current position to cordinates given
58 // M104 - Set extruder target temp
59 // M105 - Read current temp
62 // M109 - Wait for extruder current temp to reach target temp.
63 // M114 - Display current position
66 // M17 - Enable/Power all stepper motors
67 // M18 - Disable all stepper motors; same as M84
70 // M22 - Release SD card
71 // M23 - Select SD file (M23 filename.g)
72 // M24 - Start/resume SD print
73 // M25 - Pause SD print
74 // M26 - Set SD position in bytes (M26 S12345)
75 // M27 - Report SD print status
76 // M28 - Start SD write (M28 filename.g)
77 // M29 - Stop SD write
78 // M30 - Delete file from SD (M30 filename.g)
79 // M31 - Output time since last M109 or SD card start to serial
80 // M42 - Change pin status via gcode
81 // M80 - Turn on Power Supply
82 // M81 - Turn off Power Supply
83 // M82 - Set E codes absolute (default)
84 // M83 - Set E codes relative while in Absolute Coordinates (G90) mode
85 // M84 - Disable steppers until next move,
86 // or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
87 // M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
88 // M92 - Set axis_steps_per_unit - same syntax as G92
89 // M114 - Output current position to serial port
90 // M115 - Capabilities string
91 // M117 - display message
92 // M119 - Output Endstop status to serial port
93 // M140 - Set bed target temp
94 // M190 - Wait for bed current temp to reach target temp.
95 // M200 - Set filament diameter
96 // M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
97 // M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
98 // M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
99 // 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
100 // 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
101 // M206 - set additional homeing offset
102 // M220 S<factor in percent>- set speed factor override percentage
103 // M221 S<factor in percent>- set extrude factor override percentage
104 // M240 - Trigger a camera to take a photograph
105 // M301 - Set PID parameters P I and D
106 // M302 - Allow cold extrudes
107 // M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
108 // M400 - Finish all moves
109 // M500 - stores paramters in EEPROM
110 // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
111 // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
112 // M503 - print the current settings (from memory not from eeprom)
113 // M999 - Restart after being stopped by error
115 //Stepper Movement Variables
117 //===========================================================================
118 //=============================imported variables============================
119 //===========================================================================
122 //===========================================================================
123 //=============================public variables=============================
124 //===========================================================================
128 float homing_feedrate[] = HOMING_FEEDRATE;
129 bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
130 volatile int feedmultiply=100; //100->1 200->2
131 int saved_feedmultiply;
132 volatile bool feedmultiplychanged=false;
133 volatile int extrudemultiply=100; //100->1 200->2
134 float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
135 float add_homeing[3]={0,0,0};
136 uint8_t active_extruder = 0;
137 unsigned char FanSpeed=0;
140 //===========================================================================
141 //=============================private variables=============================
142 //===========================================================================
143 const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
144 static float destination[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0};
145 static float offset[3] = {0.0, 0.0, 0.0};
146 static bool home_all_axis = true;
147 static float feedrate = 1500.0, next_feedrate, saved_feedrate;
148 static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0;
150 static bool relative_mode = false; //Determines Absolute or Relative Coordinates
151 static bool relative_mode_e = false; //Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode.
153 static char cmdbuffer[BUFSIZE][MAX_CMD_SIZE];
154 static bool fromsd[BUFSIZE];
155 static int bufindr = 0;
156 static int bufindw = 0;
157 static int buflen = 0;
159 static char serial_char;
160 static int serial_count = 0;
161 static boolean comment_mode = false;
162 static char *strchr_pointer; // just a pointer to find chars in the cmd string like X, Y, Z, E, etc
164 const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
166 //static float tt = 0;
167 //static float bt = 0;
169 //Inactivity shutdown variables
170 static unsigned long previous_millis_cmd = 0;
171 static unsigned long max_inactive_time = 0;
172 static unsigned long stepper_inactive_time = DEFAULT_STEPPER_DEACTIVE_TIME*1000l;
174 static unsigned long starttime=0;
175 static unsigned long stoptime=0;
177 static uint8_t tmp_extruder;
181 //===========================================================================
182 //=============================ROUTINES=============================
183 //===========================================================================
185 void get_arc_coordinates();
188 extern unsigned int __bss_end;
189 extern unsigned int __heap_start;
190 extern void *__brkval;
195 if((int)__brkval == 0)
196 free_memory = ((int)&free_memory) - ((int)&__bss_end);
198 free_memory = ((int)&free_memory) - ((int)__brkval);
204 //adds an command to the main command buffer
205 //thats really done in a non-safe way.
206 //needs overworking someday
207 void enquecommand(const char *cmd)
211 //this is dangerous if a mixing of serial and this happsens
212 strcpy(&(cmdbuffer[bufindw][0]),cmd);
214 SERIAL_ECHOPGM("enqueing \"");
215 SERIAL_ECHO(cmdbuffer[bufindw]);
216 SERIAL_ECHOLNPGM("\"");
217 bufindw= (bufindw + 1)%BUFSIZE;
224 #ifdef PHOTOGRAPH_PIN
225 #if (PHOTOGRAPH_PIN > -1)
226 SET_OUTPUT(PHOTOGRAPH_PIN);
227 WRITE(PHOTOGRAPH_PIN, LOW);
232 void setup_powerhold()
235 #if (SUICIDE_PIN> -1)
236 SET_OUTPUT(SUICIDE_PIN);
237 WRITE(SUICIDE_PIN, HIGH);
245 #if (SUICIDE_PIN> -1)
246 SET_OUTPUT(SUICIDE_PIN);
247 WRITE(SUICIDE_PIN, LOW);
255 MYSERIAL.begin(BAUDRATE);
256 SERIAL_PROTOCOLLNPGM("start");
259 // Check startup - does nothing if bootloader sets MCUSR to 0
261 if(mcu & 1) SERIAL_ECHOLNPGM(MSG_POWERUP);
262 if(mcu & 2) SERIAL_ECHOLNPGM(MSG_EXTERNAL_RESET);
263 if(mcu & 4) SERIAL_ECHOLNPGM(MSG_BROWNOUT_RESET);
264 if(mcu & 8) SERIAL_ECHOLNPGM(MSG_WATCHDOG_RESET);
265 if(mcu & 32) SERIAL_ECHOLNPGM(MSG_SOFTWARE_RESET);
268 SERIAL_ECHOPGM(MSG_MARLIN);
269 SERIAL_ECHOLNPGM(VERSION_STRING);
270 #ifdef STRING_VERSION_CONFIG_H
271 #ifdef STRING_CONFIG_H_AUTHOR
273 SERIAL_ECHOPGM(MSG_CONFIGURATION_VER);
274 SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
275 SERIAL_ECHOPGM(MSG_AUTHOR);
276 SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
280 SERIAL_ECHOPGM(MSG_FREE_MEMORY);
281 SERIAL_ECHO(freeMemory());
282 SERIAL_ECHOPGM(MSG_PLANNER_BUFFER_BYTES);
283 SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
284 for(int8_t i = 0; i < BUFSIZE; i++)
289 EEPROM_RetrieveSettings(); // loads data from EEPROM if available
291 for(int8_t i=0; i < NUM_AXIS; i++)
293 axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i];
297 tp_init(); // Initialize temperature loop
298 plan_init(); // Initialize planner;
299 st_init(); // Initialize stepper;
307 if(buflen < (BUFSIZE-1))
310 card.checkautostart(false);
317 if(strstr(cmdbuffer[bufindr],"M29") == NULL)
319 card.write_command(cmdbuffer[bufindr]);
320 SERIAL_PROTOCOLLNPGM(MSG_OK);
325 SERIAL_PROTOCOLLNPGM(MSG_FILE_SAVED);
336 bufindr = (bufindr + 1)%BUFSIZE;
338 //check heater every n milliseconds
340 manage_inactivity(1);
347 while( MYSERIAL.available() > 0 && buflen < BUFSIZE) {
348 serial_char = MYSERIAL.read();
349 if(serial_char == '\n' ||
350 serial_char == '\r' ||
351 (serial_char == ':' && comment_mode == false) ||
352 serial_count >= (MAX_CMD_SIZE - 1) )
354 if(!serial_count) { //if empty line
355 comment_mode = false; //for new command
358 cmdbuffer[bufindw][serial_count] = 0; //terminate string
360 comment_mode = false; //for new command
361 fromsd[bufindw] = false;
362 if(strstr(cmdbuffer[bufindw], "N") != NULL)
364 strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
365 gcode_N = (strtol(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL, 10));
366 if(gcode_N != gcode_LastN+1 && (strstr(cmdbuffer[bufindw], "M110") == NULL) ) {
368 SERIAL_ERRORPGM(MSG_ERR_LINE_NO);
369 SERIAL_ERRORLN(gcode_LastN);
370 //Serial.println(gcode_N);
371 FlushSerialRequestResend();
376 if(strstr(cmdbuffer[bufindw], "*") != NULL)
380 while(cmdbuffer[bufindw][count] != '*') checksum = checksum^cmdbuffer[bufindw][count++];
381 strchr_pointer = strchr(cmdbuffer[bufindw], '*');
383 if( (int)(strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)) != checksum) {
385 SERIAL_ERRORPGM(MSG_ERR_CHECKSUM_MISMATCH);
386 SERIAL_ERRORLN(gcode_LastN);
387 FlushSerialRequestResend();
391 //if no errors, continue parsing
396 SERIAL_ERRORPGM(MSG_ERR_NO_CHECKSUM);
397 SERIAL_ERRORLN(gcode_LastN);
398 FlushSerialRequestResend();
403 gcode_LastN = gcode_N;
404 //if no errors, continue parsing
406 else // if we don't receive 'N' but still see '*'
408 if((strstr(cmdbuffer[bufindw], "*") != NULL))
411 SERIAL_ERRORPGM(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM);
412 SERIAL_ERRORLN(gcode_LastN);
417 if((strstr(cmdbuffer[bufindw], "G") != NULL)){
418 strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
419 switch((int)((strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)))){
424 if(Stopped == false) { // If printer is stopped by an error the G[0-3] codes are ignored.
429 SERIAL_PROTOCOLLNPGM(MSG_OK);
432 SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
433 LCD_MESSAGEPGM(MSG_STOPPED);
441 bufindw = (bufindw + 1)%BUFSIZE;
444 serial_count = 0; //clear buffer
448 if(serial_char == ';') comment_mode = true;
449 if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
453 if(!card.sdprinting || serial_count!=0){
456 while( !card.eof() && buflen < BUFSIZE) {
457 int16_t n=card.get();
458 serial_char = (char)n;
459 if(serial_char == '\n' ||
460 serial_char == '\r' ||
461 (serial_char == ':' && comment_mode == false) ||
462 serial_count >= (MAX_CMD_SIZE - 1)||n==-1)
465 SERIAL_PROTOCOLLNPGM(MSG_FILE_PRINTED);
468 unsigned long t=(stoptime-starttime)/1000;
472 sprintf(time,"%i min, %i sec",min,sec);
476 card.printingHasFinished();
477 card.checkautostart(true);
482 comment_mode = false; //for new command
483 return; //if empty line
485 cmdbuffer[bufindw][serial_count] = 0; //terminate string
486 // if(!comment_mode){
487 fromsd[bufindw] = true;
489 bufindw = (bufindw + 1)%BUFSIZE;
491 comment_mode = false; //for new command
492 serial_count = 0; //clear buffer
496 if(serial_char == ';') comment_mode = true;
497 if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char;
508 return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL));
511 long code_value_long()
513 return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10));
516 bool code_seen(char code_string[]) //Return True if the string was found
518 return (strstr(cmdbuffer[bufindr], code_string) != NULL);
521 bool code_seen(char code)
523 strchr_pointer = strchr(cmdbuffer[bufindr], code);
524 return (strchr_pointer != NULL); //Return True if a character was found
527 #define HOMEAXIS(LETTER) \
528 if ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))\
530 current_position[LETTER##_AXIS] = 0; \
531 plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); \
532 destination[LETTER##_AXIS] = 1.5 * LETTER##_MAX_LENGTH * LETTER##_HOME_DIR; \
533 feedrate = homing_feedrate[LETTER##_AXIS]; \
534 plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
537 current_position[LETTER##_AXIS] = 0;\
538 plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);\
539 destination[LETTER##_AXIS] = -LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\
540 plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
543 destination[LETTER##_AXIS] = 2*LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\
544 feedrate = homing_feedrate[LETTER##_AXIS]/2 ; \
545 plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
548 current_position[LETTER##_AXIS] = (LETTER##_HOME_DIR == -1) ? LETTER##_HOME_POS : LETTER##_MAX_LENGTH;\
549 destination[LETTER##_AXIS] = current_position[LETTER##_AXIS];\
551 endstops_hit_on_purpose();\
554 void process_commands()
556 unsigned long codenum; //throw away variable
557 char *starpos = NULL;
561 switch((int)code_value())
565 if(Stopped == false) {
566 get_coordinates(); // For X Y Z E F
572 case 2: // G2 - CW ARC
573 if(Stopped == false) {
574 get_arc_coordinates();
575 prepare_arc_move(true);
578 case 3: // G3 - CCW ARC
579 if(Stopped == false) {
580 get_arc_coordinates();
581 prepare_arc_move(false);
585 LCD_MESSAGEPGM(MSG_DWELL);
587 if(code_seen('P')) codenum = code_value(); // milliseconds to wait
588 if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
591 codenum += millis(); // keep track of when we started waiting
592 previous_millis_cmd = millis();
593 while(millis() < codenum ){
595 manage_inactivity(1);
598 case 28: //G28 Home all Axis one at a time
599 saved_feedrate = feedrate;
600 saved_feedmultiply = feedmultiply;
602 previous_millis_cmd = millis();
604 enable_endstops(true);
606 for(int8_t i=0; i < NUM_AXIS; i++) {
607 destination[i] = current_position[i];
610 home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
612 if((home_all_axis)||( code_seen(axis_codes[X_AXIS]) && code_seen(axis_codes[Y_AXIS])) ) //first diagonal move
614 current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;
616 plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
617 destination[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR;
618 feedrate = homing_feedrate[X_AXIS];
619 if(homing_feedrate[Y_AXIS]<feedrate)
620 feedrate =homing_feedrate[Y_AXIS];
621 plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
624 current_position[X_AXIS] = (X_HOME_DIR == -1) ? X_HOME_POS : X_MAX_LENGTH;
625 current_position[Y_AXIS] = (Y_HOME_DIR == -1) ? Y_HOME_POS : Y_MAX_LENGTH;
626 plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
627 destination[X_AXIS] = current_position[X_AXIS];
628 destination[Y_AXIS] = current_position[Y_AXIS];
629 plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
632 endstops_hit_on_purpose();
636 if((home_all_axis) || (code_seen(axis_codes[X_AXIS])))
641 if((home_all_axis) || (code_seen(axis_codes[Y_AXIS]))) {
645 if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
649 if(code_seen(axis_codes[X_AXIS]))
651 if(code_value_long() != 0) {
652 current_position[X_AXIS]=code_value()+add_homeing[0];
656 if(code_seen(axis_codes[Y_AXIS])) {
657 if(code_value_long() != 0) {
658 current_position[Y_AXIS]=code_value()+add_homeing[1];
662 if(code_seen(axis_codes[Z_AXIS])) {
663 if(code_value_long() != 0) {
664 current_position[Z_AXIS]=code_value()+add_homeing[2];
667 plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
669 #ifdef ENDSTOPS_ONLY_FOR_HOMING
670 enable_endstops(false);
673 feedrate = saved_feedrate;
674 feedmultiply = saved_feedmultiply;
675 previous_millis_cmd = millis();
676 endstops_hit_on_purpose();
679 relative_mode = false;
682 relative_mode = true;
685 if(!code_seen(axis_codes[E_AXIS]))
687 for(int8_t i=0; i < NUM_AXIS; i++) {
688 if(code_seen(axis_codes[i])) {
689 current_position[i] = code_value()+add_homeing[i];
691 current_position[i] = code_value();
692 plan_set_e_position(current_position[E_AXIS]);
695 current_position[i] = code_value()+add_homeing[i];
696 plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
704 else if(code_seen('M'))
706 switch( (int)code_value() )
709 LCD_MESSAGEPGM(MSG_NO_MOVE);
719 case 20: // M20 - list SD card
720 SERIAL_PROTOCOLLNPGM(MSG_BEGIN_FILE_LIST);
722 SERIAL_PROTOCOLLNPGM(MSG_END_FILE_LIST);
724 case 21: // M21 - init SD card
729 case 22: //M22 - release SD card
733 case 23: //M23 - Select file
734 starpos = (strchr(strchr_pointer + 4,'*'));
737 card.openFile(strchr_pointer + 4,true);
739 case 24: //M24 - Start SD print
740 card.startFileprint();
743 case 25: //M25 - Pause SD print
746 case 26: //M26 - Set SD index
747 if(card.cardOK && code_seen('S')) {
748 card.setIndex(code_value_long());
751 case 27: //M27 - Get SD status
754 case 28: //M28 - Start SD write
755 starpos = (strchr(strchr_pointer + 4,'*'));
757 char* npos = strchr(cmdbuffer[bufindr], 'N');
758 strchr_pointer = strchr(npos,' ') + 1;
761 card.openFile(strchr_pointer+4,false);
763 case 29: //M29 - Stop SD write
764 //processed in write to file routine above
765 //card,saving = false;
767 case 30: //M30 <filename> Delete File
770 starpos = (strchr(strchr_pointer + 4,'*'));
772 char* npos = strchr(cmdbuffer[bufindr], 'N');
773 strchr_pointer = strchr(npos,' ') + 1;
776 card.removeFile(strchr_pointer + 4);
782 case 31: //M31 take time since the start of the SD print or an M109 command
786 unsigned long t=(stoptime-starttime)/1000;
790 sprintf(time,"%i min, %i sec",min,sec);
797 case 42: //M42 -Change pin status via gcode
800 int pin_status = code_value();
801 if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
803 int pin_number = code_value();
804 for(int8_t i = 0; i < (int8_t)sizeof(sensitive_pins); i++)
806 if (sensitive_pins[i] == pin_number)
815 pinMode(pin_number, OUTPUT);
816 digitalWrite(pin_number, pin_status);
817 analogWrite(pin_number, pin_status);
823 tmp_extruder = active_extruder;
825 tmp_extruder = code_value();
826 if(tmp_extruder >= EXTRUDERS) {
828 SERIAL_ECHO(MSG_M104_INVALID_EXTRUDER);
829 SERIAL_ECHOLN(tmp_extruder);
833 if (code_seen('S')) setTargetHotend(code_value(), tmp_extruder);
836 case 140: // M140 set bed temp
837 if (code_seen('S')) setTargetBed(code_value());
840 tmp_extruder = active_extruder;
842 tmp_extruder = code_value();
843 if(tmp_extruder >= EXTRUDERS) {
845 SERIAL_ECHO(MSG_M105_INVALID_EXTRUDER);
846 SERIAL_ECHOLN(tmp_extruder);
850 #if (TEMP_0_PIN > -1)
851 SERIAL_PROTOCOLPGM("ok T:");
852 SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
853 SERIAL_PROTOCOLPGM(" /");
854 SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1);
855 #if TEMP_BED_PIN > -1
856 SERIAL_PROTOCOLPGM(" B:");
857 SERIAL_PROTOCOL_F(degBed(),1);
858 SERIAL_PROTOCOLPGM(" /");
859 SERIAL_PROTOCOL_F(degTargetBed(),1);
860 #endif //TEMP_BED_PIN
863 SERIAL_ERRORLNPGM(MSG_ERR_NO_THERMISTORS);
866 SERIAL_PROTOCOLPGM(" @:");
867 SERIAL_PROTOCOL(getHeaterPower(tmp_extruder));
869 SERIAL_PROTOCOLLN("");
873 {// M109 - Wait for extruder heater to reach target.
874 tmp_extruder = active_extruder;
876 tmp_extruder = code_value();
877 if(tmp_extruder >= EXTRUDERS) {
879 SERIAL_ECHO(MSG_M109_INVALID_EXTRUDER);
880 SERIAL_ECHOLN(tmp_extruder);
884 LCD_MESSAGEPGM(MSG_HEATING);
886 autotemp_enabled=false;
888 if (code_seen('S')) setTargetHotend(code_value(), tmp_extruder);
890 if (code_seen('S')) autotemp_min=code_value();
891 if (code_seen('B')) autotemp_max=code_value();
894 autotemp_factor=code_value();
895 autotemp_enabled=true;
902 /* See if we are heating up or cooling down */
903 bool target_direction = isHeatingHotend(tmp_extruder); // true if heating, false if cooling
905 #ifdef TEMP_RESIDENCY_TIME
908 /* continue to loop until we have reached the target temp
909 _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
910 while((residencyStart == -1) ||
911 (residencyStart >= 0 && (((unsigned int) (millis() - residencyStart)) < (TEMP_RESIDENCY_TIME * 1000UL))) ) {
913 while ( target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder)&&(CooldownNoWait==false)) ) {
914 #endif //TEMP_RESIDENCY_TIME
915 if( (millis() - codenum) > 1000UL )
916 { //Print Temp Reading and remaining time every 1 second while heating up/cooling down
917 SERIAL_PROTOCOLPGM("T:");
918 SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
919 SERIAL_PROTOCOLPGM(" E:");
920 SERIAL_PROTOCOL((int)tmp_extruder);
921 #ifdef TEMP_RESIDENCY_TIME
922 SERIAL_PROTOCOLPGM(" W:");
923 if(residencyStart > -1)
925 codenum = ((TEMP_RESIDENCY_TIME * 1000UL) - (millis() - residencyStart)) / 1000UL;
926 SERIAL_PROTOCOLLN( codenum );
930 SERIAL_PROTOCOLLN( "?" );
933 SERIAL_PROTOCOLLN("");
938 manage_inactivity(1);
940 #ifdef TEMP_RESIDENCY_TIME
941 /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
942 or when current temp falls outside the hysteresis after target temp was reached */
943 if ((residencyStart == -1 && target_direction && (degHotend(tmp_extruder) >= (degTargetHotend(tmp_extruder)-TEMP_WINDOW))) ||
944 (residencyStart == -1 && !target_direction && (degHotend(tmp_extruder) <= (degTargetHotend(tmp_extruder)+TEMP_WINDOW))) ||
945 (residencyStart > -1 && labs(degHotend(tmp_extruder) - degTargetHotend(tmp_extruder)) > TEMP_HYSTERESIS) )
947 residencyStart = millis();
949 #endif //TEMP_RESIDENCY_TIME
951 LCD_MESSAGEPGM(MSG_HEATING_COMPLETE);
953 previous_millis_cmd = millis();
956 case 190: // M190 - Wait for bed heater to reach target.
957 #if TEMP_BED_PIN > -1
958 LCD_MESSAGEPGM(MSG_BED_HEATING);
959 if (code_seen('S')) setTargetBed(code_value());
961 while(isHeatingBed())
963 if(( millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
965 float tt=degHotend(active_extruder);
966 SERIAL_PROTOCOLPGM("T:");
968 SERIAL_PROTOCOLPGM(" E:");
969 SERIAL_PROTOCOL((int)active_extruder);
970 SERIAL_PROTOCOLPGM(" B:");
971 SERIAL_PROTOCOL_F(degBed(),1);
972 SERIAL_PROTOCOLLN("");
976 manage_inactivity(1);
979 LCD_MESSAGEPGM(MSG_BED_DONE);
980 previous_millis_cmd = millis();
985 case 106: //M106 Fan On
987 FanSpeed=constrain(code_value(),0,255);
993 case 107: //M107 Fan Off
999 case 80: // M80 - ATX Power On
1000 SET_OUTPUT(PS_ON_PIN); //GND
1001 WRITE(PS_ON_PIN, LOW);
1005 case 81: // M81 - ATX Power Off
1007 #if defined SUICIDE_PIN && SUICIDE_PIN > -1
1010 #elif (PS_ON_PIN > -1)
1011 SET_INPUT(PS_ON_PIN); //Floating
1016 axis_relative_modes[3] = false;
1019 axis_relative_modes[3] = true;
1021 case 18: //compatibility
1024 stepper_inactive_time = code_value() * 1000;
1028 bool all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2]))|| (code_seen(axis_codes[3])));
1035 finishAndDisableSteppers();
1040 if(code_seen('X')) disable_x();
1041 if(code_seen('Y')) disable_y();
1042 if(code_seen('Z')) disable_z();
1043 #if ((E0_ENABLE_PIN != X_ENABLE_PIN) && (E1_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS
1044 if(code_seen('E')) {
1050 LCD_MESSAGEPGM(MSG_PART_RELEASE);
1056 max_inactive_time = code_value() * 1000;
1059 for(int8_t i=0; i < NUM_AXIS; i++)
1061 if(code_seen(axis_codes[i]))
1064 float value = code_value();
1066 float factor = axis_steps_per_unit[i] / value; // increase e constants if M92 E14 is given for netfab.
1067 max_e_jerk *= factor;
1068 max_feedrate[i] *= factor;
1069 axis_steps_per_sqr_second[i] *= factor;
1071 axis_steps_per_unit[i] = value;
1074 axis_steps_per_unit[i] = code_value();
1079 SerialprintPGM(MSG_M115_REPORT);
1081 case 117: // M117 display message
1082 LCD_MESSAGE(cmdbuffer[bufindr]+5);
1085 SERIAL_PROTOCOLPGM("X:");
1086 SERIAL_PROTOCOL(current_position[X_AXIS]);
1087 SERIAL_PROTOCOLPGM("Y:");
1088 SERIAL_PROTOCOL(current_position[Y_AXIS]);
1089 SERIAL_PROTOCOLPGM("Z:");
1090 SERIAL_PROTOCOL(current_position[Z_AXIS]);
1091 SERIAL_PROTOCOLPGM("E:");
1092 SERIAL_PROTOCOL(current_position[E_AXIS]);
1094 SERIAL_PROTOCOLPGM(MSG_COUNT_X);
1095 SERIAL_PROTOCOL(float(st_get_position(X_AXIS))/axis_steps_per_unit[X_AXIS]);
1096 SERIAL_PROTOCOLPGM("Y:");
1097 SERIAL_PROTOCOL(float(st_get_position(Y_AXIS))/axis_steps_per_unit[Y_AXIS]);
1098 SERIAL_PROTOCOLPGM("Z:");
1099 SERIAL_PROTOCOL(float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]);
1101 SERIAL_PROTOCOLLN("");
1104 enable_endstops(false) ;
1107 enable_endstops(true) ;
1110 #if (X_MIN_PIN > -1)
1111 SERIAL_PROTOCOLPGM(MSG_X_MIN);
1112 SERIAL_PROTOCOL(((READ(X_MIN_PIN)^X_ENDSTOPS_INVERTING)?"H ":"L "));
1114 #if (X_MAX_PIN > -1)
1115 SERIAL_PROTOCOLPGM(MSG_X_MAX);
1116 SERIAL_PROTOCOL(((READ(X_MAX_PIN)^X_ENDSTOPS_INVERTING)?"H ":"L "));
1118 #if (Y_MIN_PIN > -1)
1119 SERIAL_PROTOCOLPGM(MSG_Y_MIN);
1120 SERIAL_PROTOCOL(((READ(Y_MIN_PIN)^Y_ENDSTOPS_INVERTING)?"H ":"L "));
1122 #if (Y_MAX_PIN > -1)
1123 SERIAL_PROTOCOLPGM(MSG_Y_MAX);
1124 SERIAL_PROTOCOL(((READ(Y_MAX_PIN)^Y_ENDSTOPS_INVERTING)?"H ":"L "));
1126 #if (Z_MIN_PIN > -1)
1127 SERIAL_PROTOCOLPGM(MSG_Z_MIN);
1128 SERIAL_PROTOCOL(((READ(Z_MIN_PIN)^Z_ENDSTOPS_INVERTING)?"H ":"L "));
1130 #if (Z_MAX_PIN > -1)
1131 SERIAL_PROTOCOLPGM(MSG_Z_MAX);
1132 SERIAL_PROTOCOL(((READ(Z_MAX_PIN)^Z_ENDSTOPS_INVERTING)?"H ":"L "));
1134 SERIAL_PROTOCOLLN("");
1136 //TODO: update for all axis, use for loop
1138 for(int8_t i=0; i < NUM_AXIS; i++)
1140 if(code_seen(axis_codes[i]))
1142 max_acceleration_units_per_sq_second[i] = code_value();
1143 axis_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
1147 #if 0 // Not used for Sprinter/grbl gen6
1149 for(int8_t i=0; i < NUM_AXIS; i++) {
1150 if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i];
1154 case 203: // M203 max feedrate mm/sec
1155 for(int8_t i=0; i < NUM_AXIS; i++) {
1156 if(code_seen(axis_codes[i])) max_feedrate[i] = code_value();
1159 case 204: // M204 acclereration S normal moves T filmanent only moves
1161 if(code_seen('S')) acceleration = code_value() ;
1162 if(code_seen('T')) retract_acceleration = code_value() ;
1165 case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
1167 if(code_seen('S')) minimumfeedrate = code_value();
1168 if(code_seen('T')) mintravelfeedrate = code_value();
1169 if(code_seen('B')) minsegmenttime = code_value() ;
1170 if(code_seen('X')) max_xy_jerk = code_value() ;
1171 if(code_seen('Z')) max_z_jerk = code_value() ;
1172 if(code_seen('E')) max_e_jerk = code_value() ;
1175 case 206: // M206 additional homeing offset
1176 for(int8_t i=0; i < 3; i++)
1178 if(code_seen(axis_codes[i])) add_homeing[i] = code_value();
1181 case 220: // M220 S<factor in percent>- set speed factor override percentage
1185 feedmultiply = code_value() ;
1186 feedmultiplychanged=true;
1190 case 221: // M221 S<factor in percent>- set extrude factor override percentage
1194 extrudemultiply = code_value() ;
1202 if(code_seen('P')) Kp = code_value();
1203 if(code_seen('I')) Ki = code_value()*PID_dT;
1204 if(code_seen('D')) Kd = code_value()/PID_dT;
1205 #ifdef PID_ADD_EXTRUSION_RATE
1206 if(code_seen('C')) Kc = code_value();
1209 SERIAL_PROTOCOL(MSG_OK);
1210 SERIAL_PROTOCOL(" p:");
1211 SERIAL_PROTOCOL(Kp);
1212 SERIAL_PROTOCOL(" i:");
1213 SERIAL_PROTOCOL(Ki/PID_dT);
1214 SERIAL_PROTOCOL(" d:");
1215 SERIAL_PROTOCOL(Kd*PID_dT);
1216 #ifdef PID_ADD_EXTRUSION_RATE
1217 SERIAL_PROTOCOL(" c:");
1218 SERIAL_PROTOCOL(Kc*PID_dT);
1220 SERIAL_PROTOCOLLN("");
1224 case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
1226 #ifdef PHOTOGRAPH_PIN
1227 #if (PHOTOGRAPH_PIN > -1)
1228 const uint8_t NUM_PULSES=16;
1229 const float PULSE_LENGTH=0.01524;
1230 for(int i=0; i < NUM_PULSES; i++) {
1231 WRITE(PHOTOGRAPH_PIN, HIGH);
1232 _delay_ms(PULSE_LENGTH);
1233 WRITE(PHOTOGRAPH_PIN, LOW);
1234 _delay_ms(PULSE_LENGTH);
1237 for(int i=0; i < NUM_PULSES; i++) {
1238 WRITE(PHOTOGRAPH_PIN, HIGH);
1239 _delay_ms(PULSE_LENGTH);
1240 WRITE(PHOTOGRAPH_PIN, LOW);
1241 _delay_ms(PULSE_LENGTH);
1248 case 302: // finish all moves
1250 allow_cold_extrudes(true);
1253 case 303: // M303 PID autotune
1256 if (code_seen('S')) temp=code_value();
1260 case 400: // finish all moves
1265 case 500: // Store settings in EEPROM
1267 EEPROM_StoreSettings();
1270 case 501: // Read settings from EEPROM
1272 EEPROM_RetrieveSettings();
1275 case 502: // Revert to default settings
1277 EEPROM_RetrieveSettings(true);
1280 case 503: // print settings currently in memory
1282 EEPROM_printSettings();
1285 case 999: // Restart after being stopped
1287 gcode_LastN = Stopped_gcode_LastN;
1288 FlushSerialRequestResend();
1293 else if(code_seen('T'))
1295 tmp_extruder = code_value();
1296 if(tmp_extruder >= EXTRUDERS) {
1299 SERIAL_ECHO(tmp_extruder);
1300 SERIAL_ECHOLN(MSG_INVALID_EXTRUDER);
1303 active_extruder = tmp_extruder;
1305 SERIAL_ECHO(MSG_ACTIVE_EXTRUDER);
1306 SERIAL_PROTOCOLLN((int)active_extruder);
1313 SERIAL_ECHOPGM(MSG_UNKNOWN_COMMAND);
1314 SERIAL_ECHO(cmdbuffer[bufindr]);
1315 SERIAL_ECHOLNPGM("\"");
1321 void FlushSerialRequestResend()
1323 //char cmdbuffer[bufindr][100]="Resend:";
1325 SERIAL_PROTOCOLPGM(MSG_RESEND);
1326 SERIAL_PROTOCOLLN(gcode_LastN + 1);
1332 previous_millis_cmd = millis();
1337 SERIAL_PROTOCOLLNPGM(MSG_OK);
1340 void get_coordinates()
1342 for(int8_t i=0; i < NUM_AXIS; i++) {
1343 if(code_seen(axis_codes[i])) destination[i] = (float)code_value() + (axis_relative_modes[i] || relative_mode)*current_position[i];
1344 else destination[i] = current_position[i]; //Are these else lines really needed?
1346 if(code_seen('F')) {
1347 next_feedrate = code_value();
1348 if(next_feedrate > 0.0) feedrate = next_feedrate;
1352 void get_arc_coordinates()
1355 if(code_seen('I')) {
1356 offset[0] = code_value();
1361 if(code_seen('J')) {
1362 offset[1] = code_value();
1371 if (min_software_endstops) {
1372 if (destination[X_AXIS] < X_HOME_POS) destination[X_AXIS] = X_HOME_POS;
1373 if (destination[Y_AXIS] < Y_HOME_POS) destination[Y_AXIS] = Y_HOME_POS;
1374 if (destination[Z_AXIS] < Z_HOME_POS) destination[Z_AXIS] = Z_HOME_POS;
1377 if (max_software_endstops) {
1378 if (destination[X_AXIS] > X_MAX_LENGTH) destination[X_AXIS] = X_MAX_LENGTH;
1379 if (destination[Y_AXIS] > Y_MAX_LENGTH) destination[Y_AXIS] = Y_MAX_LENGTH;
1380 if (destination[Z_AXIS] > Z_MAX_LENGTH) destination[Z_AXIS] = Z_MAX_LENGTH;
1382 previous_millis_cmd = millis();
1383 plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0, active_extruder);
1384 for(int8_t i=0; i < NUM_AXIS; i++) {
1385 current_position[i] = destination[i];
1389 void prepare_arc_move(char isclockwise) {
1390 float r = hypot(offset[X_AXIS], offset[Y_AXIS]); // Compute arc radius for mc_arc
1393 mc_arc(current_position, destination, offset, X_AXIS, Y_AXIS, Z_AXIS, feedrate*feedmultiply/60/100.0, r, isclockwise, active_extruder);
1395 // As far as the parser is concerned, the position is now == target. In reality the
1396 // motion control system might still be processing the action and the real tool position
1397 // in any intermediate location.
1398 for(int8_t i=0; i < NUM_AXIS; i++) {
1399 current_position[i] = destination[i];
1401 previous_millis_cmd = millis();
1404 #ifdef CONTROLLERFAN_PIN
1405 unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
1406 unsigned long lastMotorCheck = 0;
1408 void controllerFan()
1410 if ((millis() - lastMotorCheck) >= 2500) //Not a time critical function, so we only check every 2500ms
1412 lastMotorCheck = millis();
1414 if(!READ(X_ENABLE_PIN) || !READ(Y_ENABLE_PIN) || !READ(Z_ENABLE_PIN)
1416 || !READ(E2_ENABLE_PIN)
1419 || !READ(E2_ENABLE_PIN)
1421 || !READ(E0_ENABLE_PIN)) //If any of the drivers are enabled...
1423 lastMotor = millis(); //... set time to NOW so the fan will turn on
1426 if ((millis() - lastMotor) >= (CONTROLLERFAN_SEC*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC...
1428 WRITE(CONTROLLERFAN_PIN, LOW); //... turn the fan off
1432 WRITE(CONTROLLERFAN_PIN, HIGH); //... turn the fan on
1438 void manage_inactivity(byte debug)
1440 if( (millis() - previous_millis_cmd) > max_inactive_time )
1441 if(max_inactive_time)
1443 if(stepper_inactive_time) {
1444 if( (millis() - previous_millis_cmd) > stepper_inactive_time )
1446 if(blocks_queued() == false) {
1456 #ifdef CONTROLLERFAN_PIN
1457 controllerFan(); //Check if fan should be turned on to cool stepper drivers down
1459 #ifdef EXTRUDER_RUNOUT_PREVENT
1460 if( (millis() - previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 )
1461 if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP)
1463 bool oldstatus=READ(E0_ENABLE_PIN);
1465 float oldepos=current_position[E_AXIS];
1466 float oldedes=destination[E_AXIS];
1467 plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS],
1468 current_position[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS],
1469 EXTRUDER_RUNOUT_SPEED/60.*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], active_extruder);
1470 current_position[E_AXIS]=oldepos;
1471 destination[E_AXIS]=oldedes;
1472 plan_set_e_position(oldepos);
1473 previous_millis_cmd=millis();
1475 WRITE(E0_ENABLE_PIN,oldstatus);
1478 check_axes_activity();
1483 cli(); // Stop interrupts
1493 if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
1495 SERIAL_ERRORLNPGM(MSG_ERR_KILLED);
1496 LCD_MESSAGEPGM(MSG_KILLED);
1498 while(1); // Wait for reset
1504 if(Stopped == false) {
1506 Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
1508 SERIAL_ERRORLNPGM(MSG_ERR_STOPPED);
1509 LCD_MESSAGEPGM(MSG_STOPPED);
1513 bool IsStopped() { return Stopped; };