Repetier-Firmware  0.80
Repetier/Reptier.h
Go to the documentation of this file.
00001 /*
00002     This file is part of Repetier-Firmware.
00003 
00004     Repetier-Firmware is free software: you can redistribute it and/or modify
00005     it under the terms of the GNU General Public License as published by
00006     the Free Software Foundation, either version 3 of the License, or
00007     (at your option) any later version.
00008 
00009     Repetier-Firmware is distributed in the hope that it will be useful,
00010     but WITHOUT ANY WARRANTY; without even the implied warranty of
00011     MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00012     GNU General Public License for more details.
00013 
00014     You should have received a copy of the GNU General Public License
00015     along with Foobar.  If not, see <http://www.gnu.org/licenses/>.
00016 
00017     This firmware is a nearly complete rewrite of the sprinter firmware
00018     by kliment (https://github.com/kliment/Sprinter)
00019     which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
00020 */
00021 
00022 #ifndef _REPETIER_H
00023 #define _REPETIER_H
00024 
00025 #include <avr/io.h>
00026 
00027 #define REPETIER_VERSION "0.80dev"
00028 
00029 // ##########################################################################################
00030 // ##                                  Debug configuration                                 ##
00031 // ##########################################################################################
00032 
00034 //#define DEBUG_QUEUE_MOVE
00037 #define INCLUDE_DEBUG_COMMUNICATION
00038 
00040 //#define INCLUDE_DEBUG_NO_MOVE
00044 //#define DEBUG_FREE_MEMORY
00045 //#define DEBUG_ADVANCE
00047 //#define DEBUG_OPS
00049 //#define DEBUG_GENERIC
00051 //#define DEBUG_STEPCOUNT
00052 // Uncomment the following line to enable debugging. You can better control debugging below the following line
00053 //#define DEBUG
00054 
00055 
00056 // Uncomment if no analyzer is connected
00057 //#define ANALYZER
00058 // Channel->pin assignments
00059 #define ANALYZER_CH0 63 // New move
00060 #define ANALYZER_CH1 40 // Step loop
00061 #define ANALYZER_CH2 53 // X Step
00062 #define ANALYZER_CH3 65 // Y Step
00063 #define ANALYZER_CH4 59 // X Direction
00064 #define ANALYZER_CH5 64 // Y Direction
00065 #define ANALYZER_CH6 58 // xsig 
00066 #define ANALYZER_CH7 57 // ysig
00067 
00068 #ifdef ANALYZER
00069 #define ANALYZER_ON(a) {WRITE(a,HIGH);}
00070 #define ANALYZER_OFF(a) {WRITE(a,LOW);}
00071 #else
00072 #define ANALYZER_ON(a)
00073 #define ANALYZER_OFF(a)
00074 #endif
00075 
00076 
00077 // Bits of the ADC converter
00078 #define ANALOG_INPUT_BITS 10
00079 // Build median from 2^ANALOG_INPUT_SAMPLE samples
00080 #define ANALOG_INPUT_SAMPLE 5
00081 #define ANALOG_REF_AREF 0
00082 #define ANALOG_REF_AVCC _BV(REFS0)
00083 #define ANALOG_REF_INT_1_1 _BV(REFS1)
00084 #define ANALOG_REF_INT_2_56 _BV(REFS0) | _BV(REFS1)
00085 
00086 // MS1 MS2 Stepper Driver Microstepping mode table
00087 #define MICROSTEP1 LOW,LOW
00088 #define MICROSTEP2 HIGH,LOW
00089 #define MICROSTEP4 LOW,HIGH
00090 #define MICROSTEP8 HIGH,HIGH
00091 #define MICROSTEP16 HIGH,HIGH
00092 
00093 #define NEW_XY_GANTRY
00094 
00095 #include "Configuration.h"
00096 #if DRIVE_SYSTEM==1 || DRIVE_SYSTEM==2
00097 #define XY_GANTRY
00098 #endif
00099 
00100 //Step to split a cirrcle in small Lines 
00101 #ifndef MM_PER_ARC_SEGMENT
00102 #define MM_PER_ARC_SEGMENT 1
00103 #define MM_PER_ARC_SEGMENT_BIG 3
00104 #else
00105 #define MM_PER_ARC_SEGMENT_BIG MM_PER_ARC_SEGMENT
00106 #endif
00107 //After this count of steps a new SIN / COS caluclation is startet to correct the circle interpolation
00108 #define N_ARC_CORRECTION 25
00109 #if CPU_ARCH==ARCH_AVR
00110 #include <avr/io.h>
00111 #else
00112 #define PROGMEM
00113 #define PGM_P const char *
00114 #define PSTR(s) s
00115 #define pgm_read_byte_near(x) (*(char*)x)
00116 #define pgm_read_byte(x) (*(char*)x)
00117 #endif
00118 
00119 #define KOMMA
00120 #if NUM_EXTRUDER>0 && EXT0_TEMPSENSOR_TYPE<100
00121 #define EXT0_ANALOG_INPUTS 1
00122 #define EXT0_SENSOR_INDEX 0
00123 #define EXT0_ANALOG_CHANNEL EXT0_TEMPSENSOR_PIN
00124 #define KOMMA ,
00125 #else
00126 #define EXT0_ANALOG_INPUTS 0
00127 #define EXT0_SENSOR_INDEX EXT0_TEMPSENSOR_PIN
00128 #define EXT0_ANALOG_CHANNEL
00129 #endif
00130 
00131 #if NUM_EXTRUDER>1 && EXT1_TEMPSENSOR_TYPE<100
00132 #define EXT1_ANALOG_INPUTS 1
00133 #define EXT1_SENSOR_INDEX EXT0_ANALOG_INPUTS
00134 #define EXT1_ANALOG_CHANNEL KOMMA EXT1_TEMPSENSOR_PIN
00135 #define KOMMA ,
00136 #else
00137 #define EXT1_ANALOG_INPUTS 0
00138 #define EXT1_SENSOR_INDEX EXT1_TEMPSENSOR_PIN
00139 #define EXT1_ANALOG_CHANNEL
00140 #endif
00141 
00142 #if NUM_EXTRUDER>2 && EXT2_TEMPSENSOR_TYPE<100
00143 #define EXT2_ANALOG_INPUTS 1
00144 #define EXT2_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS
00145 #define EXT2_ANALOG_CHANNEL KOMMA EXT2_TEMPSENSOR_PIN
00146 #define KOMMA ,
00147 #else
00148 #define EXT2_ANALOG_INPUTS 0
00149 #define EXT2_SENSOR_INDEX EXT2_TEMPSENSOR_PIN
00150 #define EXT2_ANALOG_CHANNEL
00151 #endif
00152 
00153 #if NUM_EXTRUDER>3 && EXT3_TEMPSENSOR_TYPE<100
00154 #define EXT3_ANALOG_INPUTS 1
00155 #define EXT3_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS
00156 #define EXT3_ANALOG_CHANNEL KOMMA EXT3_TEMPSENSOR_PIN
00157 #define KOMMA ,
00158 #else
00159 #define EXT3_ANALOG_INPUTS 0
00160 #define EXT3_SENSOR_INDEX EXT3_TEMPSENSOR_PIN
00161 #define EXT3_ANALOG_CHANNEL
00162 #endif
00163 
00164 #if NUM_EXTRUDER>4 && EXT4_TEMPSENSOR_TYPE<100
00165 #define EXT4_ANALOG_INPUTS 1
00166 #define EXT4_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS
00167 #define EXT4_ANALOG_CHANNEL KOMMA EXT4_TEMPSENSOR_PIN
00168 #define KOMMA ,
00169 #else
00170 #define EXT4_ANALOG_INPUTS 0
00171 #define EXT4_SENSOR_INDEX EXT4_TEMPSENSOR_PIN
00172 #define EXT4_ANALOG_CHANNEL
00173 #endif
00174 
00175 #if NUM_EXTRUDER>5 && EXT5_TEMPSENSOR_TYPE<100
00176 #define EXT5_ANALOG_INPUTS 1
00177 #define EXT5_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS
00178 #define EXT5_ANALOG_CHANNEL KOMMA EXT5_TEMPSENSOR_PIN
00179 #define KOMMA ,
00180 #else
00181 #define EXT5_ANALOG_INPUTS 0
00182 #define EXT5_SENSOR_INDEX EXT5_TEMPSENSOR_PIN
00183 #define EXT5_ANALOG_CHANNEL
00184 #endif
00185 
00186 #if HAVE_HEATED_BED==true && HEATED_BED_SENSOR_TYPE<100
00187 #define BED_ANALOG_INPUTS 1
00188 #define BED_SENSOR_INDEX EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS
00189 #define BED_ANALOG_CHANNEL KOMMA  HEATED_BED_SENSOR_PIN
00190 #define KOMMA ,
00191 #else
00192 #define BED_ANALOG_INPUTS 0
00193 #define BED_SENSOR_INDEX HEATED_BED_SENSOR_PIN
00194 #define BED_ANALOG_CHANNEL
00195 #endif
00196 
00197 #ifndef DEBUG_FREE_MEMORY
00198 #define DEBUG_MEMORY
00199 #else
00200 #define DEBUG_MEMORY check_mem();
00201 #endif
00202 
00204 #define ANALOG_INPUTS (EXT0_ANALOG_INPUTS+EXT1_ANALOG_INPUTS+EXT2_ANALOG_INPUTS+EXT3_ANALOG_INPUTS+EXT4_ANALOG_INPUTS+EXT5_ANALOG_INPUTS+BED_ANALOG_INPUTS)
00205 #if ANALOG_INPUTS>0
00206 
00207 #define  ANALOG_INPUT_CHANNELS {EXT0_ANALOG_CHANNEL EXT1_ANALOG_CHANNEL EXT2_ANALOG_CHANNEL EXT3_ANALOG_CHANNEL EXT4_ANALOG_CHANNEL EXT5_ANALOG_CHANNEL BED_ANALOG_CHANNEL}
00208 #endif
00209 #define ANALOG_PRESCALER _BV(ADPS0)|_BV(ADPS1)|_BV(ADPS2)
00210 
00211 #if MOTHERBOARD==8 || MOTHERBOARD==9 || CPU_ARCH!=ARCH_AVR
00212 #define EXTERNALSERIAL
00213 #endif
00214 //#define EXTERNALSERIAL  // Force using arduino serial
00215 #ifndef EXTERNALSERIAL
00216 #define  HardwareSerial_h // Don't use standard serial console
00217 #endif
00218 #include <inttypes.h>
00219 #include "Print.h"
00220 
00221 #if defined(ARDUINO) && ARDUINO >= 100
00222 #include "Arduino.h"
00223 #else
00224 #include "WProgram.h"
00225 #define COMPAT_PRE1
00226 #endif
00227 #include "gcode.h"
00228 #if CPU_ARCH==ARCH_AVR
00229 #include "fastio.h"
00230 #else
00231 #define READ(IO)  digitalRead(IO)
00232 #define WRITE(IO, v)  digitalWrite(IO, v)
00233 #define SET_INPUT(IO)  pinMode(IO, INPUT)
00234 #define SET_OUTPUT(IO)  pinMode(IO, OUTPUT)
00235 #endif
00236 #ifndef SDSUPPORT
00237 #define SDSUPPORT false
00238 #endif
00239 #if SDSUPPORT
00240 #include "SdFat.h"
00241 #endif
00242 #ifndef SDSUPPORT
00243 #define SDSUPPORT false
00244 #endif
00245 #if SDSUPPORT
00246 #include "SdFat.h"
00247 #endif
00248 
00249 #if ENABLE_BACKLASH_COMPENSATION && DRIVE_SYSTEM!=0
00250 #undef ENABLE_BACKLASH_COMPENSATION
00251 #define ENABLE_BACKLASH_COMPENSATION false
00252 #endif
00253 
00254 #define uint uint16_t
00255 #define uint8 uint8_t
00256 #define int8 int8_t
00257 #define uint32 uint32_t
00258 #define int32 int32_t
00259 
00260 /*#if MOTHERBOARD==6 || MOTHERBOARD==62 || MOTHERBOARD==7
00261 #if MOTHERBOARD!=7
00262 #define SIMULATE_PWM
00263 #endif
00264 #define EXTRUDER_TIMER_VECTOR TIMER2_COMPA_vect
00265 #define EXTRUDER_OCR OCR2A
00266 #define EXTRUDER_TCCR TCCR2A
00267 #define EXTRUDER_TIMSK TIMSK2
00268 #define EXTRUDER_OCIE OCIE2A
00269 #define PWM_TIMER_VECTOR TIMER2_COMPB_vect
00270 #define PWM_OCR OCR2B
00271 #define PWM_TCCR TCCR2B
00272 #define PWM_TIMSK TIMSK2
00273 #define PWM_OCIE OCIE2B
00274 #else*/
00275 #define EXTRUDER_TIMER_VECTOR TIMER0_COMPA_vect
00276 #define EXTRUDER_OCR OCR0A
00277 #define EXTRUDER_TCCR TCCR0A
00278 #define EXTRUDER_TIMSK TIMSK0
00279 #define EXTRUDER_OCIE OCIE0A
00280 #define PWM_TIMER_VECTOR TIMER0_COMPB_vect
00281 #define PWM_OCR OCR0B
00282 #define PWM_TCCR TCCR0A
00283 #define PWM_TIMSK TIMSK0
00284 #define PWM_OCIE OCIE0B
00285 //#endif
00286 
00291 typedef struct {
00292   byte pwmIndex; 
00293   byte sensorType; 
00294   byte sensorPin; 
00295   int currentTemperature; 
00296   int targetTemperature; 
00297   float currentTemperatureC; 
00298   float targetTemperatureC; 
00299   unsigned long lastTemperatureUpdate; 
00300   char heatManager; 
00301 #ifdef TEMP_PID
00302   long tempIState; 
00303   byte pidDriveMax; 
00304   byte pidDriveMin; 
00305   float pidPGain; 
00306   float pidIGain; 
00307   float pidDGain;  
00308   byte pidMax; 
00309   float tempIStateLimitMax;
00310   float tempIStateLimitMin;
00311   byte tempPointer;
00312   float tempArray[4];
00313 #endif
00314 } TemperatureController;
00320 typedef struct { // Size: 12*1 Byte+12*4 Byte+4*2Byte = 68 Byte
00321   byte id;
00322   long xOffset;
00323   long yOffset;
00324   float stepsPerMM;        
00325   byte enablePin;          
00326 //  byte directionPin; ///< Pin number to assign the direction.
00327 //  byte stepPin; ///< Pin number for a step.
00328   byte enableOn;
00329 //  byte invertDir; ///< 1 if the direction of the extruder should be inverted.
00330   float maxFeedrate;      
00331   float maxAcceleration;  
00332   float maxStartFeedrate; 
00333   long extrudePosition;   
00334   int watchPeriod;        
00335   int waitRetractTemperature; 
00336   int waitRetractUnits;   
00337 #ifdef USE_ADVANCE
00338 #ifdef ENABLE_QUADRATIC_ADVANCE
00339   float advanceK;         
00340 #endif
00341   float advanceL;
00342 #endif
00343   TemperatureController tempControl;
00344   const char * PROGMEM selectCommands;
00345   const char * PROGMEM deselectCommands;
00346 } Extruder;
00347 
00348 extern const uint8 osAnalogInputChannels[] PROGMEM;
00349 extern uint8 osAnalogInputCounter[ANALOG_INPUTS];
00350 extern uint osAnalogInputBuildup[ANALOG_INPUTS];
00351 extern uint8 osAnalogInputPos; // Current sampling position
00352 extern volatile uint osAnalogInputValues[ANALOG_INPUTS];
00353 extern byte pwm_pos[NUM_EXTRUDER+3]; // 0-NUM_EXTRUDER = Heater 0-NUM_EXTRUDER of extruder, NUM_EXTRUDER = Heated bed, NUM_EXTRUDER+1 Board fan, NUM_EXTRUDER+2 = Fan
00354 #ifdef USE_ADVANCE
00355 #ifdef ENABLE_QUADRATIC_ADVANCE
00356 extern int maxadv;
00357 #endif
00358 extern int maxadv2;
00359 extern float maxadvspeed;
00360 #endif
00361 
00362 extern Extruder *current_extruder;
00363 extern Extruder extruder[];
00364 // Initalize extruder and heated bed related pins
00365 extern void initExtruder();
00366 extern void initHeatedBed();
00367 extern void updateTempControlVars(TemperatureController *tc);
00368 extern void extruder_select(byte ext_num);
00369 // Set current extruder position
00370 //extern void extruder_set_position(float pos,bool relative);
00371 // set the temperature of current extruder
00372 extern void extruder_set_temperature(float temp_celsius,byte extr);
00373 // Set temperature of heated bed
00374 extern void heated_bed_set_temperature(float temp_celsius);
00375 //extern long extruder_steps_to_position(float value,byte relative);
00376 extern void extruder_set_direction(byte steps);
00377 extern void extruder_disable();
00378 #ifdef TEMP_PID
00379 void autotunePID(float temp,int controllerId);
00380 #endif
00381 
00382 //#ifdef TEMP_PID
00383 //extern byte current_extruder_out;
00384 //#endif
00385 
00390 inline void extruder_step() {
00391 #if NUM_EXTRUDER==1
00392   WRITE(EXT0_STEP_PIN,HIGH);
00393 #else
00394   switch(current_extruder->id) {
00395   case 0:
00396 #if NUM_EXTRUDER>0
00397     WRITE(EXT0_STEP_PIN,HIGH);
00398 #endif
00399     break;
00400 #if defined(EXT1_STEP_PIN) && NUM_EXTRUDER>1
00401   case 1:
00402     WRITE(EXT1_STEP_PIN,HIGH);
00403     break;
00404 #endif
00405 #if defined(EXT2_STEP_PIN) && NUM_EXTRUDER>2
00406   case 2:
00407     WRITE(EXT2_STEP_PIN,HIGH);
00408     break;
00409 #endif
00410 #if defined(EXT3_STEP_PIN) && NUM_EXTRUDER>3
00411   case 3:
00412     WRITE(EXT3_STEP_PIN,HIGH);
00413     break;
00414 #endif
00415 #if defined(EXT4_STEP_PIN) && NUM_EXTRUDER>4
00416   case 4:
00417     WRITE(EXT4_STEP_PIN,HIGH);
00418     break;
00419 #endif
00420 #if defined(EXT5_STEP_PIN) && NUM_EXTRUDER>5
00421   case 5:
00422     WRITE(EXT5_STEP_PIN,HIGH);
00423     break;
00424 #endif
00425   }
00426 #endif
00427 }
00432 inline void extruder_unstep() {
00433 #if NUM_EXTRUDER==1
00434   WRITE(EXT0_STEP_PIN,LOW);
00435 #else
00436   switch(current_extruder->id) {
00437   case 0:
00438 #if NUM_EXTRUDER>0
00439     WRITE(EXT0_STEP_PIN,LOW);
00440 #endif
00441     break;
00442 #if defined(EXT1_STEP_PIN) && NUM_EXTRUDER>1
00443   case 1:
00444     WRITE(EXT1_STEP_PIN,LOW);
00445     break;
00446 #endif
00447 #if defined(EXT2_STEP_PIN) && NUM_EXTRUDER>2
00448   case 2:
00449     WRITE(EXT2_STEP_PIN,LOW);
00450     break;
00451 #endif
00452 #if defined(EXT3_STEP_PIN) && NUM_EXTRUDER>3
00453   case 3:
00454     WRITE(EXT3_STEP_PIN,LOW);
00455     break;
00456 #endif
00457 #if defined(EXT4_STEP_PIN) && NUM_EXTRUDER>4
00458   case 4:
00459     WRITE(EXT4_STEP_PIN,LOW);
00460     break;
00461 #endif
00462 #if defined(EXT5_STEP_PIN) && NUM_EXTRUDER>5
00463   case 5:
00464     WRITE(EXT5_STEP_PIN,LOW);
00465     break;
00466 #endif
00467   }
00468 #endif
00469 }
00471 inline void extruder_set_direction(byte dir) {  
00472 #if NUM_EXTRUDER==1
00473   if(dir)
00474     WRITE(EXT0_DIR_PIN,!EXT0_INVERSE);
00475   else
00476     WRITE(EXT0_DIR_PIN,EXT0_INVERSE);
00477 #else
00478   switch(current_extruder->id) {
00479 #if NUM_EXTRUDER>0
00480   case 0:
00481   if(dir)
00482     WRITE(EXT0_DIR_PIN,!EXT0_INVERSE);
00483   else
00484     WRITE(EXT0_DIR_PIN,EXT0_INVERSE);
00485     break;
00486 #endif
00487 #if defined(EXT1_DIR_PIN) && NUM_EXTRUDER>1
00488   case 1:
00489   if(dir)
00490     WRITE(EXT1_DIR_PIN,!EXT1_INVERSE);
00491   else
00492     WRITE(EXT1_DIR_PIN,EXT1_INVERSE);
00493     break;
00494 #endif
00495 #if defined(EXT2_DIR_PIN) && NUM_EXTRUDER>2
00496   case 2:
00497   if(dir)
00498     WRITE(EXT2_DIR_PIN,!EXT2_INVERSE);
00499   else
00500     WRITE(EXT2_DIR_PIN,EXT2_INVERSE);
00501     break;
00502 #endif
00503 #if defined(EXT3_DIR_PIN) && NUM_EXTRUDER>3
00504   case 3:
00505   if(dir)
00506     WRITE(EXT3_DIR_PIN,!EXT3_INVERSE);
00507   else
00508     WRITE(EXT3_DIR_PIN,EXT3_INVERSE);
00509     break;
00510 #endif
00511 #if defined(EXT4_DIR_PIN) && NUM_EXTRUDER>4
00512   case 4:
00513   if(dir)
00514     WRITE(EXT4_DIR_PIN,!EXT4_INVERSE);
00515   else
00516     WRITE(EXT4_DIR_PIN,EXT4_INVERSE);
00517     break;
00518 #endif
00519 #if defined(EXT5_DIR_PIN) && NUM_EXTRUDER>5
00520   case 5:
00521   if(dir)
00522     WRITE(EXT5_DIR_PIN,!EXT5_INVERSE);
00523   else
00524     WRITE(EXT5_DIR_PIN,EXT5_INVERSE);
00525     break;
00526 #endif
00527   }
00528 #endif
00529 }
00530 inline void extruder_enable() {
00531 #if NUM_EXTRUDER==1
00532 #if EXT0_ENABLE_PIN>-1
00533     WRITE(EXT0_ENABLE_PIN,EXT0_ENABLE_ON ); 
00534 #endif
00535 #else
00536   if(current_extruder->enablePin > -1) 
00537     digitalWrite(current_extruder->enablePin,current_extruder->enableOn); 
00538 #endif
00539 }
00540 extern void(* resetFunc) (void); 
00541 // Read a temperature and return its value in °C
00542 // this high level method supports all known methods
00543 extern int read_raw_temperature(byte type,byte pin);
00544 extern float heated_bed_get_temperature();
00545 // Convert a raw temperature value into °C
00546 extern float conv_raw_temp(byte type,int raw_temp);
00547 // Converts a temperture temp in °C into a raw value
00548 // which can be compared with results of read_raw_temperature
00549 extern int conv_temp_raw(byte type,float temp);
00550 // Updates the temperature of all extruders and heated bed if it's time.
00551 // Toggels the heater power if necessary.
00552 extern void manage_temperatures();
00553 extern bool reportTempsensorError(); 
00554 extern byte manage_monitor;
00555 
00556 void process_command(GCode *code,byte bufferedCommand);
00557 
00558 void manage_inactivity(byte debug);
00559 
00560 extern void wait_until_end_of_move();
00561 extern void update_ramps_parameter();
00562 extern void update_extruder_flags();
00563 extern void finishNextSegment();
00564 extern void printPosition();
00565 extern void defaultLoopActions();
00566 extern void change_feedrate_multiply(int factor); 
00567 extern void set_fan_speed(int speed,bool wait); 
00568 extern void home_axis(bool xaxis,bool yaxis,bool zaxis); 
00569 extern byte get_coordinates(GCode *com);
00570 extern void move_steps(long x,long y,long z,long e,float feedrate,bool waitEnd,bool check_endstop);
00571 extern void queue_move(byte check_endstops,byte pathOptimize);
00572 #if DRIVE_SYSTEM==3
00573 extern byte calculate_delta(long cartesianPosSteps[], long deltaPosSteps[]);
00574 extern void set_delta_position(long xaxis, long yaxis, long zaxis);
00575 extern float rodMaxLength;
00576 extern void split_delta_move(byte check_endstops,byte pathOptimize, byte softEndstop);
00577 #ifdef SOFTWARE_LEVELING
00578 extern void calculate_plane(long factors[], long p1[], long p2[], long p3[]);
00579 extern float calc_zoffset(long factors[], long pointX, long pointY);
00580 #endif
00581 #endif
00582 extern void linear_move(long steps_remaining[]);
00583 extern inline void disable_x();
00584 extern inline void disable_y();
00585 extern inline void disable_z();
00586 extern inline void enable_x();
00587 extern inline void enable_y();
00588 extern inline void enable_z();
00589 
00590 #define PREVIOUS_PLANNER_INDEX(p) {p--;if(p==255) p = MOVE_CACHE_SIZE-1;}
00591 #define NEXT_PLANNER_INDEX(idx) {++idx;if(idx==MOVE_CACHE_SIZE) idx=0;}
00592 
00593 extern void kill(byte only_steppers);
00594 
00595 extern float axis_steps_per_unit[];
00596 extern float inv_axis_steps_per_unit[];
00597 extern float max_feedrate[];
00598 extern float homing_feedrate[];
00599 extern float max_start_speed_units_per_second[];
00600 extern long max_acceleration_units_per_sq_second[];
00601 extern long max_travel_acceleration_units_per_sq_second[];
00602 extern unsigned long axis_steps_per_sqr_second[];
00603 extern unsigned long axis_travel_steps_per_sqr_second[];
00604 extern byte relative_mode;    
00605 extern byte relative_mode_e;  
00606 
00607 extern byte unit_inches;
00608 extern unsigned long previous_millis_cmd;
00609 extern unsigned long max_inactive_time;
00610 extern unsigned long stepper_inactive_time;
00611 
00612 extern void setupTimerInterrupt();
00613 extern void current_control_init();
00614 extern void microstep_init();
00615 extern void print_temperatures();
00616 extern void check_mem();
00617 #if ARC_SUPPORT
00618 extern void mc_arc(float *position, float *target, float *offset, float radius, uint8_t isclockwise);
00619 #endif
00620 
00621 #define PRINTER_FLAG0_STEPPER_DISABLED      1
00622 #define PRINTER_FLAG0_SEPERATE_EXTRUDER_INT 2
00623 #define PRINTER_FLAG0_TEMPSENSOR_DEFECT     4
00624 typedef struct { 
00625   byte flag0; // 1 = stepper disabled, 2 = use external extruder interrupt, 4 = temp Sensor defect 
00626 #if USE_OPS==1 || defined(USE_ADVANCE)
00627   volatile int extruderStepsNeeded; 
00628 //  float extruderSpeed;              ///< Extruder speed in mm/s.
00629   byte minExtruderSpeed;            
00630   byte maxExtruderSpeed;            
00631   byte extruderAccelerateDelay;     
00632 #endif
00633   long interval;                    
00634 #if USE_OPS==1
00635   bool filamentRetracted;           
00636 #endif
00637   unsigned long timer;              
00638   unsigned long stepNumber;         
00639 #ifdef USE_ADVANCE
00640 #ifdef ENABLE_QUADRATIC_ADVANCE
00641   long advance_executed;             
00642 #endif
00643   int advance_steps_set;
00644   unsigned int advance_lin_set;
00645 #endif
00646   long currentPositionSteps[4];     
00647   long destinationSteps[4];         
00648 #if DRIVE_SYSTEM==3
00649 #ifdef STEP_COUNTER
00650   long countZSteps;                                     
00651 #endif
00652   long currentDeltaPositionSteps[4];
00653   long maxDeltaPositionSteps;
00654 #endif
00655 #ifdef SOFTWARE_LEVELING
00656   long levelingP1[3];
00657   long levelingP2[3];
00658   long levelingP3[3];
00659 #endif
00660 #if USE_OPS==1
00661   int opsRetractSteps;              
00662   int opsPushbackSteps;             
00663   float opsMinDistance;
00664   float opsRetractDistance;
00665   float opsRetractBacklash;
00666   byte opsMode;                     
00667   float opsMoveAfter;               
00668   int opsMoveAfterSteps;            
00669 #endif
00670   long xMaxSteps;                   
00671   long yMaxSteps;                   
00672   long zMaxSteps;                   
00673   long xMinSteps;                   
00674   long yMinSteps;                   
00675   long zMinSteps;                   
00676   float xLength;
00677   float xMin;
00678   float yLength;
00679   float yMin;
00680   float zLength;
00681   float zMin;
00682   float feedrate;                   
00683   int feedrateMultiply;             
00684   unsigned int extrudeMultiply;     
00685   float maxJerk;                    
00686   float maxZJerk;                   
00687   long offsetX;                     
00688   long offsetY;                     
00689   unsigned int vMaxReached;         
00690   byte stepper_loops;
00691   unsigned long msecondsPrinting;            
00692   float filamentPrinted;            
00693   byte waslasthalfstepping;         
00694 #if ENABLE_BACKLASH_COMPENSATION
00695   float backlashX;
00696   float backlashY;
00697   float backlashZ;
00698   byte backlashDir;
00699 #endif
00700 #ifdef DEBUG_STEPCOUNT
00701   long totalStepsRemaining;
00702 #endif
00703 #if FEATURE_MEMORY_POSITION
00704   long memoryX;
00705   long memoryY;
00706   long memoryZ;
00707 #endif
00708 #ifdef XY_GANTRY
00709   char motorX;
00710   char motorY;
00711 #endif
00712 } PrinterState;
00713 extern PrinterState printer_state;
00714 
00716 #define FLAG_WARMUP 1
00717 #define FLAG_NOMINAL 2
00718 #define FLAG_DECELERATING 4
00719 #define FLAG_ACCELERATION_ENABLED 8
00720 #define FLAG_CHECK_ENDSTOPS 16
00721 #define FLAG_SKIP_ACCELERATING 32
00722 #define FLAG_SKIP_DEACCELERATING 64
00723 #define FLAG_BLOCKED 128
00724 
00726 #define FLAG_JOIN_STEPPARAMS_COMPUTED 1
00727 
00728 #define FLAG_JOIN_END_FIXED 2
00729 
00730 #define FLAG_JOIN_START_FIXED 4
00731 
00732 #define FLAG_JOIN_START_RETRACT 8
00733 
00734 #define FLAG_JOIN_END_RETRACT 16
00735 
00736 #define FLAG_JOIN_NO_RETRACT 32
00737 
00738 #define FLAG_JOIN_WAIT_EXTRUDER_UP 64
00739 
00740 #define FLAG_JOIN_WAIT_EXTRUDER_DOWN 128
00741 // Printing related data
00742 #if DRIVE_SYSTEM==3
00743 // Allow the delta cache to store segments for every line in line cache. Beware this gets big ... fast.
00744 // MAX_DELTA_SEGMENTS_PER_LINE * 
00745 #define DELTA_CACHE_SIZE (MAX_DELTA_SEGMENTS_PER_LINE * MOVE_CACHE_SIZE)
00746 typedef struct { 
00747         byte dir;                                                                       
00748         unsigned int deltaSteps[3];                             
00749 } DeltaSegment;
00750 extern DeltaSegment segments[];                                 // Delta segment cache
00751 extern unsigned int delta_segment_write_pos;    // Position where we write the next cached delta move
00752 extern volatile unsigned int delta_segment_count; // Number of delta moves cached 0 = nothing in cache
00753 extern byte lastMoveID;
00754 #endif
00755 typedef struct { // RAM usage: 24*4+15 = 113 Byte
00756   byte primaryAxis;
00757   volatile byte flags;
00758   long timeInTicks;
00759   byte joinFlags;
00760   byte halfstep;                  
00761   byte dir;                       
00762   long delta[4];                  
00763   long error[4];                  
00764   float speedX;                   
00765   float speedY;                   
00766   float speedZ;                   
00767   float speedE;                   
00768   float fullSpeed;                
00769   float invFullSpeed;             
00770   float acceleration;             
00771   float maxJunctionSpeed;         
00772   float startSpeed;               
00773   float endSpeed;                 
00774   float distance;
00775 #if DRIVE_SYSTEM==3
00776   byte numDeltaSegments;                                
00777   byte moveID;                                                  
00778   int deltaSegmentReadPos;                              
00779   long numPrimaryStepPerSegment;                
00780 #endif
00781   unsigned long fullInterval;     
00782   unsigned long stepsRemaining;   
00783   unsigned int accelSteps;        
00784   unsigned int decelSteps;        
00785   unsigned long accelerationPrim; 
00786   unsigned long facceleration;    
00787   unsigned int vMax;              
00788   unsigned int vStart;            
00789   unsigned int vEnd;              
00790 #ifdef USE_ADVANCE
00791 #ifdef ENABLE_QUADRATIC_ADVANCE
00792   long advanceRate;               
00793   long advanceFull;               
00794   long advanceStart;
00795   long advanceEnd;
00796 #endif
00797   unsigned int advanceL;         
00798 #endif
00799 #if USE_OPS==1
00800   long opsReverseSteps;           
00801 #endif
00802 #ifdef DEBUG_STEPCOUNT
00803   long totalStepsRemaining;
00804 #endif
00805 } PrintLine;
00806 
00807 extern PrintLine lines[];
00808 extern byte lines_write_pos; // Position where we write the next cached line move
00809 extern byte lines_pos; // Position for executing line movement
00810 extern volatile byte lines_count; // Number of lines cached 0 = nothing to do
00811 extern byte printmoveSeen;
00812 extern long baudrate;
00813 #if OS_ANALOG_INPUTS>0
00814 // Get last result for pin x
00815 extern volatile uint osAnalogInputValues[OS_ANALOG_INPUTS];
00816 #endif
00817 #define BEGIN_INTERRUPT_PROTECTED {byte sreg=SREG;__asm volatile( "cli" ::: "memory" );
00818 #define END_INTERRUPT_PROTECTED SREG=sreg;}
00819 #define ESCAPE_INTERRUPT_PROTECTED SREG=sreg;
00820 
00821 #define SECONDS_TO_TICKS(s) (unsigned long)(s*(float)F_CPU)
00822 extern long CPUDivU2(unsigned int divisor);
00823 
00824 extern unsigned int counter_periodical;
00825 extern volatile byte execute_periodical;
00826 extern byte counter_250ms;
00827 extern void write_monitor();
00828 extern void check_periodical();
00829 #define CELSIUS_EXTRA_BITS 3
00830 #define ANALOG_REDUCE_BITS 0
00831 #define ANALOG_REDUCE_FACTOR 1
00832 
00833 #if HAVE_HEATED_BED
00834 #define NUM_TEMPERATURE_LOOPS NUM_EXTRUDER+1
00835 extern TemperatureController heatedBedController;
00836 #else
00837 #define NUM_TEMPERATURE_LOOPS NUM_EXTRUDER
00838 #endif
00839 #define TEMP_INT_TO_FLOAT(temp) ((float)(temp)/(float)(1<<CELSIUS_EXTRA_BITS))
00840 #define TEMP_FLOAT_TO_INT(temp) ((int)((temp)*(1<<CELSIUS_EXTRA_BITS)))
00841 
00842 extern TemperatureController *tempController[NUM_TEMPERATURE_LOOPS];
00843 extern byte autotuneIndex;
00844 
00845 #if SDSUPPORT
00846 
00847 #define SD_MAX_FOLDER_DEPTH 2
00848 
00849 #include "SdFat.h"
00850 
00851 enum LsAction {LS_SerialPrint,LS_Count,LS_GetFilename};
00852 class SDCard {
00853 public:
00854   SdFat fat;
00855   //Sd2Card card; // ~14 Byte
00856   //SdVolume volume;
00857   //SdFile root;
00858   //SdFile dir[SD_MAX_FOLDER_DEPTH+1];
00859   SdFile file;
00860   uint32_t filesize;
00861   uint32_t sdpos;
00862   char fullName[13*SD_MAX_FOLDER_DEPTH+13]; // Fill name
00863   char *shortname; // Pointer to start of filename itself
00864   char *pathend; // File to char where pathname in fullname ends
00865   bool sdmode;  // true if we are printing from sd card
00866   bool sdactive;
00867   //int16_t n;
00868   bool savetosd;
00869   SDCard();
00870   void initsd();
00871   void write_command(GCode *code);
00872   void selectFile(char *filename);
00873   inline void mount() {
00874     sdmode = false;
00875     initsd();
00876   }
00877   inline void unmount() {
00878     sdmode = false;
00879     sdactive = false;
00880   }
00881   inline void startPrint() {if(sdactive) sdmode = true; }
00882   inline void pausePrint() {sdmode = false;}
00883   inline void setIndex(uint32_t  newpos) { if(!sdactive) return; sdpos = newpos;file.seekSet(sdpos);}
00884   void printStatus();
00885   void ls();
00886   void startWrite(char *filename);
00887   void deleteFile(char *filename);
00888   void finishWrite();
00889   char *createFilename(char *buffer,const dir_t &p);
00890   void makeDirectory(char *filename);
00891   bool showFilename(const uint8_t *name);
00892   void automount();
00893 private:
00894   void lsRecursive(SdBaseFile *parent,byte level);
00895  // SdFile *getDirectory(char* name);
00896 };
00897 
00898 extern SDCard sd;
00899 #endif
00900 
00901 extern int waitRelax; // Delay filament relax at the end of print, could be a simple timeout
00902 #ifdef USE_OPS
00903 extern byte printmoveSeen;
00904 #endif
00905 extern void updateStepsParameter(PrintLine *p/*,byte caller*/);
00906 
00908 inline void disable_x() {
00909 #if (X_ENABLE_PIN > -1)
00910   WRITE(X_ENABLE_PIN,!X_ENABLE_ON);
00911 #endif
00912 }
00914 inline void disable_y() {
00915 #if (Y_ENABLE_PIN > -1)
00916   WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON);
00917 #endif
00918 }
00920 inline void disable_z() {
00921 #if (Z_ENABLE_PIN > -1)
00922  WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON);
00923 #endif
00924 }
00926 inline void  enable_x() {
00927 #if (X_ENABLE_PIN > -1)
00928  WRITE(X_ENABLE_PIN, X_ENABLE_ON);
00929 #endif
00930 }
00932 inline void  enable_y() {
00933 #if (Y_ENABLE_PIN > -1)
00934   WRITE(Y_ENABLE_PIN, Y_ENABLE_ON);
00935 #endif
00936 }
00938 inline void  enable_z() {
00939 #if (Z_ENABLE_PIN > -1)
00940  WRITE(Z_ENABLE_PIN, Z_ENABLE_ON);
00941 #endif
00942 }
00943 
00944 
00945 #if DRIVE_SYSTEM==3
00946 #define SIN_60 0.8660254037844386
00947 #define COS_60 0.5
00948 #define DELTA_DIAGONAL_ROD_STEPS (AXIS_STEPS_PER_MM * DELTA_DIAGONAL_ROD)
00949 #define DELTA_DIAGONAL_ROD_STEPS_SQUARED (DELTA_DIAGONAL_ROD_STEPS * DELTA_DIAGONAL_ROD_STEPS)
00950 #define DELTA_ZERO_OFFSET_STEPS (AXIS_STEPS_PER_MM * DELTA_ZERO_OFFSET)
00951 #define DELTA_RADIUS_STEPS (AXIS_STEPS_PER_MM * DELTA_RADIUS)
00952 
00953 #define DELTA_TOWER1_X_STEPS -SIN_60*DELTA_RADIUS_STEPS
00954 #define DELTA_TOWER1_Y_STEPS -COS_60*DELTA_RADIUS_STEPS
00955 #define DELTA_TOWER2_X_STEPS SIN_60*DELTA_RADIUS_STEPS
00956 #define DELTA_TOWER2_Y_STEPS -COS_60*DELTA_RADIUS_STEPS
00957 #define DELTA_TOWER3_X_STEPS 0.0
00958 #define DELTA_TOWER3_Y_STEPS DELTA_RADIUS_STEPS
00959 
00960 #define NUM_AXIS 4
00961 #define X_AXIS 0
00962 #define Y_AXIS 1
00963 #define Z_AXIS 2
00964 #define E_AXIS 3
00965 
00966 #endif
00967 
00968 #define STR(s) #s
00969 #define XSTR(s) STR(s)
00970 
00971 #endif
 All Data Structures Namespaces Files Functions Variables Typedefs Friends Defines