Merge branch 'Marlin_v1' of https://github.com/ErikZalm/Marlin into Marlin_v1

This commit is contained in:
Bernhard 2011-12-22 09:22:39 +01:00
commit 4bababf5b0
14 changed files with 5873 additions and 5599 deletions

View file

@ -43,16 +43,20 @@
// 5 is ParCan supplied 104GT-2 100K // 5 is ParCan supplied 104GT-2 100K
// 6 is EPCOS 100k // 6 is EPCOS 100k
// 7 is 100k Honeywell thermistor 135-104LAG-J01 // 7 is 100k Honeywell thermistor 135-104LAG-J01
//#define THERMISTORHEATER_0 3 //#define THERMISTORHEATER_0 3
//#define THERMISTORHEATER_1 3 //#define THERMISTORHEATER_1 1
//#define THERMISTORBED 3 //#define THERMISTORHEATER_2 1
//#define HEATER_0_USES_THERMISTOR //#define HEATER_0_USES_THERMISTOR
//#define HEATER_1_USES_THERMISTOR //#define HEATER_1_USES_THERMISTOR
//#define HEATER_2_USES_THERMISTOR
#define HEATER_0_USES_AD595 #define HEATER_0_USES_AD595
//#define HEATER_1_USES_AD595 //#define HEATER_1_USES_AD595
//#define HEATER_2_USES_AD595
// Select one of these only to define how the bed temp is read. // Select one of these only to define how the bed temp is read.
//#define THERMISTORBED 1
//#define BED_USES_THERMISTOR //#define BED_USES_THERMISTOR
//#define BED_USES_AD595 //#define BED_USES_AD595
@ -65,12 +69,13 @@
//#define WATCHPERIOD 20000 //20 seconds //#define WATCHPERIOD 20000 //20 seconds
// Actual temperature must be close to target for this long before M109 returns success // Actual temperature must be close to target for this long before M109 returns success
//#define TEMP_RESIDENCY_TIME 20 // (seconds) #define TEMP_RESIDENCY_TIME 30 // (seconds)
//#define TEMP_HYSTERESIS 5 // (C°) range of +/- temperatures considered "close" to the target one #define TEMP_HYSTERESIS 3 // (C°) range of +/- temperatures considered "close" to the target one
//// The minimal temperature defines the temperature below which the heater will not be enabled //// The minimal temperature defines the temperature below which the heater will not be enabled
#define HEATER_0_MINTEMP 5 #define HEATER_0_MINTEMP 5
//#define HEATER_1_MINTEMP 5 //#define HEATER_1_MINTEMP 5
//#define HEATER_2_MINTEMP 5
//#define BED_MINTEMP 5 //#define BED_MINTEMP 5
@ -79,6 +84,7 @@
// You should use MINTEMP for thermistor short/failure protection. // You should use MINTEMP for thermistor short/failure protection.
#define HEATER_0_MAXTEMP 275 #define HEATER_0_MAXTEMP 275
//#define HEATER_1_MAXTEMP 275 //#define HEATER_1_MAXTEMP 275
//#define HEATER_2_MAXTEMP 275
//#define BED_MAXTEMP 150 //#define BED_MAXTEMP 150
@ -90,21 +96,17 @@
// Heating is finished if a temperature close to this degree shift is reached // Heating is finished if a temperature close to this degree shift is reached
#define HEATING_EARLY_FINISH_DEG_OFFSET 1 //Degree #define HEATING_EARLY_FINISH_DEG_OFFSET 1 //Degree
// PID settings: // PID settings:
// Uncomment the following line to enable PID support. // Uncomment the following line to enable PID support.
#define PIDTEMP #define PIDTEMP
#define PID_MAX 255 // limits current to nozzle; 255=full current
#ifdef PIDTEMP #ifdef PIDTEMP
#if MOTHERBOARD == 62
#error Sanguinololu does not support PID, sorry. Please disable it.
#endif
//#define PID_DEBUG // Sends debug data to the serial port. //#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104 sets the output power in % //#define PID_OPENLOOP 1 // Puts PID in open loop. M104 sets the output power in %
#define PID_MAX 255 // limits current to nozzle; 255=full current
#define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term #define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
#define K1 0.95 //smoothing factor withing the PID #define K1 0.95 //smoothing factor withing the PID
#define PID_dT 0.1 //sampling period of the PID #define PID_dT 0.128 //sampling period of the PID
//To develop some PID settings for your machine, you can initiall follow //To develop some PID settings for your machine, you can initiall follow
// the Ziegler-Nichols method. // the Ziegler-Nichols method.
@ -132,6 +134,11 @@
#define DEFAULT_Ki (1.25*PID_dT) #define DEFAULT_Ki (1.25*PID_dT)
#define DEFAULT_Kd (99/PID_dT) #define DEFAULT_Kd (99/PID_dT)
// Makergear
// #define DEFAULT_Kp 7.0
// #define DEFAULT_Ki 0.1
// #define DEFAULT_Kd 12
// Mendel Parts V9 on 12V // Mendel Parts V9 on 12V
// #define DEFAULT_Kp 63.0 // #define DEFAULT_Kp 63.0
// #define DEFAULT_Ki (2.25*PID_dT) // #define DEFAULT_Ki (2.25*PID_dT)
@ -149,7 +156,7 @@
// if Kc is choosen well, the additional required power due to increased melting should be compensated. // if Kc is choosen well, the additional required power due to increased melting should be compensated.
#define PID_ADD_EXTRUSION_RATE #define PID_ADD_EXTRUSION_RATE
#ifdef PID_ADD_EXTRUSION_RATE #ifdef PID_ADD_EXTRUSION_RATE
#define DEFAULT_Kc (3) //heatingpower=Kc*(e_speed) #define DEFAULT_Kc (1) //heatingpower=Kc*(e_speed)
#endif #endif
#endif // PIDTEMP #endif // PIDTEMP
@ -169,36 +176,39 @@
// Endstop Settings // Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors #define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins. // The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
// For optos H21LOB set to true, for Mendel-Parts newer optos TCST2103 set to false // For optos H21LOB set to true, for Mendel-Parts newer optos TCST2103 set to false
//#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing #define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 0 #define X_ENABLE_ON 0
#define Y_ENABLE_ON 0 #define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0 #define Z_ENABLE_ON 0
#define E_ENABLE_ON 0 #define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used. // Disables axis when it's not being used.
#define DISABLE_X false #define DISABLE_X false
#define DISABLE_Y false #define DISABLE_Y false
#define DISABLE_Z false #define DISABLE_Z false
#define DISABLE_E false #define DISABLE_E false // For all extruders
// Inverting axis direction // Inverting axis direction
//#define INVERT_X_DIR false // for Mendel set to false, for Orca set to true //#define INVERT_X_DIR false // for Mendel set to false, for Orca set to true
//#define INVERT_Y_DIR true // for Mendel set to true, for Orca set to false //#define INVERT_Y_DIR true // for Mendel set to true, for Orca set to false
//#define INVERT_Z_DIR false // for Mendel set to false, for Orca set to true //#define INVERT_Z_DIR false // for Mendel set to false, for Orca set to true
//#define INVERT_E_DIR true // for direct drive extruder v9 set to true, for geared extruder set to false //#define INVERT_E*_DIR true // for direct drive extruder v9 set to true, for geared extruder set to false, used for all extruders
#define INVERT_X_DIR true // for Mendel set to false, for Orca set to true #define INVERT_X_DIR true // for Mendel set to false, for Orca set to true
#define INVERT_Y_DIR false // for Mendel set to true, for Orca set to false #define INVERT_Y_DIR false // for Mendel set to true, for Orca set to false
#define INVERT_Z_DIR true // for Mendel set to false, for Orca set to true #define INVERT_Z_DIR true // for Mendel set to false, for Orca set to true
#define INVERT_E_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false #define INVERT_E0_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E1_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E2_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
//// ENDSTOP SETTINGS: //// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN // Sets direction of endstops when homing; 1=MAX, -1=MIN
@ -206,11 +216,11 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
#define Y_HOME_DIR -1 #define Y_HOME_DIR -1
#define Z_HOME_DIR -1 #define Z_HOME_DIR -1
#define min_software_endstops false //If true, axis won't move to coordinates less than zero. #define min_software_endstops true //If true, axis won't move to coordinates less than zero.
#define max_software_endstops false //If true, axis won't move to coordinates greater than the defined lengths below. #define max_software_endstops true //If true, axis won't move to coordinates greater than the defined lengths below.
#define X_MAX_LENGTH 210 #define X_MAX_LENGTH 205
#define Y_MAX_LENGTH 210 #define Y_MAX_LENGTH 205
#define Z_MAX_LENGTH 210 #define Z_MAX_LENGTH 200
//// MOVEMENT SETTINGS //// MOVEMENT SETTINGS
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E #define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
@ -229,7 +239,8 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
// default settings // default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200*8/3,760*1.1} // default steps per unit for ultimaker #define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200*8/3,760*1.1} // default steps per unit for ultimaker
//#define DEFAULT_AXIS_STEPS_PER_UNIT {40, 40, 3333.92, 67} //sells mendel with v9 extruder //#define DEFAULT_AXIS_STEPS_PER_UNIT {40, 40, 3333.92, 360} //sells mendel with v9 extruder
//#define DEFAULT_AXIS_STEPS_PER_UNIT {80.3232, 80.8900, 2284.7651, 757.2218} // SAE Prusa w/ Wade extruder
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 45} // (mm/sec) #define DEFAULT_MAX_FEEDRATE {500, 500, 5, 45} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot. #define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
@ -285,10 +296,10 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
// hooke's law says: force = k * distance // hooke's law says: force = k * distance
// bernoulli's priniciple says: v ^ 2 / 2 + g . h + pressure / density = constant // bernoulli's priniciple says: v ^ 2 / 2 + g . h + pressure / density = constant
// so: v ^ 2 is proportional to number of steps we advance the extruder // so: v ^ 2 is proportional to number of steps we advance the extruder
//#define ADVANCE #define ADVANCE
#ifdef ADVANCE #ifdef ADVANCE
#define EXTRUDER_ADVANCE_K .3 #define EXTRUDER_ADVANCE_K .0
#define D_FILAMENT 2.85 #define D_FILAMENT 2.85
#define STEPS_MM_E 836 #define STEPS_MM_E 836
@ -304,7 +315,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers? #define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
#define SD_FINISHED_RELEASECOMMAND "M84 X Y E" // no z because of layer shift. #define SD_FINISHED_RELEASECOMMAND "M84 X Y E" // no z because of layer shift.
//#define ULTIPANEL #define ULTIPANEL
#ifdef ULTIPANEL #ifdef ULTIPANEL
//#define NEWPANEL //enable this if you have a click-encoder panel //#define NEWPANEL //enable this if you have a click-encoder panel
#define SDSUPPORT #define SDSUPPORT

View file

@ -101,14 +101,31 @@ void manage_inactivity(byte debug);
#define disable_z() ; #define disable_z() ;
#endif #endif
#if E_ENABLE_PIN > -1 #if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
#define enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON) #define enable_e0() WRITE(E0_ENABLE_PIN, E_ENABLE_ON)
#define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON) #define disable_e0() WRITE(E0_ENABLE_PIN,!E_ENABLE_ON)
#else #else
#define enable_e() ; #define enable_e0() /* nothing */
#define disable_e() ; #define disable_e0() /* nothing */
#endif #endif
#if (EXTRUDERS > 1) && defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
#define enable_e1() WRITE(E1_ENABLE_PIN, E_ENABLE_ON)
#define disable_e1() WRITE(E1_ENABLE_PIN,!E_ENABLE_ON)
#else
#define enable_e1() /* nothing */
#define disable_e1() /* nothing */
#endif
#if (EXTRUDERS > 2) && defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
#define enable_e2() WRITE(E2_ENABLE_PIN, E_ENABLE_ON)
#define disable_e2() WRITE(E2_ENABLE_PIN,!E_ENABLE_ON)
#else
#define enable_e2() /* nothing */
#define disable_e2() /* nothing */
#endif
enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3}; enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3};
@ -133,4 +150,7 @@ extern float current_position[NUM_AXIS] ;
extern float add_homeing[3]; extern float add_homeing[3];
extern bool stop_heating_wait; extern bool stop_heating_wait;
// Handling multiple extruders pins
extern uint8_t active_extruder;
#endif #endif

View file

@ -122,7 +122,6 @@
//=========================================================================== //===========================================================================
//=============================imported variables============================ //=============================imported variables============================
//=========================================================================== //===========================================================================
extern float HeaterPower;
//=========================================================================== //===========================================================================
@ -136,9 +135,11 @@ bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
volatile int feedmultiply=100; //100->1 200->2 volatile int feedmultiply=100; //100->1 200->2
int saved_feedmultiply; int saved_feedmultiply;
volatile bool feedmultiplychanged=false; volatile bool feedmultiplychanged=false;
float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0}; float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
float add_homeing[3]={0,0,0}; float add_homeing[3]={0,0,0};
uint8_t active_extruder = 0;
bool stop_heating_wait=false; bool stop_heating_wait=false;
//=========================================================================== //===========================================================================
//=============================private variables============================= //=============================private variables=============================
//=========================================================================== //===========================================================================
@ -470,16 +471,16 @@ FORCE_INLINE bool code_seen(char code)
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); \ plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); \
destination[LETTER##_AXIS] = 1.5 * LETTER##_MAX_LENGTH * LETTER##_HOME_DIR; \ destination[LETTER##_AXIS] = 1.5 * LETTER##_MAX_LENGTH * LETTER##_HOME_DIR; \
feedrate = homing_feedrate[LETTER##_AXIS]; \ feedrate = homing_feedrate[LETTER##_AXIS]; \
prepare_move(); \ plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
\ \
current_position[LETTER##_AXIS] = 0;\ current_position[LETTER##_AXIS] = 0;\
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);\ plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);\
destination[LETTER##_AXIS] = -LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\ destination[LETTER##_AXIS] = -LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\
prepare_move(); \ plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
\ \
destination[LETTER##_AXIS] = 2*LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\ destination[LETTER##_AXIS] = 2*LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\
feedrate = homing_feedrate[LETTER##_AXIS]/2 ; \ feedrate = homing_feedrate[LETTER##_AXIS]/2 ; \
prepare_move(); \ plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
\ \
current_position[LETTER##_AXIS] = (LETTER##_HOME_DIR == -1) ? 0 : LETTER##_MAX_LENGTH;\ current_position[LETTER##_AXIS] = (LETTER##_HOME_DIR == -1) ? 0 : LETTER##_MAX_LENGTH;\
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);\ plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);\
@ -543,6 +544,7 @@ FORCE_INLINE void process_commands()
if( code_seen(axis_codes[0]) && code_seen(axis_codes[1]) ) //first diagonal move if( code_seen(axis_codes[0]) && code_seen(axis_codes[1]) ) //first diagonal move
{ {
current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0; current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
destination[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR; destination[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR;
feedrate = homing_feedrate[X_AXIS]; feedrate = homing_feedrate[X_AXIS];
@ -582,7 +584,7 @@ FORCE_INLINE void process_commands()
} }
if(code_seen(axis_codes[Y_AXIS])) { if(code_seen(axis_codes[Y_AXIS])) {
current_position[1]=code_value()+add_homeing[1]; current_position[1]=code_value()+add_homeing[1];
} }
if(code_seen(axis_codes[Z_AXIS])) { if(code_seen(axis_codes[Z_AXIS])) {
@ -610,9 +612,11 @@ FORCE_INLINE void process_commands()
if(code_seen(axis_codes[i])) { if(code_seen(axis_codes[i])) {
current_position[i] = code_value()+add_homeing[i]; current_position[i] = code_value()+add_homeing[i];
if(i == E_AXIS) { if(i == E_AXIS) {
current_position[i] = code_value();
plan_set_e_position(current_position[E_AXIS]); plan_set_e_position(current_position[E_AXIS]);
} }
else { else {
current_position[i] = code_value()+add_homeing[i];
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
} }
} }
@ -623,7 +627,6 @@ FORCE_INLINE void process_commands()
else if(code_seen('M')) else if(code_seen('M'))
{ {
switch( (int)code_value() ) switch( (int)code_value() )
{ {
case 17: case 17:
@ -631,10 +634,12 @@ FORCE_INLINE void process_commands()
enable_x(); enable_x();
enable_y(); enable_y();
enable_z(); enable_z();
enable_e(); enable_e0();
enable_e1();
enable_e2();
break; break;
#ifdef SDSUPPORT
#ifdef SDSUPPORT
case 20: // M20 - list SD card case 20: // M20 - list SD card
SERIAL_PROTOCOLLNPGM("Begin file list"); SERIAL_PROTOCOLLNPGM("Begin file list");
card.ls(); card.ls();
@ -663,9 +668,8 @@ FORCE_INLINE void process_commands()
card.pauseSDPrint(); card.pauseSDPrint();
break; break;
case 26: //M26 - Set SD index case 26: //M26 - Set SD index
if(card.cardOK && code_seen('S')){ if(card.cardOK && code_seen('S')) {
card.setIndex(code_value_long()); card.setIndex(code_value_long());
} }
break; break;
case 27: //M27 - Get SD status case 27: //M27 - Get SD status
@ -679,16 +683,15 @@ FORCE_INLINE void process_commands()
*(starpos-1) = '\0'; *(starpos-1) = '\0';
} }
card.openFile(strchr_pointer+4,false); card.openFile(strchr_pointer+4,false);
break; break;
case 29: //M29 - Stop SD write case 29: //M29 - Stop SD write
//processed in write to file routine above //processed in write to file routine above
//card,saving = false; //card,saving = false;
break; break;
#endif //SDSUPPORT #endif //SDSUPPORT
case 30: //M30 take time since the start of the SD print or an M109 command case 30: //M30 take time since the start of the SD print or an M109 command
{ {
stoptime=millis(); stoptime=millis();
char time[30]; char time[30];
unsigned long t=(stoptime-starttime)/1000; unsigned long t=(stoptime-starttime)/1000;
@ -700,8 +703,8 @@ FORCE_INLINE void process_commands()
SERIAL_ECHOLN(time); SERIAL_ECHOLN(time);
LCD_MESSAGE(time); LCD_MESSAGE(time);
autotempShutdown(); autotempShutdown();
} }
break; break;
case 42: //M42 -Change pin status via gcode case 42: //M42 -Change pin status via gcode
if (code_seen('S')) if (code_seen('S'))
{ {
@ -755,21 +758,20 @@ FORCE_INLINE void process_commands()
break; break;
} }
} }
#if (TEMP_0_PIN > -1) || (TEMP_2_PIN > -1) #if (TEMP_0_PIN > -1)
SERIAL_PROTOCOLPGM("ok T:"); SERIAL_PROTOCOLPGM("ok T:");
SERIAL_PROTOCOL( degHotend(tmp_extruder)); SERIAL_PROTOCOL(degHotend(tmp_extruder));
#if TEMP_1_PIN > -1 #if TEMP_BED_PIN > -1
SERIAL_PROTOCOLPGM(" B:"); SERIAL_PROTOCOLPGM(" B:");
SERIAL_PROTOCOL(degBed()); SERIAL_PROTOCOL(degBed());
#endif //TEMP_1_PIN #endif //TEMP_BED_PIN
#else #else
SERIAL_ERROR_START; SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("No thermistors - no temp"); SERIAL_ERRORLNPGM("No thermistors - no temp");
#endif #endif
#ifdef PIDTEMP #ifdef PIDTEMP
SERIAL_PROTOCOLPGM(" @:"); SERIAL_PROTOCOLPGM(" @:");
SERIAL_PROTOCOL( HeaterPower); SERIAL_PROTOCOL(getHeaterPower(tmp_extruder));
#endif #endif
SERIAL_PROTOCOLLN(""); SERIAL_PROTOCOLLN("");
return; return;
@ -812,19 +814,33 @@ FORCE_INLINE void process_commands()
residencyStart = -1; residencyStart = -1;
/* continue to loop until we have reached the target temp /* continue to loop until we have reached the target temp
_and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */ _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
while((target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder))) || while((residencyStart == -1) ||
(residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) { (residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
#else #else
while ( target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder)&&(CooldownNoWait==false)) ) { while ( target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder)&&(CooldownNoWait==false)) ) {
#endif //TEMP_RESIDENCY_TIME #endif //TEMP_RESIDENCY_TIME
if( (millis() - codenum) > 1000 ) if( (millis() - codenum) > 1000 )
{ //Print Temp Reading every 1 second while heating up/cooling down { //Print Temp Reading and remaining time every 1 second while heating up/cooling down
SERIAL_PROTOCOLPGM("T:"); SERIAL_PROTOCOLPGM("T:");
SERIAL_PROTOCOLLN( degHotend(tmp_extruder) ); SERIAL_PROTOCOL( degHotend(tmp_extruder) );
codenum = millis(); SERIAL_PROTOCOLPGM(" E:");
} SERIAL_PROTOCOL( (int)tmp_extruder );
manage_heater(); #ifdef TEMP_RESIDENCY_TIME
LCD_STATUS; SERIAL_PROTOCOLPGM(" W:");
if(residencyStart > -1)
{
codenum = TEMP_RESIDENCY_TIME - ((millis() - residencyStart) / 1000);
SERIAL_PROTOCOLLN( codenum );
}
else
{
SERIAL_PROTOCOLLN( "?" );
}
#endif
codenum = millis();
}
manage_heater();
LCD_STATUS;
if(stop_heating_wait) break; if(stop_heating_wait) break;
#ifdef TEMP_RESIDENCY_TIME #ifdef TEMP_RESIDENCY_TIME
/* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
@ -842,8 +858,8 @@ FORCE_INLINE void process_commands()
previous_millis_cmd = millis(); previous_millis_cmd = millis();
} }
break; break;
case 190: // M190 - Wait bed for heater to reach target. case 190: // M190 - Wait for bed heater to reach target.
#if TEMP_1_PIN > -1 #if TEMP_BED_PIN > -1
LCD_MESSAGEPGM("Bed Heating."); LCD_MESSAGEPGM("Bed Heating.");
if (code_seen('S')) setTargetBed(code_value()); if (code_seen('S')) setTargetBed(code_value());
codenum = millis(); codenum = millis();
@ -851,13 +867,13 @@ FORCE_INLINE void process_commands()
{ {
if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up. if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
{ {
float tt=degHotend0(); float tt=degHotend(active_extruder);
SERIAL_PROTOCOLPGM("T:"); SERIAL_PROTOCOLPGM("T:");
SERIAL_PROTOCOLLN(tt ); SERIAL_PROTOCOL(tt);
SERIAL_PROTOCOLPGM("ok T:"); SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOL(tt ); SERIAL_PROTOCOL( (int)active_extruder );
SERIAL_PROTOCOLPGM(" B:"); SERIAL_PROTOCOLPGM(" B:");
SERIAL_PROTOCOLLN(degBed() ); SERIAL_PROTOCOLLN(degBed());
codenum = millis(); codenum = millis();
} }
manage_heater(); manage_heater();
@ -910,6 +926,9 @@ FORCE_INLINE void process_commands()
bool all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2]))|| (code_seen(axis_codes[3]))); bool all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2]))|| (code_seen(axis_codes[3])));
if(all_axis) if(all_axis)
{ {
disable_e0();
disable_e1();
disable_e2();
finishAndDisableSteppers(); finishAndDisableSteppers();
} }
else else
@ -918,8 +937,12 @@ FORCE_INLINE void process_commands()
if(code_seen('X')) disable_x(); if(code_seen('X')) disable_x();
if(code_seen('Y')) disable_y(); if(code_seen('Y')) disable_y();
if(code_seen('Z')) disable_z(); if(code_seen('Z')) disable_z();
#if ((E_ENABLE_PIN != X_ENABLE_PIN) && (E_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS #if ((E0_ENABLE_PIN != X_ENABLE_PIN) && (E1_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS
if(code_seen('E')) disable_e(); if(code_seen('E')) {
disable_e0();
disable_e1();
disable_e2();
}
#endif #endif
LCD_MESSAGEPGM("Partial Release"); LCD_MESSAGEPGM("Partial Release");
} }
@ -1100,7 +1123,9 @@ FORCE_INLINE void process_commands()
} }
} }
else if(code_seen('T')) {
else if(code_seen('T'))
{
tmp_extruder = code_value(); tmp_extruder = code_value();
if(tmp_extruder >= EXTRUDERS) { if(tmp_extruder >= EXTRUDERS) {
SERIAL_ECHO_START; SERIAL_ECHO_START;
@ -1110,8 +1135,12 @@ FORCE_INLINE void process_commands()
} }
else { else {
active_extruder = tmp_extruder; active_extruder = tmp_extruder;
SERIAL_ECHO_START;
SERIAL_ECHO("Active Extruder: ");
SERIAL_PROTOCOLLN((int)active_extruder);
} }
} }
else else
{ {
SERIAL_ECHO_START; SERIAL_ECHO_START;
@ -1219,8 +1248,8 @@ void manage_inactivity(byte debug)
if( (millis()-previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 ) if( (millis()-previous_millis_cmd) > EXTRUDER_RUNOUT_SECONDS*1000 )
if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP) if(degHotend(active_extruder)>EXTRUDER_RUNOUT_MINTEMP)
{ {
bool oldstatus=READ(E_ENABLE_PIN); bool oldstatus=READ(E0_ENABLE_PIN);
enable_e(); enable_e0();
float oldepos=current_position[E_AXIS]; float oldepos=current_position[E_AXIS];
float oldedes=destination[E_AXIS]; float oldedes=destination[E_AXIS];
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS],
@ -1232,7 +1261,7 @@ void manage_inactivity(byte debug)
previous_millis_cmd=millis(); previous_millis_cmd=millis();
//enquecommand(DEFAULT_STEPPER_DEACTIVE_COMMAND); //enquecommand(DEFAULT_STEPPER_DEACTIVE_COMMAND);
st_synchronize(); st_synchronize();
WRITE(E_ENABLE_PIN,oldstatus); WRITE(E0_ENABLE_PIN,oldstatus);
} }
#endif #endif
check_axes_activity(); check_axes_activity();
@ -1240,12 +1269,15 @@ void manage_inactivity(byte debug)
void kill() void kill()
{ {
cli(); // Stop interrupts
disable_heater(); disable_heater();
disable_x(); disable_x();
disable_y(); disable_y();
disable_z(); disable_z();
disable_e(); disable_e0();
disable_e1();
disable_e2();
if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT); if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
SERIAL_ERROR_START; SERIAL_ERROR_START;

View file

@ -442,4 +442,4 @@ void CardReader::printingHasFinished()
} }
autotempShutdown(); autotempShutdown();
} }
#endif //SDSUPPORT #endif //SDSUPPORT

View file

@ -1,2559 +1,2582 @@
/* /*
This code contibuted by Triffid_Hunter and modified by Kliment This code contibuted by Triffid_Hunter and modified by Kliment
why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
*/ */
#ifndef _ARDUINO_H #ifndef _ARDUINO_H
#define _ARDUINO_H #define _ARDUINO_H
#include <avr/io.h> #include <avr/io.h>
/* /*
utility functions utility functions
*/ */
#ifndef MASK #ifndef MASK
/// MASKING- returns \f$2^PIN\f$ /// MASKING- returns \f$2^PIN\f$
#define MASK(PIN) (1 << PIN) #define MASK(PIN) (1 << PIN)
#endif #endif
/* /*
magic I/O routines magic I/O routines
now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0);
now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0); */
*/
/// Read a pin
/// Read a pin #define _READ(IO) ((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN)))
#define _READ(IO) ((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN))) /// write to a pin
/// write to a pin // On some boards pins > 0x100 are used. These are not converted to atomic actions. An critical section is needed.
#define _WRITE(IO, v) do { if (v) {DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }; } while (0)
//#define _WRITE(IO, v) do { #if (DIO ## IO ## _WPORT >= 0x100) CRITICAL_SECTION_START; if (v) {DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); };#if (DIO ## IO ## _WPORT >= 0x100) CRITICAL_SECTION_END; } while (0) #define _WRITE_NC(IO, v) do { if (v) {DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }; } while (0)
/// toggle a pin
#define _TOGGLE(IO) do {DIO ## IO ## _RPORT = MASK(DIO ## IO ## _PIN); } while (0) #define _WRITE_C(IO, v) do { if (v) { \
CRITICAL_SECTION_START; \
/// set pin as input {DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); }\
#define _SET_INPUT(IO) do {DIO ## IO ## _DDR &= ~MASK(DIO ## IO ## _PIN); } while (0) CRITICAL_SECTION_END; \
/// set pin as output }\
#define _SET_OUTPUT(IO) do {DIO ## IO ## _DDR |= MASK(DIO ## IO ## _PIN); } while (0) else {\
CRITICAL_SECTION_START; \
/// check if pin is an input {DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }\
#define _GET_INPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) == 0) CRITICAL_SECTION_END; \
/// check if pin is an output }\
#define _GET_OUTPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) != 0) }\
while (0)
// why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
#define _WRITE(IO, v) do { if (&(DIO ## IO ## _RPORT) >= (uint8_t *)0x100) {_WRITE_C(IO, v); } else {_WRITE_NC(IO, v); }; } while (0)
/// Read a pin wrapper
#define READ(IO) _READ(IO) /// toggle a pin
/// Write to a pin wrapper #define _TOGGLE(IO) do {DIO ## IO ## _RPORT = MASK(DIO ## IO ## _PIN); } while (0)
#define WRITE(IO, v) _WRITE(IO, v)
/// toggle a pin wrapper /// set pin as input
#define TOGGLE(IO) _TOGGLE(IO) #define _SET_INPUT(IO) do {DIO ## IO ## _DDR &= ~MASK(DIO ## IO ## _PIN); } while (0)
/// set pin as output
/// set pin as input wrapper #define _SET_OUTPUT(IO) do {DIO ## IO ## _DDR |= MASK(DIO ## IO ## _PIN); } while (0)
#define SET_INPUT(IO) _SET_INPUT(IO)
/// set pin as output wrapper /// check if pin is an input
#define SET_OUTPUT(IO) _SET_OUTPUT(IO) #define _GET_INPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) == 0)
/// check if pin is an output
/// check if pin is an input wrapper #define _GET_OUTPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) != 0)
#define GET_INPUT(IO) _GET_INPUT(IO)
/// check if pin is an output wrapper /// check if pin is an timer
#define GET_OUTPUT(IO) _GET_OUTPUT(IO) #define _GET_TIMER(IO) ((DIO ## IO ## _PWM)
/* // why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
ports and functions
/// Read a pin wrapper
added as necessary or if I feel like it- not a comprehensive list! #define READ(IO) _READ(IO)
*/ /// Write to a pin wrapper
#define WRITE(IO, v) _WRITE(IO, v)
#if defined (__AVR_ATmega168__) || defined (__AVR_ATmega328__) || defined (__AVR_ATmega328P__)
// UART /// toggle a pin wrapper
#define RXD DIO0 #define TOGGLE(IO) _TOGGLE(IO)
#define TXD DIO1
/// set pin as input wrapper
// SPI #define SET_INPUT(IO) _SET_INPUT(IO)
#define SCK DIO13 /// set pin as output wrapper
#define MISO DIO12 #define SET_OUTPUT(IO) _SET_OUTPUT(IO)
#define MOSI DIO11
#define SS DIO10 /// check if pin is an input wrapper
#define GET_INPUT(IO) _GET_INPUT(IO)
// TWI (I2C) /// check if pin is an output wrapper
#define SCL AIO5 #define GET_OUTPUT(IO) _GET_OUTPUT(IO)
#define SDA AIO4
/// check if pin is an timer wrapper
// timers and PWM #define GET_TIMER(IO) _GET_TIMER(IO)
#define OC0A DIO6
#define OC0B DIO5 /*
#define OC1A DIO9 ports and functions
#define OC1B DIO10
#define OC2A DIO11 added as necessary or if I feel like it- not a comprehensive list!
#define OC2B DIO3 */
#define DEBUG_LED AIO5 #if defined (__AVR_ATmega168__) || defined (__AVR_ATmega328__) || defined (__AVR_ATmega328P__)
// UART
/* #define RXD DIO0
pins #define TXD DIO1
*/
// SPI
#define DIO0_PIN PIND0 #define SCK DIO13
#define DIO0_RPORT PIND #define MISO DIO12
#define DIO0_WPORT PORTD #define MOSI DIO11
#define DIO0_DDR DDRD #define SS DIO10
#define DIO0_PWM NULL
// TWI (I2C)
#define DIO1_PIN PIND1 #define SCL AIO5
#define DIO1_RPORT PIND #define SDA AIO4
#define DIO1_WPORT PORTD
#define DIO1_DDR DDRD // timers and PWM
#define DIO1_PWM NULL #define OC0A DIO6
#define OC0B DIO5
#define DIO2_PIN PIND2 #define OC1A DIO9
#define DIO2_RPORT PIND #define OC1B DIO10
#define DIO2_WPORT PORTD #define OC2A DIO11
#define DIO2_DDR DDRD #define OC2B DIO3
#define DIO2_PWM NULL
#define DEBUG_LED AIO5
#define DIO3_PIN PIND3
#define DIO3_RPORT PIND /*
#define DIO3_WPORT PORTD pins
#define DIO3_DDR DDRD */
#define DIO3_PWM &OCR2B
#define DIO0_PIN PIND0
#define DIO4_PIN PIND4 #define DIO0_RPORT PIND
#define DIO4_RPORT PIND #define DIO0_WPORT PORTD
#define DIO4_WPORT PORTD #define DIO0_DDR DDRD
#define DIO4_DDR DDRD #define DIO0_PWM NULL
#define DIO4_PWM NULL
#define DIO1_PIN PIND1
#define DIO5_PIN PIND5 #define DIO1_RPORT PIND
#define DIO5_RPORT PIND #define DIO1_WPORT PORTD
#define DIO5_WPORT PORTD #define DIO1_DDR DDRD
#define DIO5_DDR DDRD #define DIO1_PWM NULL
#define DIO5_PWM &OCR0B
#define DIO2_PIN PIND2
#define DIO6_PIN PIND6 #define DIO2_RPORT PIND
#define DIO6_RPORT PIND #define DIO2_WPORT PORTD
#define DIO6_WPORT PORTD #define DIO2_DDR DDRD
#define DIO6_DDR DDRD #define DIO2_PWM NULL
#define DIO6_PWM &OCR0A
#define DIO3_PIN PIND3
#define DIO7_PIN PIND7 #define DIO3_RPORT PIND
#define DIO7_RPORT PIND #define DIO3_WPORT PORTD
#define DIO7_WPORT PORTD #define DIO3_DDR DDRD
#define DIO7_DDR DDRD #define DIO3_PWM &OCR2B
#define DIO7_PWM NULL
#define DIO4_PIN PIND4
#define DIO8_PIN PINB0 #define DIO4_RPORT PIND
#define DIO8_RPORT PINB #define DIO4_WPORT PORTD
#define DIO8_WPORT PORTB #define DIO4_DDR DDRD
#define DIO8_DDR DDRB #define DIO4_PWM NULL
#define DIO8_PWM NULL
#define DIO5_PIN PIND5
#define DIO9_PIN PINB1 #define DIO5_RPORT PIND
#define DIO9_RPORT PINB #define DIO5_WPORT PORTD
#define DIO9_WPORT PORTB #define DIO5_DDR DDRD
#define DIO9_DDR DDRB #define DIO5_PWM &OCR0B
#define DIO9_PWM NULL
#define DIO6_PIN PIND6
#define DIO10_PIN PINB2 #define DIO6_RPORT PIND
#define DIO10_RPORT PINB #define DIO6_WPORT PORTD
#define DIO10_WPORT PORTB #define DIO6_DDR DDRD
#define DIO10_DDR DDRB #define DIO6_PWM &OCR0A
#define DIO10_PWM NULL
#define DIO7_PIN PIND7
#define DIO11_PIN PINB3 #define DIO7_RPORT PIND
#define DIO11_RPORT PINB #define DIO7_WPORT PORTD
#define DIO11_WPORT PORTB #define DIO7_DDR DDRD
#define DIO11_DDR DDRB #define DIO7_PWM NULL
#define DIO11_PWM &OCR2A
#define DIO8_PIN PINB0
#define DIO12_PIN PINB4 #define DIO8_RPORT PINB
#define DIO12_RPORT PINB #define DIO8_WPORT PORTB
#define DIO12_WPORT PORTB #define DIO8_DDR DDRB
#define DIO12_DDR DDRB #define DIO8_PWM NULL
#define DIO12_PWM NULL
#define DIO9_PIN PINB1
#define DIO13_PIN PINB5 #define DIO9_RPORT PINB
#define DIO13_RPORT PINB #define DIO9_WPORT PORTB
#define DIO13_WPORT PORTB #define DIO9_DDR DDRB
#define DIO13_DDR DDRB #define DIO9_PWM NULL
#define DIO13_PWM NULL
#define DIO10_PIN PINB2
#define DIO10_RPORT PINB
#define DIO14_PIN PINC0 #define DIO10_WPORT PORTB
#define DIO14_RPORT PINC #define DIO10_DDR DDRB
#define DIO14_WPORT PORTC #define DIO10_PWM NULL
#define DIO14_DDR DDRC
#define DIO14_PWM NULL #define DIO11_PIN PINB3
#define DIO11_RPORT PINB
#define DIO15_PIN PINC1 #define DIO11_WPORT PORTB
#define DIO15_RPORT PINC #define DIO11_DDR DDRB
#define DIO15_WPORT PORTC #define DIO11_PWM &OCR2A
#define DIO15_DDR DDRC
#define DIO15_PWM NULL #define DIO12_PIN PINB4
#define DIO12_RPORT PINB
#define DIO16_PIN PINC2 #define DIO12_WPORT PORTB
#define DIO16_RPORT PINC #define DIO12_DDR DDRB
#define DIO16_WPORT PORTC #define DIO12_PWM NULL
#define DIO16_DDR DDRC
#define DIO16_PWM NULL #define DIO13_PIN PINB5
#define DIO13_RPORT PINB
#define DIO17_PIN PINC3 #define DIO13_WPORT PORTB
#define DIO17_RPORT PINC #define DIO13_DDR DDRB
#define DIO17_WPORT PORTC #define DIO13_PWM NULL
#define DIO17_DDR DDRC
#define DIO17_PWM NULL
#define DIO14_PIN PINC0
#define DIO18_PIN PINC4 #define DIO14_RPORT PINC
#define DIO18_RPORT PINC #define DIO14_WPORT PORTC
#define DIO18_WPORT PORTC #define DIO14_DDR DDRC
#define DIO18_DDR DDRC #define DIO14_PWM NULL
#define DIO18_PWM NULL
#define DIO15_PIN PINC1
#define DIO19_PIN PINC5 #define DIO15_RPORT PINC
#define DIO19_RPORT PINC #define DIO15_WPORT PORTC
#define DIO19_WPORT PORTC #define DIO15_DDR DDRC
#define DIO19_DDR DDRC #define DIO15_PWM NULL
#define DIO19_PWM NULL
#define DIO16_PIN PINC2
#define DIO20_PIN PINC6 #define DIO16_RPORT PINC
#define DIO20_RPORT PINC #define DIO16_WPORT PORTC
#define DIO20_WPORT PORTC #define DIO16_DDR DDRC
#define DIO20_DDR DDRC #define DIO16_PWM NULL
#define DIO20_PWM NULL
#define DIO17_PIN PINC3
#define DIO21_PIN PINC7 #define DIO17_RPORT PINC
#define DIO21_RPORT PINC #define DIO17_WPORT PORTC
#define DIO21_WPORT PORTC #define DIO17_DDR DDRC
#define DIO21_DDR DDRC #define DIO17_PWM NULL
#define DIO21_PWM NULL
#define DIO18_PIN PINC4
#define DIO18_RPORT PINC
#define DIO18_WPORT PORTC
#undef PB0 #define DIO18_DDR DDRC
#define PB0_PIN PINB0 #define DIO18_PWM NULL
#define PB0_RPORT PINB
#define PB0_WPORT PORTB #define DIO19_PIN PINC5
#define PB0_DDR DDRB #define DIO19_RPORT PINC
#define PB0_PWM NULL #define DIO19_WPORT PORTC
#define DIO19_DDR DDRC
#undef PB1 #define DIO19_PWM NULL
#define PB1_PIN PINB1
#define PB1_RPORT PINB #define DIO20_PIN PINC6
#define PB1_WPORT PORTB #define DIO20_RPORT PINC
#define PB1_DDR DDRB #define DIO20_WPORT PORTC
#define PB1_PWM NULL #define DIO20_DDR DDRC
#define DIO20_PWM NULL
#undef PB2
#define PB2_PIN PINB2 #define DIO21_PIN PINC7
#define PB2_RPORT PINB #define DIO21_RPORT PINC
#define PB2_WPORT PORTB #define DIO21_WPORT PORTC
#define PB2_DDR DDRB #define DIO21_DDR DDRC
#define PB2_PWM NULL #define DIO21_PWM NULL
#undef PB3
#define PB3_PIN PINB3
#define PB3_RPORT PINB #undef PB0
#define PB3_WPORT PORTB #define PB0_PIN PINB0
#define PB3_DDR DDRB #define PB0_RPORT PINB
#define PB3_PWM &OCR2A #define PB0_WPORT PORTB
#define PB0_DDR DDRB
#undef PB4 #define PB0_PWM NULL
#define PB4_PIN PINB4
#define PB4_RPORT PINB #undef PB1
#define PB4_WPORT PORTB #define PB1_PIN PINB1
#define PB4_DDR DDRB #define PB1_RPORT PINB
#define PB4_PWM NULL #define PB1_WPORT PORTB
#define PB1_DDR DDRB
#undef PB5 #define PB1_PWM NULL
#define PB5_PIN PINB5
#define PB5_RPORT PINB #undef PB2
#define PB5_WPORT PORTB #define PB2_PIN PINB2
#define PB5_DDR DDRB #define PB2_RPORT PINB
#define PB5_PWM NULL #define PB2_WPORT PORTB
#define PB2_DDR DDRB
#undef PB6 #define PB2_PWM NULL
#define PB6_PIN PINB6
#define PB6_RPORT PINB #undef PB3
#define PB6_WPORT PORTB #define PB3_PIN PINB3
#define PB6_DDR DDRB #define PB3_RPORT PINB
#define PB6_PWM NULL #define PB3_WPORT PORTB
#define PB3_DDR DDRB
#undef PB7 #define PB3_PWM &OCR2A
#define PB7_PIN PINB7
#define PB7_RPORT PINB #undef PB4
#define PB7_WPORT PORTB #define PB4_PIN PINB4
#define PB7_DDR DDRB #define PB4_RPORT PINB
#define PB7_PWM NULL #define PB4_WPORT PORTB
#define PB4_DDR DDRB
#define PB4_PWM NULL
#undef PC0
#define PC0_PIN PINC0 #undef PB5
#define PC0_RPORT PINC #define PB5_PIN PINB5
#define PC0_WPORT PORTC #define PB5_RPORT PINB
#define PC0_DDR DDRC #define PB5_WPORT PORTB
#define PC0_PWM NULL #define PB5_DDR DDRB
#define PB5_PWM NULL
#undef PC1
#define PC1_PIN PINC1 #undef PB6
#define PC1_RPORT PINC #define PB6_PIN PINB6
#define PC1_WPORT PORTC #define PB6_RPORT PINB
#define PC1_DDR DDRC #define PB6_WPORT PORTB
#define PC1_PWM NULL #define PB6_DDR DDRB
#define PB6_PWM NULL
#undef PC2
#define PC2_PIN PINC2 #undef PB7
#define PC2_RPORT PINC #define PB7_PIN PINB7
#define PC2_WPORT PORTC #define PB7_RPORT PINB
#define PC2_DDR DDRC #define PB7_WPORT PORTB
#define PC2_PWM NULL #define PB7_DDR DDRB
#define PB7_PWM NULL
#undef PC3
#define PC3_PIN PINC3
#define PC3_RPORT PINC #undef PC0
#define PC3_WPORT PORTC #define PC0_PIN PINC0
#define PC3_DDR DDRC #define PC0_RPORT PINC
#define PC3_PWM NULL #define PC0_WPORT PORTC
#define PC0_DDR DDRC
#undef PC4 #define PC0_PWM NULL
#define PC4_PIN PINC4
#define PC4_RPORT PINC #undef PC1
#define PC4_WPORT PORTC #define PC1_PIN PINC1
#define PC4_DDR DDRC #define PC1_RPORT PINC
#define PC4_PWM NULL #define PC1_WPORT PORTC
#define PC1_DDR DDRC
#undef PC5 #define PC1_PWM NULL
#define PC5_PIN PINC5
#define PC5_RPORT PINC #undef PC2
#define PC5_WPORT PORTC #define PC2_PIN PINC2
#define PC5_DDR DDRC #define PC2_RPORT PINC
#define PC5_PWM NULL #define PC2_WPORT PORTC
#define PC2_DDR DDRC
#undef PC6 #define PC2_PWM NULL
#define PC6_PIN PINC6
#define PC6_RPORT PINC #undef PC3
#define PC6_WPORT PORTC #define PC3_PIN PINC3
#define PC6_DDR DDRC #define PC3_RPORT PINC
#define PC6_PWM NULL #define PC3_WPORT PORTC
#define PC3_DDR DDRC
#undef PC7 #define PC3_PWM NULL
#define PC7_PIN PINC7
#define PC7_RPORT PINC #undef PC4
#define PC7_WPORT PORTC #define PC4_PIN PINC4
#define PC7_DDR DDRC #define PC4_RPORT PINC
#define PC7_PWM NULL #define PC4_WPORT PORTC
#define PC4_DDR DDRC
#define PC4_PWM NULL
#undef PD0
#define PD0_PIN PIND0 #undef PC5
#define PD0_RPORT PIND #define PC5_PIN PINC5
#define PD0_WPORT PORTD #define PC5_RPORT PINC
#define PD0_DDR DDRD #define PC5_WPORT PORTC
#define PD0_PWM NULL #define PC5_DDR DDRC
#define PC5_PWM NULL
#undef PD1
#define PD1_PIN PIND1 #undef PC6
#define PD1_RPORT PIND #define PC6_PIN PINC6
#define PD1_WPORT PORTD #define PC6_RPORT PINC
#define PD1_DDR DDRD #define PC6_WPORT PORTC
#define PD1_PWM NULL #define PC6_DDR DDRC
#define PC6_PWM NULL
#undef PD2
#define PD2_PIN PIND2 #undef PC7
#define PD2_RPORT PIND #define PC7_PIN PINC7
#define PD2_WPORT PORTD #define PC7_RPORT PINC
#define PD2_DDR DDRD #define PC7_WPORT PORTC
#define PD2_PWM NULL #define PC7_DDR DDRC
#define PC7_PWM NULL
#undef PD3
#define PD3_PIN PIND3
#define PD3_RPORT PIND #undef PD0
#define PD3_WPORT PORTD #define PD0_PIN PIND0
#define PD3_DDR DDRD #define PD0_RPORT PIND
#define PD3_PWM &OCR2B #define PD0_WPORT PORTD
#define PD0_DDR DDRD
#undef PD4 #define PD0_PWM NULL
#define PD4_PIN PIND4
#define PD4_RPORT PIND #undef PD1
#define PD4_WPORT PORTD #define PD1_PIN PIND1
#define PD4_DDR DDRD #define PD1_RPORT PIND
#define PD4_PWM NULL #define PD1_WPORT PORTD
#define PD1_DDR DDRD
#undef PD5 #define PD1_PWM NULL
#define PD5_PIN PIND5
#define PD5_RPORT PIND #undef PD2
#define PD5_WPORT PORTD #define PD2_PIN PIND2
#define PD5_DDR DDRD #define PD2_RPORT PIND
#define PD5_PWM &OCR0B #define PD2_WPORT PORTD
#define PD2_DDR DDRD
#undef PD6 #define PD2_PWM NULL
#define PD6_PIN PIND6
#define PD6_RPORT PIND #undef PD3
#define PD6_WPORT PORTD #define PD3_PIN PIND3
#define PD6_DDR DDRD #define PD3_RPORT PIND
#define PD6_PWM &OCR0A #define PD3_WPORT PORTD
#define PD3_DDR DDRD
#undef PD7 #define PD3_PWM &OCR2B
#define PD7_PIN PIND7
#define PD7_RPORT PIND #undef PD4
#define PD7_WPORT PORTD #define PD4_PIN PIND4
#define PD7_DDR DDRD #define PD4_RPORT PIND
#define PD7_PWM NULL #define PD4_WPORT PORTD
#endif /* _AVR_ATmega{168,328,328P}__ */ #define PD4_DDR DDRD
#define PD4_PWM NULL
#if defined (__AVR_ATmega644__) || defined (__AVR_ATmega644P__) || defined (__AVR_ATmega644PA__)
// UART #undef PD5
#define RXD DIO8 #define PD5_PIN PIND5
#define TXD DIO9 #define PD5_RPORT PIND
#define RXD0 DIO8 #define PD5_WPORT PORTD
#define TXD0 DIO9 #define PD5_DDR DDRD
#define PD5_PWM &OCR0B
#define RXD1 DIO10
#define TXD1 DIO11 #undef PD6
#define PD6_PIN PIND6
// SPI #define PD6_RPORT PIND
#define SCK DIO7 #define PD6_WPORT PORTD
#define MISO DIO6 #define PD6_DDR DDRD
#define MOSI DIO5 #define PD6_PWM &OCR0A
#define SS DIO4
#undef PD7
// TWI (I2C) #define PD7_PIN PIND7
#define SCL DIO16 #define PD7_RPORT PIND
#define SDA DIO17 #define PD7_WPORT PORTD
#define PD7_DDR DDRD
// timers and PWM #define PD7_PWM NULL
#define OC0A DIO3 #endif /* _AVR_ATmega{168,328,328P}__ */
#define OC0B DIO4
#define OC1A DIO13 #if defined (__AVR_ATmega644__) || defined (__AVR_ATmega644P__) || defined (__AVR_ATmega644PA__)
#define OC1B DIO12 // UART
#define OC2A DIO15 #define RXD DIO8
#define OC2B DIO14 #define TXD DIO9
#define RXD0 DIO8
#define DEBUG_LED DIO0 #define TXD0 DIO9
/*
pins #define RXD1 DIO10
*/ #define TXD1 DIO11
#define DIO0_PIN PINB0 // SPI
#define DIO0_RPORT PINB #define SCK DIO7
#define DIO0_WPORT PORTB #define MISO DIO6
#define DIO0_DDR DDRB #define MOSI DIO5
#define DIO0_PWM NULL #define SS DIO4
#define DIO1_PIN PINB1 // TWI (I2C)
#define DIO1_RPORT PINB #define SCL DIO16
#define DIO1_WPORT PORTB #define SDA DIO17
#define DIO1_DDR DDRB
#define DIO1_PWM NULL // timers and PWM
#define OC0A DIO3
#define DIO2_PIN PINB2 #define OC0B DIO4
#define DIO2_RPORT PINB #define OC1A DIO13
#define DIO2_WPORT PORTB #define OC1B DIO12
#define DIO2_DDR DDRB #define OC2A DIO15
#define DIO2_PWM NULL #define OC2B DIO14
#define DIO3_PIN PINB3 #define DEBUG_LED DIO0
#define DIO3_RPORT PINB /*
#define DIO3_WPORT PORTB pins
#define DIO3_DDR DDRB */
#define DIO3_PWM &OCR0A
#define DIO0_PIN PINB0
#define DIO4_PIN PINB4 #define DIO0_RPORT PINB
#define DIO4_RPORT PINB #define DIO0_WPORT PORTB
#define DIO4_WPORT PORTB #define DIO0_DDR DDRB
#define DIO4_DDR DDRB #define DIO0_PWM NULL
#define DIO4_PWM &OCR0B
#define DIO1_PIN PINB1
#define DIO5_PIN PINB5 #define DIO1_RPORT PINB
#define DIO5_RPORT PINB #define DIO1_WPORT PORTB
#define DIO5_WPORT PORTB #define DIO1_DDR DDRB
#define DIO5_DDR DDRB #define DIO1_PWM NULL
#define DIO5_PWM NULL
#define DIO2_PIN PINB2
#define DIO6_PIN PINB6 #define DIO2_RPORT PINB
#define DIO6_RPORT PINB #define DIO2_WPORT PORTB
#define DIO6_WPORT PORTB #define DIO2_DDR DDRB
#define DIO6_DDR DDRB #define DIO2_PWM NULL
#define DIO6_PWM NULL
#define DIO3_PIN PINB3
#define DIO7_PIN PINB7 #define DIO3_RPORT PINB
#define DIO7_RPORT PINB #define DIO3_WPORT PORTB
#define DIO7_WPORT PORTB #define DIO3_DDR DDRB
#define DIO7_DDR DDRB #define DIO3_PWM OCR0A
#define DIO7_PWM NULL
#define DIO4_PIN PINB4
#define DIO8_PIN PIND0 #define DIO4_RPORT PINB
#define DIO8_RPORT PIND #define DIO4_WPORT PORTB
#define DIO8_WPORT PORTD #define DIO4_DDR DDRB
#define DIO8_DDR DDRD #define DIO4_PWM OCR0B
#define DIO8_PWM NULL
#define DIO5_PIN PINB5
#define DIO9_PIN PIND1 #define DIO5_RPORT PINB
#define DIO9_RPORT PIND #define DIO5_WPORT PORTB
#define DIO9_WPORT PORTD #define DIO5_DDR DDRB
#define DIO9_DDR DDRD #define DIO5_PWM NULL
#define DIO9_PWM NULL
#define DIO6_PIN PINB6
#define DIO10_PIN PIND2 #define DIO6_RPORT PINB
#define DIO10_RPORT PIND #define DIO6_WPORT PORTB
#define DIO10_WPORT PORTD #define DIO6_DDR DDRB
#define DIO10_DDR DDRD #define DIO6_PWM NULL
#define DIO10_PWM NULL
#define DIO7_PIN PINB7
#define DIO11_PIN PIND3 #define DIO7_RPORT PINB
#define DIO11_RPORT PIND #define DIO7_WPORT PORTB
#define DIO11_WPORT PORTD #define DIO7_DDR DDRB
#define DIO11_DDR DDRD #define DIO7_PWM NULL
#define DIO11_PWM NULL
#define DIO8_PIN PIND0
#define DIO12_PIN PIND4 #define DIO8_RPORT PIND
#define DIO12_RPORT PIND #define DIO8_WPORT PORTD
#define DIO12_WPORT PORTD #define DIO8_DDR DDRD
#define DIO12_DDR DDRD #define DIO8_PWM NULL
#define DIO12_PWM NULL
#define DIO9_PIN PIND1
#define DIO13_PIN PIND5 #define DIO9_RPORT PIND
#define DIO13_RPORT PIND #define DIO9_WPORT PORTD
#define DIO13_WPORT PORTD #define DIO9_DDR DDRD
#define DIO13_DDR DDRD #define DIO9_PWM NULL
#define DIO13_PWM NULL
#define DIO10_PIN PIND2
#define DIO14_PIN PIND6 #define DIO10_RPORT PIND
#define DIO14_RPORT PIND #define DIO10_WPORT PORTD
#define DIO14_WPORT PORTD #define DIO10_DDR DDRD
#define DIO14_DDR DDRD #define DIO10_PWM NULL
#define DIO14_PWM &OCR2B
#define DIO11_PIN PIND3
#define DIO15_PIN PIND7 #define DIO11_RPORT PIND
#define DIO15_RPORT PIND #define DIO11_WPORT PORTD
#define DIO15_WPORT PORTD #define DIO11_DDR DDRD
#define DIO15_DDR DDRD #define DIO11_PWM NULL
#define DIO15_PWM &OCR2A
#define DIO12_PIN PIND4
#define DIO16_PIN PINC0 #define DIO12_RPORT PIND
#define DIO16_RPORT PINC #define DIO12_WPORT PORTD
#define DIO16_WPORT PORTC #define DIO12_DDR DDRD
#define DIO16_DDR DDRC #define DIO12_PWM OCR1B
#define DIO16_PWM NULL
#define DIO13_PIN PIND5
#define DIO17_PIN PINC1 #define DIO13_RPORT PIND
#define DIO17_RPORT PINC #define DIO13_WPORT PORTD
#define DIO17_WPORT PORTC #define DIO13_DDR DDRD
#define DIO17_DDR DDRC #define DIO13_PWM OCR1A
#define DIO17_PWM NULL
#define DIO14_PIN PIND6
#define DIO18_PIN PINC2 #define DIO14_RPORT PIND
#define DIO18_RPORT PINC #define DIO14_WPORT PORTD
#define DIO18_WPORT PORTC #define DIO14_DDR DDRD
#define DIO18_DDR DDRC #define DIO14_PWM OCR2B
#define DIO18_PWM NULL
#define DIO15_PIN PIND7
#define DIO19_PIN PINC3 #define DIO15_RPORT PIND
#define DIO19_RPORT PINC #define DIO15_WPORT PORTD
#define DIO19_WPORT PORTC #define DIO15_DDR DDRD
#define DIO19_DDR DDRC #define DIO15_PWM OCR2A
#define DIO19_PWM NULL
#define DIO16_PIN PINC0
#define DIO20_PIN PINC4 #define DIO16_RPORT PINC
#define DIO20_RPORT PINC #define DIO16_WPORT PORTC
#define DIO20_WPORT PORTC #define DIO16_DDR DDRC
#define DIO20_DDR DDRC #define DIO16_PWM NULL
#define DIO20_PWM NULL
#define DIO17_PIN PINC1
#define DIO21_PIN PINC5 #define DIO17_RPORT PINC
#define DIO21_RPORT PINC #define DIO17_WPORT PORTC
#define DIO21_WPORT PORTC #define DIO17_DDR DDRC
#define DIO21_DDR DDRC #define DIO17_PWM NULL
#define DIO21_PWM NULL
#define DIO18_PIN PINC2
#define DIO22_PIN PINC6 #define DIO18_RPORT PINC
#define DIO22_RPORT PINC #define DIO18_WPORT PORTC
#define DIO22_WPORT PORTC #define DIO18_DDR DDRC
#define DIO22_DDR DDRC #define DIO18_PWM NULL
#define DIO22_PWM NULL
#define DIO19_PIN PINC3
#define DIO23_PIN PINC7 #define DIO19_RPORT PINC
#define DIO23_RPORT PINC #define DIO19_WPORT PORTC
#define DIO23_WPORT PORTC #define DIO19_DDR DDRC
#define DIO23_DDR DDRC #define DIO19_PWM NULL
#define DIO23_PWM NULL
#define DIO20_PIN PINC4
#define DIO24_PIN PINA7 #define DIO20_RPORT PINC
#define DIO24_RPORT PINA #define DIO20_WPORT PORTC
#define DIO24_WPORT PORTA #define DIO20_DDR DDRC
#define DIO24_DDR DDRA #define DIO20_PWM NULL
#define DIO24_PWM NULL
#define DIO21_PIN PINC5
#define DIO25_PIN PINA6 #define DIO21_RPORT PINC
#define DIO25_RPORT PINA #define DIO21_WPORT PORTC
#define DIO25_WPORT PORTA #define DIO21_DDR DDRC
#define DIO25_DDR DDRA #define DIO21_PWM NULL
#define DIO25_PWM NULL
#define DIO22_PIN PINC6
#define DIO26_PIN PINA5 #define DIO22_RPORT PINC
#define DIO26_RPORT PINA #define DIO22_WPORT PORTC
#define DIO26_WPORT PORTA #define DIO22_DDR DDRC
#define DIO26_DDR DDRA #define DIO22_PWM NULL
#define DIO26_PWM NULL
#define DIO23_PIN PINC7
#define DIO27_PIN PINA4 #define DIO23_RPORT PINC
#define DIO27_RPORT PINA #define DIO23_WPORT PORTC
#define DIO27_WPORT PORTA #define DIO23_DDR DDRC
#define DIO27_DDR DDRA #define DIO23_PWM NULL
#define DIO27_PWM NULL
#define DIO24_PIN PINA7
#define DIO28_PIN PINA3 #define DIO24_RPORT PINA
#define DIO28_RPORT PINA #define DIO24_WPORT PORTA
#define DIO28_WPORT PORTA #define DIO24_DDR DDRA
#define DIO28_DDR DDRA #define DIO24_PWM NULL
#define DIO28_PWM NULL
#define DIO25_PIN PINA6
#define DIO29_PIN PINA2 #define DIO25_RPORT PINA
#define DIO29_RPORT PINA #define DIO25_WPORT PORTA
#define DIO29_WPORT PORTA #define DIO25_DDR DDRA
#define DIO29_DDR DDRA #define DIO25_PWM NULL
#define DIO29_PWM NULL
#define DIO26_PIN PINA5
#define DIO30_PIN PINA1 #define DIO26_RPORT PINA
#define DIO30_RPORT PINA #define DIO26_WPORT PORTA
#define DIO30_WPORT PORTA #define DIO26_DDR DDRA
#define DIO30_DDR DDRA #define DIO26_PWM NULL
#define DIO30_PWM NULL
#define DIO27_PIN PINA4
#define DIO31_PIN PINA0 #define DIO27_RPORT PINA
#define DIO31_RPORT PINA #define DIO27_WPORT PORTA
#define DIO31_WPORT PORTA #define DIO27_DDR DDRA
#define DIO31_DDR DDRA #define DIO27_PWM NULL
#define DIO31_PWM NULL
#define DIO28_PIN PINA3
#define AIO0_PIN PINA0 #define DIO28_RPORT PINA
#define AIO0_RPORT PINA #define DIO28_WPORT PORTA
#define AIO0_WPORT PORTA #define DIO28_DDR DDRA
#define AIO0_DDR DDRA #define DIO28_PWM NULL
#define AIO0_PWM NULL
#define DIO29_PIN PINA2
#define AIO1_PIN PINA1 #define DIO29_RPORT PINA
#define AIO1_RPORT PINA #define DIO29_WPORT PORTA
#define AIO1_WPORT PORTA #define DIO29_DDR DDRA
#define AIO1_DDR DDRA #define DIO29_PWM NULL
#define AIO1_PWM NULL
#define DIO30_PIN PINA1
#define AIO2_PIN PINA2 #define DIO30_RPORT PINA
#define AIO2_RPORT PINA #define DIO30_WPORT PORTA
#define AIO2_WPORT PORTA #define DIO30_DDR DDRA
#define AIO2_DDR DDRA #define DIO30_PWM NULL
#define AIO2_PWM NULL
#define DIO31_PIN PINA0
#define AIO3_PIN PINA3 #define DIO31_RPORT PINA
#define AIO3_RPORT PINA #define DIO31_WPORT PORTA
#define AIO3_WPORT PORTA #define DIO31_DDR DDRA
#define AIO3_DDR DDRA #define DIO31_PWM NULL
#define AIO3_PWM NULL
#define AIO0_PIN PINA0
#define AIO4_PIN PINA4 #define AIO0_RPORT PINA
#define AIO4_RPORT PINA #define AIO0_WPORT PORTA
#define AIO4_WPORT PORTA #define AIO0_DDR DDRA
#define AIO4_DDR DDRA #define AIO0_PWM NULL
#define AIO4_PWM NULL
#define AIO1_PIN PINA1
#define AIO5_PIN PINA5 #define AIO1_RPORT PINA
#define AIO5_RPORT PINA #define AIO1_WPORT PORTA
#define AIO5_WPORT PORTA #define AIO1_DDR DDRA
#define AIO5_DDR DDRA #define AIO1_PWM NULL
#define AIO5_PWM NULL
#define AIO2_PIN PINA2
#define AIO6_PIN PINA6 #define AIO2_RPORT PINA
#define AIO6_RPORT PINA #define AIO2_WPORT PORTA
#define AIO6_WPORT PORTA #define AIO2_DDR DDRA
#define AIO6_DDR DDRA #define AIO2_PWM NULL
#define AIO6_PWM NULL
#define AIO3_PIN PINA3
#define AIO7_PIN PINA7 #define AIO3_RPORT PINA
#define AIO7_RPORT PINA #define AIO3_WPORT PORTA
#define AIO7_WPORT PORTA #define AIO3_DDR DDRA
#define AIO7_DDR DDRA #define AIO3_PWM NULL
#define AIO7_PWM NULL
#define AIO4_PIN PINA4
#define AIO4_RPORT PINA
#define AIO4_WPORT PORTA
#undef PA0 #define AIO4_DDR DDRA
#define PA0_PIN PINA0 #define AIO4_PWM NULL
#define PA0_RPORT PINA
#define PA0_WPORT PORTA #define AIO5_PIN PINA5
#define PA0_DDR DDRA #define AIO5_RPORT PINA
#define PA0_PWM NULL #define AIO5_WPORT PORTA
#define AIO5_DDR DDRA
#undef PA1 #define AIO5_PWM NULL
#define PA1_PIN PINA1
#define PA1_RPORT PINA #define AIO6_PIN PINA6
#define PA1_WPORT PORTA #define AIO6_RPORT PINA
#define PA1_DDR DDRA #define AIO6_WPORT PORTA
#define PA1_PWM NULL #define AIO6_DDR DDRA
#define AIO6_PWM NULL
#undef PA2
#define PA2_PIN PINA2 #define AIO7_PIN PINA7
#define PA2_RPORT PINA #define AIO7_RPORT PINA
#define PA2_WPORT PORTA #define AIO7_WPORT PORTA
#define PA2_DDR DDRA #define AIO7_DDR DDRA
#define PA2_PWM NULL #define AIO7_PWM NULL
#undef PA3
#define PA3_PIN PINA3
#define PA3_RPORT PINA #undef PA0
#define PA3_WPORT PORTA #define PA0_PIN PINA0
#define PA3_DDR DDRA #define PA0_RPORT PINA
#define PA3_PWM NULL #define PA0_WPORT PORTA
#define PA0_DDR DDRA
#undef PA4 #define PA0_PWM NULL
#define PA4_PIN PINA4
#define PA4_RPORT PINA #undef PA1
#define PA4_WPORT PORTA #define PA1_PIN PINA1
#define PA4_DDR DDRA #define PA1_RPORT PINA
#define PA4_PWM NULL #define PA1_WPORT PORTA
#define PA1_DDR DDRA
#undef PA5 #define PA1_PWM NULL
#define PA5_PIN PINA5
#define PA5_RPORT PINA #undef PA2
#define PA5_WPORT PORTA #define PA2_PIN PINA2
#define PA5_DDR DDRA #define PA2_RPORT PINA
#define PA5_PWM NULL #define PA2_WPORT PORTA
#define PA2_DDR DDRA
#undef PA6 #define PA2_PWM NULL
#define PA6_PIN PINA6
#define PA6_RPORT PINA #undef PA3
#define PA6_WPORT PORTA #define PA3_PIN PINA3
#define PA6_DDR DDRA #define PA3_RPORT PINA
#define PA6_PWM NULL #define PA3_WPORT PORTA
#define PA3_DDR DDRA
#undef PA7 #define PA3_PWM NULL
#define PA7_PIN PINA7
#define PA7_RPORT PINA #undef PA4
#define PA7_WPORT PORTA #define PA4_PIN PINA4
#define PA7_DDR DDRA #define PA4_RPORT PINA
#define PA7_PWM NULL #define PA4_WPORT PORTA
#define PA4_DDR DDRA
#define PA4_PWM NULL
#undef PB0
#define PB0_PIN PINB0 #undef PA5
#define PB0_RPORT PINB #define PA5_PIN PINA5
#define PB0_WPORT PORTB #define PA5_RPORT PINA
#define PB0_DDR DDRB #define PA5_WPORT PORTA
#define PB0_PWM NULL #define PA5_DDR DDRA
#define PA5_PWM NULL
#undef PB1
#define PB1_PIN PINB1 #undef PA6
#define PB1_RPORT PINB #define PA6_PIN PINA6
#define PB1_WPORT PORTB #define PA6_RPORT PINA
#define PB1_DDR DDRB #define PA6_WPORT PORTA
#define PB1_PWM NULL #define PA6_DDR DDRA
#define PA6_PWM NULL
#undef PB2
#define PB2_PIN PINB2 #undef PA7
#define PB2_RPORT PINB #define PA7_PIN PINA7
#define PB2_WPORT PORTB #define PA7_RPORT PINA
#define PB2_DDR DDRB #define PA7_WPORT PORTA
#define PB2_PWM NULL #define PA7_DDR DDRA
#define PA7_PWM NULL
#undef PB3
#define PB3_PIN PINB3
#define PB3_RPORT PINB #undef PB0
#define PB3_WPORT PORTB #define PB0_PIN PINB0
#define PB3_DDR DDRB #define PB0_RPORT PINB
#define PB3_PWM &OCR0A #define PB0_WPORT PORTB
#define PB0_DDR DDRB
#undef PB4 #define PB0_PWM NULL
#define PB4_PIN PINB4
#define PB4_RPORT PINB #undef PB1
#define PB4_WPORT PORTB #define PB1_PIN PINB1
#define PB4_DDR DDRB #define PB1_RPORT PINB
#define PB4_PWM &OCR0B #define PB1_WPORT PORTB
#define PB1_DDR DDRB
#undef PB5 #define PB1_PWM NULL
#define PB5_PIN PINB5
#define PB5_RPORT PINB #undef PB2
#define PB5_WPORT PORTB #define PB2_PIN PINB2
#define PB5_DDR DDRB #define PB2_RPORT PINB
#define PB5_PWM NULL #define PB2_WPORT PORTB
#define PB2_DDR DDRB
#undef PB6 #define PB2_PWM NULL
#define PB6_PIN PINB6
#define PB6_RPORT PINB #undef PB3
#define PB6_WPORT PORTB #define PB3_PIN PINB3
#define PB6_DDR DDRB #define PB3_RPORT PINB
#define PB6_PWM NULL #define PB3_WPORT PORTB
#define PB3_DDR DDRB
#undef PB7 #define PB3_PWM OCR0A
#define PB7_PIN PINB7
#define PB7_RPORT PINB #undef PB4
#define PB7_WPORT PORTB #define PB4_PIN PINB4
#define PB7_DDR DDRB #define PB4_RPORT PINB
#define PB7_PWM NULL #define PB4_WPORT PORTB
#define PB4_DDR DDRB
#define PB4_PWM OCR0B
#undef PC0
#define PC0_PIN PINC0 #undef PB5
#define PC0_RPORT PINC #define PB5_PIN PINB5
#define PC0_WPORT PORTC #define PB5_RPORT PINB
#define PC0_DDR DDRC #define PB5_WPORT PORTB
#define PC0_PWM NULL #define PB5_DDR DDRB
#define PB5_PWM NULL
#undef PC1
#define PC1_PIN PINC1 #undef PB6
#define PC1_RPORT PINC #define PB6_PIN PINB6
#define PC1_WPORT PORTC #define PB6_RPORT PINB
#define PC1_DDR DDRC #define PB6_WPORT PORTB
#define PC1_PWM NULL #define PB6_DDR DDRB
#define PB6_PWM NULL
#undef PC2
#define PC2_PIN PINC2 #undef PB7
#define PC2_RPORT PINC #define PB7_PIN PINB7
#define PC2_WPORT PORTC #define PB7_RPORT PINB
#define PC2_DDR DDRC #define PB7_WPORT PORTB
#define PC2_PWM NULL #define PB7_DDR DDRB
#define PB7_PWM NULL
#undef PC3
#define PC3_PIN PINC3
#define PC3_RPORT PINC #undef PC0
#define PC3_WPORT PORTC #define PC0_PIN PINC0
#define PC3_DDR DDRC #define PC0_RPORT PINC
#define PC3_PWM NULL #define PC0_WPORT PORTC
#define PC0_DDR DDRC
#undef PC4 #define PC0_PWM NULL
#define PC4_PIN PINC4
#define PC4_RPORT PINC #undef PC1
#define PC4_WPORT PORTC #define PC1_PIN PINC1
#define PC4_DDR DDRC #define PC1_RPORT PINC
#define PC4_PWM NULL #define PC1_WPORT PORTC
#define PC1_DDR DDRC
#undef PC5 #define PC1_PWM NULL
#define PC5_PIN PINC5
#define PC5_RPORT PINC #undef PC2
#define PC5_WPORT PORTC #define PC2_PIN PINC2
#define PC5_DDR DDRC #define PC2_RPORT PINC
#define PC5_PWM NULL #define PC2_WPORT PORTC
#define PC2_DDR DDRC
#undef PC6 #define PC2_PWM NULL
#define PC6_PIN PINC6
#define PC6_RPORT PINC #undef PC3
#define PC6_WPORT PORTC #define PC3_PIN PINC3
#define PC6_DDR DDRC #define PC3_RPORT PINC
#define PC6_PWM NULL #define PC3_WPORT PORTC
#define PC3_DDR DDRC
#undef PC7 #define PC3_PWM NULL
#define PC7_PIN PINC7
#define PC7_RPORT PINC #undef PC4
#define PC7_WPORT PORTC #define PC4_PIN PINC4
#define PC7_DDR DDRC #define PC4_RPORT PINC
#define PC7_PWM NULL #define PC4_WPORT PORTC
#define PC4_DDR DDRC
#define PC4_PWM NULL
#undef PD0
#define PD0_PIN PIND0 #undef PC5
#define PD0_RPORT PIND #define PC5_PIN PINC5
#define PD0_WPORT PORTD #define PC5_RPORT PINC
#define PD0_DDR DDRD #define PC5_WPORT PORTC
#define PD0_PWM NULL #define PC5_DDR DDRC
#define PC5_PWM NULL
#undef PD1
#define PD1_PIN PIND1 #undef PC6
#define PD1_RPORT PIND #define PC6_PIN PINC6
#define PD1_WPORT PORTD #define PC6_RPORT PINC
#define PD1_DDR DDRD #define PC6_WPORT PORTC
#define PD1_PWM NULL #define PC6_DDR DDRC
#define PC6_PWM NULL
#undef PD2
#define PD2_PIN PIND2 #undef PC7
#define PD2_RPORT PIND #define PC7_PIN PINC7
#define PD2_WPORT PORTD #define PC7_RPORT PINC
#define PD2_DDR DDRD #define PC7_WPORT PORTC
#define PD2_PWM NULL #define PC7_DDR DDRC
#define PC7_PWM NULL
#undef PD3
#define PD3_PIN PIND3
#define PD3_RPORT PIND #undef PD0
#define PD3_WPORT PORTD #define PD0_PIN PIND0
#define PD3_DDR DDRD #define PD0_RPORT PIND
#define PD3_PWM NULL #define PD0_WPORT PORTD
#define PD0_DDR DDRD
#undef PD4 #define PD0_PWM NULL
#define PD4_PIN PIND4
#define PD4_RPORT PIND #undef PD1
#define PD4_WPORT PORTD #define PD1_PIN PIND1
#define PD4_DDR DDRD #define PD1_RPORT PIND
#define PD4_PWM NULL #define PD1_WPORT PORTD
#define PD1_DDR DDRD
#undef PD5 #define PD1_PWM NULL
#define PD5_PIN PIND5
#define PD5_RPORT PIND #undef PD2
#define PD5_WPORT PORTD #define PD2_PIN PIND2
#define PD5_DDR DDRD #define PD2_RPORT PIND
#define PD5_PWM NULL #define PD2_WPORT PORTD
#define PD2_DDR DDRD
#undef PD6 #define PD2_PWM NULL
#define PD6_PIN PIND6
#define PD6_RPORT PIND #undef PD3
#define PD6_WPORT PORTD #define PD3_PIN PIND3
#define PD6_DDR DDRD #define PD3_RPORT PIND
#define PD6_PWM &OCR2B #define PD3_WPORT PORTD
#define PD3_DDR DDRD
#undef PD7 #define PD3_PWM NULL
#define PD7_PIN PIND7
#define PD7_RPORT PIND #undef PD4
#define PD7_WPORT PORTD #define PD4_PIN PIND4
#define PD7_DDR DDRD #define PD4_RPORT PIND
#define PD7_PWM &OCR2A #define PD4_WPORT PORTD
#endif /* _AVR_ATmega{644,644P,644PA}__ */ #define PD4_DDR DDRD
#define PD4_PWM NULL
#if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
// UART #undef PD5
#define RXD DIO0 #define PD5_PIN PIND5
#define TXD DIO1 #define PD5_RPORT PIND
#define PD5_WPORT PORTD
// SPI #define PD5_DDR DDRD
#define SCK DIO52 #define PD5_PWM NULL
#define MISO DIO50
#define MOSI DIO51 #undef PD6
#define SS DIO53 #define PD6_PIN PIND6
#define PD6_RPORT PIND
// TWI (I2C) #define PD6_WPORT PORTD
#define SCL DIO21 #define PD6_DDR DDRD
#define SDA DIO20 #define PD6_PWM OCR2B
// timers and PWM #undef PD7
#define OC0A DIO13 #define PD7_PIN PIND7
#define OC0B DIO4 #define PD7_RPORT PIND
#define OC1A DIO11 #define PD7_WPORT PORTD
#define OC1B DIO12 #define PD7_DDR DDRD
#define OC2A DIO10 #define PD7_PWM OCR2A
#define OC2B DIO9 #endif /* _AVR_ATmega{644,644P,644PA}__ */
#define OC3A DIO5
#define OC3B DIO2 #if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
#define OC3C DIO3 // UART
#define OC4A DIO6 #define RXD DIO0
#define OC4B DIO7 #define TXD DIO1
#define OC4C DIO8
#define OC5A DIO46 // SPI
#define OC5B DIO45 #define SCK DIO52
#define OC5C DIO44 #define MISO DIO50
#define MOSI DIO51
// change for your board #define SS DIO53
#define DEBUG_LED DIO21
// TWI (I2C)
/* #define SCL DIO21
pins #define SDA DIO20
*/
#define DIO0_PIN PINE0 // timers and PWM
#define DIO0_RPORT PINE #define OC0A DIO13
#define DIO0_WPORT PORTE #define OC0B DIO4
#define DIO0_DDR DDRE #define OC1A DIO11
#define DIO0_PWM NULL #define OC1B DIO12
#define OC2A DIO10
#define DIO1_PIN PINE1 #define OC2B DIO9
#define DIO1_RPORT PINE #define OC3A DIO5
#define DIO1_WPORT PORTE #define OC3B DIO2
#define DIO1_DDR DDRE #define OC3C DIO3
#define DIO1_PWM NULL #define OC4A DIO6
#define OC4B DIO7
#define DIO2_PIN PINE4 #define OC4C DIO8
#define DIO2_RPORT PINE #define OC5A DIO46
#define DIO2_WPORT PORTE #define OC5B DIO45
#define DIO2_DDR DDRE #define OC5C DIO44
#define DIO2_PWM &OCR3BL
// change for your board
#define DIO3_PIN PINE5 #define DEBUG_LED DIO21
#define DIO3_RPORT PINE
#define DIO3_WPORT PORTE /*
#define DIO3_DDR DDRE pins
#define DIO3_PWM &OCR3CL */
#define DIO0_PIN PINE0
#define DIO4_PIN PING5 #define DIO0_RPORT PINE
#define DIO4_RPORT PING #define DIO0_WPORT PORTE
#define DIO4_WPORT PORTG #define DIO0_DDR DDRE
#define DIO4_DDR DDRG #define DIO0_PWM NULL
#define DIO4_PWM &OCR0B
#define DIO1_PIN PINE1
#define DIO5_PIN PINE3 #define DIO1_RPORT PINE
#define DIO5_RPORT PINE #define DIO1_WPORT PORTE
#define DIO5_WPORT PORTE #define DIO1_DDR DDRE
#define DIO5_DDR DDRE #define DIO1_PWM NULL
#define DIO5_PWM &OCR3AL
#define DIO2_PIN PINE4
#define DIO6_PIN PINH3 #define DIO2_RPORT PINE
#define DIO6_RPORT PINH #define DIO2_WPORT PORTE
#define DIO6_WPORT PORTH #define DIO2_DDR DDRE
#define DIO6_DDR DDRH #define DIO2_PWM &OCR3BL
#define DIO6_PWM &OCR4AL
#define DIO3_PIN PINE5
#define DIO7_PIN PINH4 #define DIO3_RPORT PINE
#define DIO7_RPORT PINH #define DIO3_WPORT PORTE
#define DIO7_WPORT PORTH #define DIO3_DDR DDRE
#define DIO7_DDR DDRH #define DIO3_PWM &OCR3CL
#define DIO7_PWM &OCR4BL
#define DIO4_PIN PING5
#define DIO8_PIN PINH5 #define DIO4_RPORT PING
#define DIO8_RPORT PINH #define DIO4_WPORT PORTG
#define DIO8_WPORT PORTH #define DIO4_DDR DDRG
#define DIO8_DDR DDRH #define DIO4_PWM &OCR0B
#define DIO8_PWM &OCR4CL
#define DIO5_PIN PINE3
#define DIO9_PIN PINH6 #define DIO5_RPORT PINE
#define DIO9_RPORT PINH #define DIO5_WPORT PORTE
#define DIO9_WPORT PORTH #define DIO5_DDR DDRE
#define DIO9_DDR DDRH #define DIO5_PWM &OCR3AL
#define DIO9_PWM &OCR2B
#define DIO6_PIN PINH3
#define DIO10_PIN PINB4 #define DIO6_RPORT PINH
#define DIO10_RPORT PINB #define DIO6_WPORT PORTH
#define DIO10_WPORT PORTB #define DIO6_DDR DDRH
#define DIO10_DDR DDRB #define DIO6_PWM &OCR4AL
#define DIO10_PWM &OCR2A
#define DIO7_PIN PINH4
#define DIO11_PIN PINB5 #define DIO7_RPORT PINH
#define DIO11_RPORT PINB #define DIO7_WPORT PORTH
#define DIO11_WPORT PORTB #define DIO7_DDR DDRH
#define DIO11_DDR DDRB #define DIO7_PWM &OCR4BL
#define DIO11_PWM NULL
#define DIO8_PIN PINH5
#define DIO12_PIN PINB6 #define DIO8_RPORT PINH
#define DIO12_RPORT PINB #define DIO8_WPORT PORTH
#define DIO12_WPORT PORTB #define DIO8_DDR DDRH
#define DIO12_DDR DDRB #define DIO8_PWM &OCR4CL
#define DIO12_PWM NULL
#define DIO9_PIN PINH6
#define DIO13_PIN PINB7 #define DIO9_RPORT PINH
#define DIO13_RPORT PINB #define DIO9_WPORT PORTH
#define DIO13_WPORT PORTB #define DIO9_DDR DDRH
#define DIO13_DDR DDRB #define DIO9_PWM &OCR2B
#define DIO13_PWM &OCR0A
#define DIO10_PIN PINB4
#define DIO14_PIN PINJ1 #define DIO10_RPORT PINB
#define DIO14_RPORT PINJ #define DIO10_WPORT PORTB
#define DIO14_WPORT PORTJ #define DIO10_DDR DDRB
#define DIO14_DDR DDRJ #define DIO10_PWM &OCR2A
#define DIO14_PWM NULL
#define DIO11_PIN PINB5
#define DIO15_PIN PINJ0 #define DIO11_RPORT PINB
#define DIO15_RPORT PINJ #define DIO11_WPORT PORTB
#define DIO15_WPORT PORTJ #define DIO11_DDR DDRB
#define DIO15_DDR DDRJ #define DIO11_PWM NULL
#define DIO15_PWM NULL
#define DIO12_PIN PINB6
#define DIO16_PIN PINH1 #define DIO12_RPORT PINB
#define DIO16_RPORT PINH #define DIO12_WPORT PORTB
#define DIO16_WPORT PORTH #define DIO12_DDR DDRB
#define DIO16_DDR DDRH #define DIO12_PWM NULL
#define DIO16_PWM NULL
#define DIO13_PIN PINB7
#define DIO17_PIN PINH0 #define DIO13_RPORT PINB
#define DIO17_RPORT PINH #define DIO13_WPORT PORTB
#define DIO17_WPORT PORTH #define DIO13_DDR DDRB
#define DIO17_DDR DDRH #define DIO13_PWM &OCR0A
#define DIO17_PWM NULL
#define DIO14_PIN PINJ1
#define DIO18_PIN PIND3 #define DIO14_RPORT PINJ
#define DIO18_RPORT PIND #define DIO14_WPORT PORTJ
#define DIO18_WPORT PORTD #define DIO14_DDR DDRJ
#define DIO18_DDR DDRD #define DIO14_PWM NULL
#define DIO18_PWM NULL
#define DIO15_PIN PINJ0
#define DIO19_PIN PIND2 #define DIO15_RPORT PINJ
#define DIO19_RPORT PIND #define DIO15_WPORT PORTJ
#define DIO19_WPORT PORTD #define DIO15_DDR DDRJ
#define DIO19_DDR DDRD #define DIO15_PWM NULL
#define DIO19_PWM NULL
#define DIO16_PIN PINH1
#define DIO20_PIN PIND1 #define DIO16_RPORT PINH
#define DIO20_RPORT PIND #define DIO16_WPORT PORTH
#define DIO20_WPORT PORTD #define DIO16_DDR DDRH
#define DIO20_DDR DDRD #define DIO16_PWM NULL
#define DIO20_PWM NULL
#define DIO17_PIN PINH0
#define DIO21_PIN PIND0 #define DIO17_RPORT PINH
#define DIO21_RPORT PIND #define DIO17_WPORT PORTH
#define DIO21_WPORT PORTD #define DIO17_DDR DDRH
#define DIO21_DDR DDRD #define DIO17_PWM NULL
#define DIO21_PWM NULL
#define DIO18_PIN PIND3
#define DIO22_PIN PINA0 #define DIO18_RPORT PIND
#define DIO22_RPORT PINA #define DIO18_WPORT PORTD
#define DIO22_WPORT PORTA #define DIO18_DDR DDRD
#define DIO22_DDR DDRA #define DIO18_PWM NULL
#define DIO22_PWM NULL
#define DIO19_PIN PIND2
#define DIO23_PIN PINA1 #define DIO19_RPORT PIND
#define DIO23_RPORT PINA #define DIO19_WPORT PORTD
#define DIO23_WPORT PORTA #define DIO19_DDR DDRD
#define DIO23_DDR DDRA #define DIO19_PWM NULL
#define DIO23_PWM NULL
#define DIO20_PIN PIND1
#define DIO24_PIN PINA2 #define DIO20_RPORT PIND
#define DIO24_RPORT PINA #define DIO20_WPORT PORTD
#define DIO24_WPORT PORTA #define DIO20_DDR DDRD
#define DIO24_DDR DDRA #define DIO20_PWM NULL
#define DIO24_PWM NULL
#define DIO21_PIN PIND0
#define DIO25_PIN PINA3 #define DIO21_RPORT PIND
#define DIO25_RPORT PINA #define DIO21_WPORT PORTD
#define DIO25_WPORT PORTA #define DIO21_DDR DDRD
#define DIO25_DDR DDRA #define DIO21_PWM NULL
#define DIO25_PWM NULL
#define DIO22_PIN PINA0
#define DIO26_PIN PINA4 #define DIO22_RPORT PINA
#define DIO26_RPORT PINA #define DIO22_WPORT PORTA
#define DIO26_WPORT PORTA #define DIO22_DDR DDRA
#define DIO26_DDR DDRA #define DIO22_PWM NULL
#define DIO26_PWM NULL
#define DIO23_PIN PINA1
#define DIO27_PIN PINA5 #define DIO23_RPORT PINA
#define DIO27_RPORT PINA #define DIO23_WPORT PORTA
#define DIO27_WPORT PORTA #define DIO23_DDR DDRA
#define DIO27_DDR DDRA #define DIO23_PWM NULL
#define DIO27_PWM NULL
#define DIO24_PIN PINA2
#define DIO28_PIN PINA6 #define DIO24_RPORT PINA
#define DIO28_RPORT PINA #define DIO24_WPORT PORTA
#define DIO28_WPORT PORTA #define DIO24_DDR DDRA
#define DIO28_DDR DDRA #define DIO24_PWM NULL
#define DIO28_PWM NULL
#define DIO25_PIN PINA3
#define DIO29_PIN PINA7 #define DIO25_RPORT PINA
#define DIO29_RPORT PINA #define DIO25_WPORT PORTA
#define DIO29_WPORT PORTA #define DIO25_DDR DDRA
#define DIO29_DDR DDRA #define DIO25_PWM NULL
#define DIO29_PWM NULL
#define DIO26_PIN PINA4
#define DIO30_PIN PINC7 #define DIO26_RPORT PINA
#define DIO30_RPORT PINC #define DIO26_WPORT PORTA
#define DIO30_WPORT PORTC #define DIO26_DDR DDRA
#define DIO30_DDR DDRC #define DIO26_PWM NULL
#define DIO30_PWM NULL
#define DIO27_PIN PINA5
#define DIO31_PIN PINC6 #define DIO27_RPORT PINA
#define DIO31_RPORT PINC #define DIO27_WPORT PORTA
#define DIO31_WPORT PORTC #define DIO27_DDR DDRA
#define DIO31_DDR DDRC #define DIO27_PWM NULL
#define DIO31_PWM NULL
#define DIO28_PIN PINA6
#define DIO32_PIN PINC5 #define DIO28_RPORT PINA
#define DIO32_RPORT PINC #define DIO28_WPORT PORTA
#define DIO32_WPORT PORTC #define DIO28_DDR DDRA
#define DIO32_DDR DDRC #define DIO28_PWM NULL
#define DIO32_PWM NULL
#define DIO29_PIN PINA7
#define DIO33_PIN PINC4 #define DIO29_RPORT PINA
#define DIO33_RPORT PINC #define DIO29_WPORT PORTA
#define DIO33_WPORT PORTC #define DIO29_DDR DDRA
#define DIO33_DDR DDRC #define DIO29_PWM NULL
#define DIO33_PWM NULL
#define DIO30_PIN PINC7
#define DIO34_PIN PINC3 #define DIO30_RPORT PINC
#define DIO34_RPORT PINC #define DIO30_WPORT PORTC
#define DIO34_WPORT PORTC #define DIO30_DDR DDRC
#define DIO34_DDR DDRC #define DIO30_PWM NULL
#define DIO34_PWM NULL
#define DIO31_PIN PINC6
#define DIO35_PIN PINC2 #define DIO31_RPORT PINC
#define DIO35_RPORT PINC #define DIO31_WPORT PORTC
#define DIO35_WPORT PORTC #define DIO31_DDR DDRC
#define DIO35_DDR DDRC #define DIO31_PWM NULL
#define DIO35_PWM NULL
#define DIO32_PIN PINC5
#define DIO36_PIN PINC1 #define DIO32_RPORT PINC
#define DIO36_RPORT PINC #define DIO32_WPORT PORTC
#define DIO36_WPORT PORTC #define DIO32_DDR DDRC
#define DIO36_DDR DDRC #define DIO32_PWM NULL
#define DIO36_PWM NULL
#define DIO33_PIN PINC4
#define DIO37_PIN PINC0 #define DIO33_RPORT PINC
#define DIO37_RPORT PINC #define DIO33_WPORT PORTC
#define DIO37_WPORT PORTC #define DIO33_DDR DDRC
#define DIO37_DDR DDRC #define DIO33_PWM NULL
#define DIO37_PWM NULL
#define DIO34_PIN PINC3
#define DIO38_PIN PIND7 #define DIO34_RPORT PINC
#define DIO38_RPORT PIND #define DIO34_WPORT PORTC
#define DIO38_WPORT PORTD #define DIO34_DDR DDRC
#define DIO38_DDR DDRD #define DIO34_PWM NULL
#define DIO38_PWM NULL
#define DIO35_PIN PINC2
#define DIO39_PIN PING2 #define DIO35_RPORT PINC
#define DIO39_RPORT PING #define DIO35_WPORT PORTC
#define DIO39_WPORT PORTG #define DIO35_DDR DDRC
#define DIO39_DDR DDRG #define DIO35_PWM NULL
#define DIO39_PWM NULL
#define DIO36_PIN PINC1
#define DIO40_PIN PING1 #define DIO36_RPORT PINC
#define DIO40_RPORT PING #define DIO36_WPORT PORTC
#define DIO40_WPORT PORTG #define DIO36_DDR DDRC
#define DIO40_DDR DDRG #define DIO36_PWM NULL
#define DIO40_PWM NULL
#define DIO37_PIN PINC0
#define DIO41_PIN PING0 #define DIO37_RPORT PINC
#define DIO41_RPORT PING #define DIO37_WPORT PORTC
#define DIO41_WPORT PORTG #define DIO37_DDR DDRC
#define DIO41_DDR DDRG #define DIO37_PWM NULL
#define DIO41_PWM NULL
#define DIO38_PIN PIND7
#define DIO42_PIN PINL7 #define DIO38_RPORT PIND
#define DIO42_RPORT PINL #define DIO38_WPORT PORTD
#define DIO42_WPORT PORTL #define DIO38_DDR DDRD
#define DIO42_DDR DDRL #define DIO38_PWM NULL
#define DIO42_PWM NULL
#define DIO39_PIN PING2
#define DIO43_PIN PINL6 #define DIO39_RPORT PING
#define DIO43_RPORT PINL #define DIO39_WPORT PORTG
#define DIO43_WPORT PORTL #define DIO39_DDR DDRG
#define DIO43_DDR DDRL #define DIO39_PWM NULL
#define DIO43_PWM NULL
#define DIO40_PIN PING1
#define DIO44_PIN PINL5 #define DIO40_RPORT PING
#define DIO44_RPORT PINL #define DIO40_WPORT PORTG
#define DIO44_WPORT PORTL #define DIO40_DDR DDRG
#define DIO44_DDR DDRL #define DIO40_PWM NULL
#define DIO44_PWM &OCR5CL
#define DIO41_PIN PING0
#define DIO45_PIN PINL4 #define DIO41_RPORT PING
#define DIO45_RPORT PINL #define DIO41_WPORT PORTG
#define DIO45_WPORT PORTL #define DIO41_DDR DDRG
#define DIO45_DDR DDRL #define DIO41_PWM NULL
#define DIO45_PWM &OCR5BL
#define DIO42_PIN PINL7
#define DIO46_PIN PINL3 #define DIO42_RPORT PINL
#define DIO46_RPORT PINL #define DIO42_WPORT PORTL
#define DIO46_WPORT PORTL #define DIO42_DDR DDRL
#define DIO46_DDR DDRL #define DIO42_PWM NULL
#define DIO46_PWM &OCR5AL
#define DIO43_PIN PINL6
#define DIO47_PIN PINL2 #define DIO43_RPORT PINL
#define DIO47_RPORT PINL #define DIO43_WPORT PORTL
#define DIO47_WPORT PORTL #define DIO43_DDR DDRL
#define DIO47_DDR DDRL #define DIO43_PWM NULL
#define DIO47_PWM NULL
#define DIO44_PIN PINL5
#define DIO48_PIN PINL1 #define DIO44_RPORT PINL
#define DIO48_RPORT PINL #define DIO44_WPORT PORTL
#define DIO48_WPORT PORTL #define DIO44_DDR DDRL
#define DIO48_DDR DDRL #define DIO44_PWM &OCR5CL
#define DIO48_PWM NULL
#define DIO45_PIN PINL4
#define DIO49_PIN PINL0 #define DIO45_RPORT PINL
#define DIO49_RPORT PINL #define DIO45_WPORT PORTL
#define DIO49_WPORT PORTL #define DIO45_DDR DDRL
#define DIO49_DDR DDRL #define DIO45_PWM &OCR5BL
#define DIO49_PWM NULL
#define DIO46_PIN PINL3
#define DIO50_PIN PINB3 #define DIO46_RPORT PINL
#define DIO50_RPORT PINB #define DIO46_WPORT PORTL
#define DIO50_WPORT PORTB #define DIO46_DDR DDRL
#define DIO50_DDR DDRB #define DIO46_PWM &OCR5AL
#define DIO50_PWM NULL
#define DIO47_PIN PINL2
#define DIO51_PIN PINB2 #define DIO47_RPORT PINL
#define DIO51_RPORT PINB #define DIO47_WPORT PORTL
#define DIO51_WPORT PORTB #define DIO47_DDR DDRL
#define DIO51_DDR DDRB #define DIO47_PWM NULL
#define DIO51_PWM NULL
#define DIO48_PIN PINL1
#define DIO52_PIN PINB1 #define DIO48_RPORT PINL
#define DIO52_RPORT PINB #define DIO48_WPORT PORTL
#define DIO52_WPORT PORTB #define DIO48_DDR DDRL
#define DIO52_DDR DDRB #define DIO48_PWM NULL
#define DIO52_PWM NULL
#define DIO49_PIN PINL0
#define DIO53_PIN PINB0 #define DIO49_RPORT PINL
#define DIO53_RPORT PINB #define DIO49_WPORT PORTL
#define DIO53_WPORT PORTB #define DIO49_DDR DDRL
#define DIO53_DDR DDRB #define DIO49_PWM NULL
#define DIO53_PWM NULL
#define DIO50_PIN PINB3
#define DIO54_PIN PINF0 #define DIO50_RPORT PINB
#define DIO54_RPORT PINF #define DIO50_WPORT PORTB
#define DIO54_WPORT PORTF #define DIO50_DDR DDRB
#define DIO54_DDR DDRF #define DIO50_PWM NULL
#define DIO54_PWM NULL
#define DIO51_PIN PINB2
#define DIO55_PIN PINF1 #define DIO51_RPORT PINB
#define DIO55_RPORT PINF #define DIO51_WPORT PORTB
#define DIO55_WPORT PORTF #define DIO51_DDR DDRB
#define DIO55_DDR DDRF #define DIO51_PWM NULL
#define DIO55_PWM NULL
#define DIO52_PIN PINB1
#define DIO56_PIN PINF2 #define DIO52_RPORT PINB
#define DIO56_RPORT PINF #define DIO52_WPORT PORTB
#define DIO56_WPORT PORTF #define DIO52_DDR DDRB
#define DIO56_DDR DDRF #define DIO52_PWM NULL
#define DIO56_PWM NULL
#define DIO53_PIN PINB0
#define DIO57_PIN PINF3 #define DIO53_RPORT PINB
#define DIO57_RPORT PINF #define DIO53_WPORT PORTB
#define DIO57_WPORT PORTF #define DIO53_DDR DDRB
#define DIO57_DDR DDRF #define DIO53_PWM NULL
#define DIO57_PWM NULL
#define DIO54_PIN PINF0
#define DIO58_PIN PINF4 #define DIO54_RPORT PINF
#define DIO58_RPORT PINF #define DIO54_WPORT PORTF
#define DIO58_WPORT PORTF #define DIO54_DDR DDRF
#define DIO58_DDR DDRF #define DIO54_PWM NULL
#define DIO58_PWM NULL
#define DIO55_PIN PINF1
#define DIO59_PIN PINF5 #define DIO55_RPORT PINF
#define DIO59_RPORT PINF #define DIO55_WPORT PORTF
#define DIO59_WPORT PORTF #define DIO55_DDR DDRF
#define DIO59_DDR DDRF #define DIO55_PWM NULL
#define DIO59_PWM NULL
#define DIO56_PIN PINF2
#define DIO60_PIN PINF6 #define DIO56_RPORT PINF
#define DIO60_RPORT PINF #define DIO56_WPORT PORTF
#define DIO60_WPORT PORTF #define DIO56_DDR DDRF
#define DIO60_DDR DDRF #define DIO56_PWM NULL
#define DIO60_PWM NULL
#define DIO57_PIN PINF3
#define DIO61_PIN PINF7 #define DIO57_RPORT PINF
#define DIO61_RPORT PINF #define DIO57_WPORT PORTF
#define DIO61_WPORT PORTF #define DIO57_DDR DDRF
#define DIO61_DDR DDRF #define DIO57_PWM NULL
#define DIO61_PWM NULL
#define DIO58_PIN PINF4
#define DIO62_PIN PINK0 #define DIO58_RPORT PINF
#define DIO62_RPORT PINK #define DIO58_WPORT PORTF
#define DIO62_WPORT PORTK #define DIO58_DDR DDRF
#define DIO62_DDR DDRK #define DIO58_PWM NULL
#define DIO62_PWM NULL
#define DIO59_PIN PINF5
#define DIO63_PIN PINK1 #define DIO59_RPORT PINF
#define DIO63_RPORT PINK #define DIO59_WPORT PORTF
#define DIO63_WPORT PORTK #define DIO59_DDR DDRF
#define DIO63_DDR DDRK #define DIO59_PWM NULL
#define DIO63_PWM NULL
#define DIO60_PIN PINF6
#define DIO64_PIN PINK2 #define DIO60_RPORT PINF
#define DIO64_RPORT PINK #define DIO60_WPORT PORTF
#define DIO64_WPORT PORTK #define DIO60_DDR DDRF
#define DIO64_DDR DDRK #define DIO60_PWM NULL
#define DIO64_PWM NULL
#define DIO61_PIN PINF7
#define DIO65_PIN PINK3 #define DIO61_RPORT PINF
#define DIO65_RPORT PINK #define DIO61_WPORT PORTF
#define DIO65_WPORT PORTK #define DIO61_DDR DDRF
#define DIO65_DDR DDRK #define DIO61_PWM NULL
#define DIO65_PWM NULL
#define DIO62_PIN PINK0
#define DIO66_PIN PINK4 #define DIO62_RPORT PINK
#define DIO66_RPORT PINK #define DIO62_WPORT PORTK
#define DIO66_WPORT PORTK #define DIO62_DDR DDRK
#define DIO66_DDR DDRK #define DIO62_PWM NULL
#define DIO66_PWM NULL
#define DIO63_PIN PINK1
#define DIO67_PIN PINK5 #define DIO63_RPORT PINK
#define DIO67_RPORT PINK #define DIO63_WPORT PORTK
#define DIO67_WPORT PORTK #define DIO63_DDR DDRK
#define DIO67_DDR DDRK #define DIO63_PWM NULL
#define DIO67_PWM NULL
#define DIO64_PIN PINK2
#define DIO68_PIN PINK6 #define DIO64_RPORT PINK
#define DIO68_RPORT PINK #define DIO64_WPORT PORTK
#define DIO68_WPORT PORTK #define DIO64_DDR DDRK
#define DIO68_DDR DDRK #define DIO64_PWM NULL
#define DIO68_PWM NULL
#define DIO65_PIN PINK3
#define DIO69_PIN PINK7 #define DIO65_RPORT PINK
#define DIO69_RPORT PINK #define DIO65_WPORT PORTK
#define DIO69_WPORT PORTK #define DIO65_DDR DDRK
#define DIO69_DDR DDRK #define DIO65_PWM NULL
#define DIO69_PWM NULL
#define DIO66_PIN PINK4
#define DIO66_RPORT PINK
#define DIO66_WPORT PORTK
#undef PA0 #define DIO66_DDR DDRK
#define PA0_PIN PINA0 #define DIO66_PWM NULL
#define PA0_RPORT PINA
#define PA0_WPORT PORTA #define DIO67_PIN PINK5
#define PA0_DDR DDRA #define DIO67_RPORT PINK
#define PA0_PWM NULL #define DIO67_WPORT PORTK
#undef PA1 #define DIO67_DDR DDRK
#define PA1_PIN PINA1 #define DIO67_PWM NULL
#define PA1_RPORT PINA
#define PA1_WPORT PORTA #define DIO68_PIN PINK6
#define PA1_DDR DDRA #define DIO68_RPORT PINK
#define PA1_PWM NULL #define DIO68_WPORT PORTK
#undef PA2 #define DIO68_DDR DDRK
#define PA2_PIN PINA2 #define DIO68_PWM NULL
#define PA2_RPORT PINA
#define PA2_WPORT PORTA #define DIO69_PIN PINK7
#define PA2_DDR DDRA #define DIO69_RPORT PINK
#define PA2_PWM NULL #define DIO69_WPORT PORTK
#undef PA3 #define DIO69_DDR DDRK
#define PA3_PIN PINA3 #define DIO69_PWM NULL
#define PA3_RPORT PINA
#define PA3_WPORT PORTA
#define PA3_DDR DDRA
#define PA3_PWM NULL #undef PA0
#undef PA4 #define PA0_PIN PINA0
#define PA4_PIN PINA4 #define PA0_RPORT PINA
#define PA4_RPORT PINA #define PA0_WPORT PORTA
#define PA4_WPORT PORTA #define PA0_DDR DDRA
#define PA4_DDR DDRA #define PA0_PWM NULL
#define PA4_PWM NULL #undef PA1
#undef PA5 #define PA1_PIN PINA1
#define PA5_PIN PINA5 #define PA1_RPORT PINA
#define PA5_RPORT PINA #define PA1_WPORT PORTA
#define PA5_WPORT PORTA #define PA1_DDR DDRA
#define PA5_DDR DDRA #define PA1_PWM NULL
#define PA5_PWM NULL #undef PA2
#undef PA6 #define PA2_PIN PINA2
#define PA6_PIN PINA6 #define PA2_RPORT PINA
#define PA6_RPORT PINA #define PA2_WPORT PORTA
#define PA6_WPORT PORTA #define PA2_DDR DDRA
#define PA6_DDR DDRA #define PA2_PWM NULL
#define PA6_PWM NULL #undef PA3
#undef PA7 #define PA3_PIN PINA3
#define PA7_PIN PINA7 #define PA3_RPORT PINA
#define PA7_RPORT PINA #define PA3_WPORT PORTA
#define PA7_WPORT PORTA #define PA3_DDR DDRA
#define PA7_DDR DDRA #define PA3_PWM NULL
#define PA7_PWM NULL #undef PA4
#define PA4_PIN PINA4
#undef PB0 #define PA4_RPORT PINA
#define PB0_PIN PINB0 #define PA4_WPORT PORTA
#define PB0_RPORT PINB #define PA4_DDR DDRA
#define PB0_WPORT PORTB #define PA4_PWM NULL
#define PB0_DDR DDRB #undef PA5
#define PB0_PWM NULL #define PA5_PIN PINA5
#undef PB1 #define PA5_RPORT PINA
#define PB1_PIN PINB1 #define PA5_WPORT PORTA
#define PB1_RPORT PINB #define PA5_DDR DDRA
#define PB1_WPORT PORTB #define PA5_PWM NULL
#define PB1_DDR DDRB #undef PA6
#define PB1_PWM NULL #define PA6_PIN PINA6
#undef PB2 #define PA6_RPORT PINA
#define PB2_PIN PINB2 #define PA6_WPORT PORTA
#define PB2_RPORT PINB #define PA6_DDR DDRA
#define PB2_WPORT PORTB #define PA6_PWM NULL
#define PB2_DDR DDRB #undef PA7
#define PB2_PWM NULL #define PA7_PIN PINA7
#undef PB3 #define PA7_RPORT PINA
#define PB3_PIN PINB3 #define PA7_WPORT PORTA
#define PB3_RPORT PINB #define PA7_DDR DDRA
#define PB3_WPORT PORTB #define PA7_PWM NULL
#define PB3_DDR DDRB
#define PB3_PWM NULL #undef PB0
#undef PB4 #define PB0_PIN PINB0
#define PB4_PIN PINB4 #define PB0_RPORT PINB
#define PB4_RPORT PINB #define PB0_WPORT PORTB
#define PB4_WPORT PORTB #define PB0_DDR DDRB
#define PB4_DDR DDRB #define PB0_PWM NULL
#define PB4_PWM &OCR2A #undef PB1
#undef PB5 #define PB1_PIN PINB1
#define PB5_PIN PINB5 #define PB1_RPORT PINB
#define PB5_RPORT PINB #define PB1_WPORT PORTB
#define PB5_WPORT PORTB #define PB1_DDR DDRB
#define PB5_DDR DDRB #define PB1_PWM NULL
#define PB5_PWM NULL #undef PB2
#undef PB6 #define PB2_PIN PINB2
#define PB6_PIN PINB6 #define PB2_RPORT PINB
#define PB6_RPORT PINB #define PB2_WPORT PORTB
#define PB6_WPORT PORTB #define PB2_DDR DDRB
#define PB6_DDR DDRB #define PB2_PWM NULL
#define PB6_PWM NULL #undef PB3
#undef PB7 #define PB3_PIN PINB3
#define PB7_PIN PINB7 #define PB3_RPORT PINB
#define PB7_RPORT PINB #define PB3_WPORT PORTB
#define PB7_WPORT PORTB #define PB3_DDR DDRB
#define PB7_DDR DDRB #define PB3_PWM NULL
#define PB7_PWM &OCR0A #undef PB4
#define PB4_PIN PINB4
#undef PC0 #define PB4_RPORT PINB
#define PC0_PIN PINC0 #define PB4_WPORT PORTB
#define PC0_RPORT PINC #define PB4_DDR DDRB
#define PC0_WPORT PORTC #define PB4_PWM &OCR2A
#define PC0_DDR DDRC #undef PB5
#define PC0_PWM NULL #define PB5_PIN PINB5
#undef PC1 #define PB5_RPORT PINB
#define PC1_PIN PINC1 #define PB5_WPORT PORTB
#define PC1_RPORT PINC #define PB5_DDR DDRB
#define PC1_WPORT PORTC #define PB5_PWM NULL
#define PC1_DDR DDRC #undef PB6
#define PC1_PWM NULL #define PB6_PIN PINB6
#undef PC2 #define PB6_RPORT PINB
#define PC2_PIN PINC2 #define PB6_WPORT PORTB
#define PC2_RPORT PINC #define PB6_DDR DDRB
#define PC2_WPORT PORTC #define PB6_PWM NULL
#define PC2_DDR DDRC #undef PB7
#define PC2_PWM NULL #define PB7_PIN PINB7
#undef PC3 #define PB7_RPORT PINB
#define PC3_PIN PINC3 #define PB7_WPORT PORTB
#define PC3_RPORT PINC #define PB7_DDR DDRB
#define PC3_WPORT PORTC #define PB7_PWM &OCR0A
#define PC3_DDR DDRC
#define PC3_PWM NULL #undef PC0
#undef PC4 #define PC0_PIN PINC0
#define PC4_PIN PINC4 #define PC0_RPORT PINC
#define PC4_RPORT PINC #define PC0_WPORT PORTC
#define PC4_WPORT PORTC #define PC0_DDR DDRC
#define PC4_DDR DDRC #define PC0_PWM NULL
#define PC4_PWM NULL #undef PC1
#undef PC5 #define PC1_PIN PINC1
#define PC5_PIN PINC5 #define PC1_RPORT PINC
#define PC5_RPORT PINC #define PC1_WPORT PORTC
#define PC5_WPORT PORTC #define PC1_DDR DDRC
#define PC5_DDR DDRC #define PC1_PWM NULL
#define PC5_PWM NULL #undef PC2
#undef PC6 #define PC2_PIN PINC2
#define PC6_PIN PINC6 #define PC2_RPORT PINC
#define PC6_RPORT PINC #define PC2_WPORT PORTC
#define PC6_WPORT PORTC #define PC2_DDR DDRC
#define PC6_DDR DDRC #define PC2_PWM NULL
#define PC6_PWM NULL #undef PC3
#undef PC7 #define PC3_PIN PINC3
#define PC7_PIN PINC7 #define PC3_RPORT PINC
#define PC7_RPORT PINC #define PC3_WPORT PORTC
#define PC7_WPORT PORTC #define PC3_DDR DDRC
#define PC7_DDR DDRC #define PC3_PWM NULL
#define PC7_PWM NULL #undef PC4
#define PC4_PIN PINC4
#undef PD0 #define PC4_RPORT PINC
#define PD0_PIN PIND0 #define PC4_WPORT PORTC
#define PD0_RPORT PIND #define PC4_DDR DDRC
#define PD0_WPORT PORTD #define PC4_PWM NULL
#define PD0_DDR DDRD #undef PC5
#define PD0_PWM NULL #define PC5_PIN PINC5
#undef PD1 #define PC5_RPORT PINC
#define PD1_PIN PIND1 #define PC5_WPORT PORTC
#define PD1_RPORT PIND #define PC5_DDR DDRC
#define PD1_WPORT PORTD #define PC5_PWM NULL
#define PD1_DDR DDRD #undef PC6
#define PD1_PWM NULL #define PC6_PIN PINC6
#undef PD2 #define PC6_RPORT PINC
#define PD2_PIN PIND2 #define PC6_WPORT PORTC
#define PD2_RPORT PIND #define PC6_DDR DDRC
#define PD2_WPORT PORTD #define PC6_PWM NULL
#define PD2_DDR DDRD #undef PC7
#define PD2_PWM NULL #define PC7_PIN PINC7
#undef PD3 #define PC7_RPORT PINC
#define PD3_PIN PIND3 #define PC7_WPORT PORTC
#define PD3_RPORT PIND #define PC7_DDR DDRC
#define PD3_WPORT PORTD #define PC7_PWM NULL
#define PD3_DDR DDRD
#define PD3_PWM NULL #undef PD0
#undef PD4 #define PD0_PIN PIND0
#define PD4_PIN PIND4 #define PD0_RPORT PIND
#define PD4_RPORT PIND #define PD0_WPORT PORTD
#define PD4_WPORT PORTD #define PD0_DDR DDRD
#define PD4_DDR DDRD #define PD0_PWM NULL
#define PD4_PWM NULL #undef PD1
#undef PD5 #define PD1_PIN PIND1
#define PD5_PIN PIND5 #define PD1_RPORT PIND
#define PD5_RPORT PIND #define PD1_WPORT PORTD
#define PD5_WPORT PORTD #define PD1_DDR DDRD
#define PD5_DDR DDRD #define PD1_PWM NULL
#define PD5_PWM NULL #undef PD2
#undef PD6 #define PD2_PIN PIND2
#define PD6_PIN PIND6 #define PD2_RPORT PIND
#define PD6_RPORT PIND #define PD2_WPORT PORTD
#define PD6_WPORT PORTD #define PD2_DDR DDRD
#define PD6_DDR DDRD #define PD2_PWM NULL
#define PD6_PWM NULL #undef PD3
#undef PD7 #define PD3_PIN PIND3
#define PD7_PIN PIND7 #define PD3_RPORT PIND
#define PD7_RPORT PIND #define PD3_WPORT PORTD
#define PD7_WPORT PORTD #define PD3_DDR DDRD
#define PD7_DDR DDRD #define PD3_PWM NULL
#define PD7_PWM NULL #undef PD4
#define PD4_PIN PIND4
#undef PE0 #define PD4_RPORT PIND
#define PE0_PIN PINE0 #define PD4_WPORT PORTD
#define PE0_RPORT PINE #define PD4_DDR DDRD
#define PE0_WPORT PORTE #define PD4_PWM NULL
#define PE0_DDR DDRE #undef PD5
#define PE0_PWM NULL #define PD5_PIN PIND5
#undef PE1 #define PD5_RPORT PIND
#define PE1_PIN PINE1 #define PD5_WPORT PORTD
#define PE1_RPORT PINE #define PD5_DDR DDRD
#define PE1_WPORT PORTE #define PD5_PWM NULL
#define PE1_DDR DDRE #undef PD6
#define PE1_PWM NULL #define PD6_PIN PIND6
#undef PE2 #define PD6_RPORT PIND
#define PE2_PIN PINE2 #define PD6_WPORT PORTD
#define PE2_RPORT PINE #define PD6_DDR DDRD
#define PE2_WPORT PORTE #define PD6_PWM NULL
#define PE2_DDR DDRE #undef PD7
#define PE2_PWM NULL #define PD7_PIN PIND7
#undef PE3 #define PD7_RPORT PIND
#define PE3_PIN PINE3 #define PD7_WPORT PORTD
#define PE3_RPORT PINE #define PD7_DDR DDRD
#define PE3_WPORT PORTE #define PD7_PWM NULL
#define PE3_DDR DDRE
#define PE3_PWM &OCR3AL #undef PE0
#undef PE4 #define PE0_PIN PINE0
#define PE4_PIN PINE4 #define PE0_RPORT PINE
#define PE4_RPORT PINE #define PE0_WPORT PORTE
#define PE4_WPORT PORTE #define PE0_DDR DDRE
#define PE4_DDR DDRE #define PE0_PWM NULL
#define PE4_PWM &OCR3BL #undef PE1
#undef PE5 #define PE1_PIN PINE1
#define PE5_PIN PINE5 #define PE1_RPORT PINE
#define PE5_RPORT PINE #define PE1_WPORT PORTE
#define PE5_WPORT PORTE #define PE1_DDR DDRE
#define PE5_DDR DDRE #define PE1_PWM NULL
#define PE5_PWM &OCR3CL #undef PE2
#undef PE6 #define PE2_PIN PINE2
#define PE6_PIN PINE6 #define PE2_RPORT PINE
#define PE6_RPORT PINE #define PE2_WPORT PORTE
#define PE6_WPORT PORTE #define PE2_DDR DDRE
#define PE6_DDR DDRE #define PE2_PWM NULL
#define PE6_PWM NULL #undef PE3
#undef PE7 #define PE3_PIN PINE3
#define PE7_PIN PINE7 #define PE3_RPORT PINE
#define PE7_RPORT PINE #define PE3_WPORT PORTE
#define PE7_WPORT PORTE #define PE3_DDR DDRE
#define PE7_DDR DDRE #define PE3_PWM &OCR3AL
#define PE7_PWM NULL #undef PE4
#define PE4_PIN PINE4
#undef PF0 #define PE4_RPORT PINE
#define PF0_PIN PINF0 #define PE4_WPORT PORTE
#define PF0_RPORT PINF #define PE4_DDR DDRE
#define PF0_WPORT PORTF #define PE4_PWM &OCR3BL
#define PF0_DDR DDRF #undef PE5
#define PF0_PWM NULL #define PE5_PIN PINE5
#undef PF1 #define PE5_RPORT PINE
#define PF1_PIN PINF1 #define PE5_WPORT PORTE
#define PF1_RPORT PINF #define PE5_DDR DDRE
#define PF1_WPORT PORTF #define PE5_PWM &OCR3CL
#define PF1_DDR DDRF #undef PE6
#define PF1_PWM NULL #define PE6_PIN PINE6
#undef PF2 #define PE6_RPORT PINE
#define PF2_PIN PINF2 #define PE6_WPORT PORTE
#define PF2_RPORT PINF #define PE6_DDR DDRE
#define PF2_WPORT PORTF #define PE6_PWM NULL
#define PF2_DDR DDRF #undef PE7
#define PF2_PWM NULL #define PE7_PIN PINE7
#undef PF3 #define PE7_RPORT PINE
#define PF3_PIN PINF3 #define PE7_WPORT PORTE
#define PF3_RPORT PINF #define PE7_DDR DDRE
#define PF3_WPORT PORTF #define PE7_PWM NULL
#define PF3_DDR DDRF
#define PF3_PWM NULL #undef PF0
#undef PF4 #define PF0_PIN PINF0
#define PF4_PIN PINF4 #define PF0_RPORT PINF
#define PF4_RPORT PINF #define PF0_WPORT PORTF
#define PF4_WPORT PORTF #define PF0_DDR DDRF
#define PF4_DDR DDRF #define PF0_PWM NULL
#define PF4_PWM NULL #undef PF1
#undef PF5 #define PF1_PIN PINF1
#define PF5_PIN PINF5 #define PF1_RPORT PINF
#define PF5_RPORT PINF #define PF1_WPORT PORTF
#define PF5_WPORT PORTF #define PF1_DDR DDRF
#define PF5_DDR DDRF #define PF1_PWM NULL
#define PF5_PWM NULL #undef PF2
#undef PF6 #define PF2_PIN PINF2
#define PF6_PIN PINF6 #define PF2_RPORT PINF
#define PF6_RPORT PINF #define PF2_WPORT PORTF
#define PF6_WPORT PORTF #define PF2_DDR DDRF
#define PF6_DDR DDRF #define PF2_PWM NULL
#define PF6_PWM NULL #undef PF3
#undef PF7 #define PF3_PIN PINF3
#define PF7_PIN PINF7 #define PF3_RPORT PINF
#define PF7_RPORT PINF #define PF3_WPORT PORTF
#define PF7_WPORT PORTF #define PF3_DDR DDRF
#define PF7_DDR DDRF #define PF3_PWM NULL
#define PF7_PWM NULL #undef PF4
#define PF4_PIN PINF4
#undef PG0 #define PF4_RPORT PINF
#define PG0_PIN PING0 #define PF4_WPORT PORTF
#define PG0_RPORT PING #define PF4_DDR DDRF
#define PG0_WPORT PORTG #define PF4_PWM NULL
#define PG0_DDR DDRG #undef PF5
#define PG0_PWM NULL #define PF5_PIN PINF5
#undef PG1 #define PF5_RPORT PINF
#define PG1_PIN PING1 #define PF5_WPORT PORTF
#define PG1_RPORT PING #define PF5_DDR DDRF
#define PG1_WPORT PORTG #define PF5_PWM NULL
#define PG1_DDR DDRG #undef PF6
#define PG1_PWM NULL #define PF6_PIN PINF6
#undef PG2 #define PF6_RPORT PINF
#define PG2_PIN PING2 #define PF6_WPORT PORTF
#define PG2_RPORT PING #define PF6_DDR DDRF
#define PG2_WPORT PORTG #define PF6_PWM NULL
#define PG2_DDR DDRG #undef PF7
#define PG2_PWM NULL #define PF7_PIN PINF7
#undef PG3 #define PF7_RPORT PINF
#define PG3_PIN PING3 #define PF7_WPORT PORTF
#define PG3_RPORT PING #define PF7_DDR DDRF
#define PG3_WPORT PORTG #define PF7_PWM NULL
#define PG3_DDR DDRG
#define PG3_PWM NULL #undef PG0
#undef PG4 #define PG0_PIN PING0
#define PG4_PIN PING4 #define PG0_RPORT PING
#define PG4_RPORT PING #define PG0_WPORT PORTG
#define PG4_WPORT PORTG #define PG0_DDR DDRG
#define PG4_DDR DDRG #define PG0_PWM NULL
#define PG4_PWM NULL #undef PG1
#undef PG5 #define PG1_PIN PING1
#define PG5_PIN PING5 #define PG1_RPORT PING
#define PG5_RPORT PING #define PG1_WPORT PORTG
#define PG5_WPORT PORTG #define PG1_DDR DDRG
#define PG5_DDR DDRG #define PG1_PWM NULL
#define PG5_PWM &OCR0B #undef PG2
#undef PG6 #define PG2_PIN PING2
#define PG6_PIN PING6 #define PG2_RPORT PING
#define PG6_RPORT PING #define PG2_WPORT PORTG
#define PG6_WPORT PORTG #define PG2_DDR DDRG
#define PG6_DDR DDRG #define PG2_PWM NULL
#define PG6_PWM NULL #undef PG3
#undef PG7 #define PG3_PIN PING3
#define PG7_PIN PING7 #define PG3_RPORT PING
#define PG7_RPORT PING #define PG3_WPORT PORTG
#define PG7_WPORT PORTG #define PG3_DDR DDRG
#define PG7_DDR DDRG #define PG3_PWM NULL
#define PG7_PWM NULL #undef PG4
#define PG4_PIN PING4
#undef PH0 #define PG4_RPORT PING
#define PH0_PIN PINH0 #define PG4_WPORT PORTG
#define PH0_RPORT PINH #define PG4_DDR DDRG
#define PH0_WPORT PORTH #define PG4_PWM NULL
#define PH0_DDR DDRH #undef PG5
#define PH0_PWM NULL #define PG5_PIN PING5
#undef PH1 #define PG5_RPORT PING
#define PH1_PIN PINH1 #define PG5_WPORT PORTG
#define PH1_RPORT PINH #define PG5_DDR DDRG
#define PH1_WPORT PORTH #define PG5_PWM &OCR0B
#define PH1_DDR DDRH #undef PG6
#define PH1_PWM NULL #define PG6_PIN PING6
#undef PH2 #define PG6_RPORT PING
#define PH2_PIN PINH2 #define PG6_WPORT PORTG
#define PH2_RPORT PINH #define PG6_DDR DDRG
#define PH2_WPORT PORTH #define PG6_PWM NULL
#define PH2_DDR DDRH #undef PG7
#define PH2_PWM NULL #define PG7_PIN PING7
#undef PH3 #define PG7_RPORT PING
#define PH3_PIN PINH3 #define PG7_WPORT PORTG
#define PH3_RPORT PINH #define PG7_DDR DDRG
#define PH3_WPORT PORTH #define PG7_PWM NULL
#define PH3_DDR DDRH
#define PH3_PWM &OCR4AL #undef PH0
#undef PH4 #define PH0_PIN PINH0
#define PH4_PIN PINH4 #define PH0_RPORT PINH
#define PH4_RPORT PINH #define PH0_WPORT PORTH
#define PH4_WPORT PORTH #define PH0_DDR DDRH
#define PH4_DDR DDRH #define PH0_PWM NULL
#define PH4_PWM &OCR4BL #undef PH1
#undef PH5 #define PH1_PIN PINH1
#define PH5_PIN PINH5 #define PH1_RPORT PINH
#define PH5_RPORT PINH #define PH1_WPORT PORTH
#define PH5_WPORT PORTH #define PH1_DDR DDRH
#define PH5_DDR DDRH #define PH1_PWM NULL
#define PH5_PWM &OCR4CL #undef PH2
#undef PH6 #define PH2_PIN PINH2
#define PH6_PIN PINH6 #define PH2_RPORT PINH
#define PH6_RPORT PINH #define PH2_WPORT PORTH
#define PH6_WPORT PORTH #define PH2_DDR DDRH
#define PH6_DDR DDRH #define PH2_PWM NULL
#define PH6_PWM &OCR2B #undef PH3
#undef PH7 #define PH3_PIN PINH3
#define PH7_PIN PINH7 #define PH3_RPORT PINH
#define PH7_RPORT PINH #define PH3_WPORT PORTH
#define PH7_WPORT PORTH #define PH3_DDR DDRH
#define PH7_DDR DDRH #define PH3_PWM &OCR4AL
#define PH7_PWM NULL #undef PH4
#define PH4_PIN PINH4
#undef PJ0 #define PH4_RPORT PINH
#define PJ0_PIN PINJ0 #define PH4_WPORT PORTH
#define PJ0_RPORT PINJ #define PH4_DDR DDRH
#define PJ0_WPORT PORTJ #define PH4_PWM &OCR4BL
#define PJ0_DDR DDRJ #undef PH5
#define PJ0_PWM NULL #define PH5_PIN PINH5
#undef PJ1 #define PH5_RPORT PINH
#define PJ1_PIN PINJ1 #define PH5_WPORT PORTH
#define PJ1_RPORT PINJ #define PH5_DDR DDRH
#define PJ1_WPORT PORTJ #define PH5_PWM &OCR4CL
#define PJ1_DDR DDRJ #undef PH6
#define PJ1_PWM NULL #define PH6_PIN PINH6
#undef PJ2 #define PH6_RPORT PINH
#define PJ2_PIN PINJ2 #define PH6_WPORT PORTH
#define PJ2_RPORT PINJ #define PH6_DDR DDRH
#define PJ2_WPORT PORTJ #define PH6_PWM &OCR2B
#define PJ2_DDR DDRJ #undef PH7
#define PJ2_PWM NULL #define PH7_PIN PINH7
#undef PJ3 #define PH7_RPORT PINH
#define PJ3_PIN PINJ3 #define PH7_WPORT PORTH
#define PJ3_RPORT PINJ #define PH7_DDR DDRH
#define PJ3_WPORT PORTJ #define PH7_PWM NULL
#define PJ3_DDR DDRJ
#define PJ3_PWM NULL #undef PJ0
#undef PJ4 #define PJ0_PIN PINJ0
#define PJ4_PIN PINJ4 #define PJ0_RPORT PINJ
#define PJ4_RPORT PINJ #define PJ0_WPORT PORTJ
#define PJ4_WPORT PORTJ #define PJ0_DDR DDRJ
#define PJ4_DDR DDRJ #define PJ0_PWM NULL
#define PJ4_PWM NULL #undef PJ1
#undef PJ5 #define PJ1_PIN PINJ1
#define PJ5_PIN PINJ5 #define PJ1_RPORT PINJ
#define PJ5_RPORT PINJ #define PJ1_WPORT PORTJ
#define PJ5_WPORT PORTJ #define PJ1_DDR DDRJ
#define PJ5_DDR DDRJ #define PJ1_PWM NULL
#define PJ5_PWM NULL #undef PJ2
#undef PJ6 #define PJ2_PIN PINJ2
#define PJ6_PIN PINJ6 #define PJ2_RPORT PINJ
#define PJ6_RPORT PINJ #define PJ2_WPORT PORTJ
#define PJ6_WPORT PORTJ #define PJ2_DDR DDRJ
#define PJ6_DDR DDRJ #define PJ2_PWM NULL
#define PJ6_PWM NULL #undef PJ3
#undef PJ7 #define PJ3_PIN PINJ3
#define PJ7_PIN PINJ7 #define PJ3_RPORT PINJ
#define PJ7_RPORT PINJ #define PJ3_WPORT PORTJ
#define PJ7_WPORT PORTJ #define PJ3_DDR DDRJ
#define PJ7_DDR DDRJ #define PJ3_PWM NULL
#define PJ7_PWM NULL #undef PJ4
#define PJ4_PIN PINJ4
#undef PK0 #define PJ4_RPORT PINJ
#define PK0_PIN PINK0 #define PJ4_WPORT PORTJ
#define PK0_RPORT PINK #define PJ4_DDR DDRJ
#define PK0_WPORT PORTK #define PJ4_PWM NULL
#define PK0_DDR DDRK #undef PJ5
#define PK0_PWM NULL #define PJ5_PIN PINJ5
#undef PK1 #define PJ5_RPORT PINJ
#define PK1_PIN PINK1 #define PJ5_WPORT PORTJ
#define PK1_RPORT PINK #define PJ5_DDR DDRJ
#define PK1_WPORT PORTK #define PJ5_PWM NULL
#define PK1_DDR DDRK #undef PJ6
#define PK1_PWM NULL #define PJ6_PIN PINJ6
#undef PK2 #define PJ6_RPORT PINJ
#define PK2_PIN PINK2 #define PJ6_WPORT PORTJ
#define PK2_RPORT PINK #define PJ6_DDR DDRJ
#define PK2_WPORT PORTK #define PJ6_PWM NULL
#define PK2_DDR DDRK #undef PJ7
#define PK2_PWM NULL #define PJ7_PIN PINJ7
#undef PK3 #define PJ7_RPORT PINJ
#define PK3_PIN PINK3 #define PJ7_WPORT PORTJ
#define PK3_RPORT PINK #define PJ7_DDR DDRJ
#define PK3_WPORT PORTK #define PJ7_PWM NULL
#define PK3_DDR DDRK
#define PK3_PWM NULL #undef PK0
#undef PK4 #define PK0_PIN PINK0
#define PK4_PIN PINK4 #define PK0_RPORT PINK
#define PK4_RPORT PINK #define PK0_WPORT PORTK
#define PK4_WPORT PORTK #define PK0_DDR DDRK
#define PK4_DDR DDRK #define PK0_PWM NULL
#define PK4_PWM NULL #undef PK1
#undef PK5 #define PK1_PIN PINK1
#define PK5_PIN PINK5 #define PK1_RPORT PINK
#define PK5_RPORT PINK #define PK1_WPORT PORTK
#define PK5_WPORT PORTK #define PK1_DDR DDRK
#define PK5_DDR DDRK #define PK1_PWM NULL
#define PK5_PWM NULL #undef PK2
#undef PK6 #define PK2_PIN PINK2
#define PK6_PIN PINK6 #define PK2_RPORT PINK
#define PK6_RPORT PINK #define PK2_WPORT PORTK
#define PK6_WPORT PORTK #define PK2_DDR DDRK
#define PK6_DDR DDRK #define PK2_PWM NULL
#define PK6_PWM NULL #undef PK3
#undef PK7 #define PK3_PIN PINK3
#define PK7_PIN PINK7 #define PK3_RPORT PINK
#define PK7_RPORT PINK #define PK3_WPORT PORTK
#define PK7_WPORT PORTK #define PK3_DDR DDRK
#define PK7_DDR DDRK #define PK3_PWM NULL
#define PK7_PWM NULL #undef PK4
#define PK4_PIN PINK4
#undef PL0 #define PK4_RPORT PINK
#define PL0_PIN PINL0 #define PK4_WPORT PORTK
#define PL0_RPORT PINL #define PK4_DDR DDRK
#define PL0_WPORT PORTL #define PK4_PWM NULL
#define PL0_DDR DDRL #undef PK5
#define PL0_PWM NULL #define PK5_PIN PINK5
#undef PL1 #define PK5_RPORT PINK
#define PL1_PIN PINL1 #define PK5_WPORT PORTK
#define PL1_RPORT PINL #define PK5_DDR DDRK
#define PL1_WPORT PORTL #define PK5_PWM NULL
#define PL1_DDR DDRL #undef PK6
#define PL1_PWM NULL #define PK6_PIN PINK6
#undef PL2 #define PK6_RPORT PINK
#define PL2_PIN PINL2 #define PK6_WPORT PORTK
#define PL2_RPORT PINL #define PK6_DDR DDRK
#define PL2_WPORT PORTL #define PK6_PWM NULL
#define PL2_DDR DDRL #undef PK7
#define PL2_PWM NULL #define PK7_PIN PINK7
#undef PL3 #define PK7_RPORT PINK
#define PL3_PIN PINL3 #define PK7_WPORT PORTK
#define PL3_RPORT PINL #define PK7_DDR DDRK
#define PL3_WPORT PORTL #define PK7_PWM NULL
#define PL3_DDR DDRL
#define PL3_PWM &OCR5AL #undef PL0
#undef PL4 #define PL0_PIN PINL0
#define PL4_PIN PINL4 #define PL0_RPORT PINL
#define PL4_RPORT PINL #define PL0_WPORT PORTL
#define PL4_WPORT PORTL #define PL0_DDR DDRL
#define PL4_DDR DDRL #define PL0_PWM NULL
#define PL4_PWM &OCR5BL #undef PL1
#undef PL5 #define PL1_PIN PINL1
#define PL5_PIN PINL5 #define PL1_RPORT PINL
#define PL5_RPORT PINL #define PL1_WPORT PORTL
#define PL5_WPORT PORTL #define PL1_DDR DDRL
#define PL5_DDR DDRL #define PL1_PWM NULL
#define PL5_PWM &OCR5CL #undef PL2
#undef PL6 #define PL2_PIN PINL2
#define PL6_PIN PINL6 #define PL2_RPORT PINL
#define PL6_RPORT PINL #define PL2_WPORT PORTL
#define PL6_WPORT PORTL #define PL2_DDR DDRL
#define PL6_DDR DDRL #define PL2_PWM NULL
#define PL6_PWM NULL #undef PL3
#undef PL7 #define PL3_PIN PINL3
#define PL7_PIN PINL7 #define PL3_RPORT PINL
#define PL7_RPORT PINL #define PL3_WPORT PORTL
#define PL7_WPORT PORTL #define PL3_DDR DDRL
#define PL7_DDR DDRL #define PL3_PWM &OCR5AL
#define PL7_PWM NULL #undef PL4
#define PL4_PIN PINL4
#endif #define PL4_RPORT PINL
#define PL4_WPORT PORTL
#if defined (__AVR_AT90USB1287__) #define PL4_DDR DDRL
// SPI #define PL4_PWM &OCR5BL
#define SCK DIO9 #undef PL5
#define MISO DIO11 #define PL5_PIN PINL5
#define MOSI DIO10 #define PL5_RPORT PINL
#define SS DIO8 #define PL5_WPORT PORTL
#define PL5_DDR DDRL
// change for your board #define PL5_PWM &OCR5CL
#define DEBUG_LED DIO31 /* led D5 red */ #undef PL6
#define PL6_PIN PINL6
/* #define PL6_RPORT PINL
pins #define PL6_WPORT PORTL
*/ #define PL6_DDR DDRL
#define DIO0_PIN PINA0 #define PL6_PWM NULL
#define DIO0_RPORT PINA #undef PL7
#define DIO0_WPORT PORTA #define PL7_PIN PINL7
#define DIO0_PWM NULL #define PL7_RPORT PINL
#define DIO0_DDR DDRA #define PL7_WPORT PORTL
#define PL7_DDR DDRL
#define DIO1_PIN PINA1 #define PL7_PWM NULL
#define DIO1_RPORT PINA
#define DIO1_WPORT PORTA #endif
#define DIO1_PWM NULL
#define DIO1_DDR DDRA #if defined (__AVR_AT90USB1287__)
// SPI
#define DIO2_PIN PINA2 #define SCK DIO9
#define DIO2_RPORT PINA #define MISO DIO11
#define DIO2_WPORT PORTA #define MOSI DIO10
#define DIO2_PWM NULL #define SS DIO8
#define DIO2_DDR DDRA
// change for your board
#define DIO3_PIN PINA3 #define DEBUG_LED DIO31 /* led D5 red */
#define DIO3_RPORT PINA
#define DIO3_WPORT PORTA /*
#define DIO3_PWM NULL pins
#define DIO3_DDR DDRA */
#define DIO0_PIN PINA0
#define DIO4_PIN PINA4 #define DIO0_RPORT PINA
#define DIO4_RPORT PINA #define DIO0_WPORT PORTA
#define DIO4_WPORT PORTA #define DIO0_PWM NULL
#define DIO4_PWM NULL #define DIO0_DDR DDRA
#define DIO4_DDR DDRA
#define DIO1_PIN PINA1
#define DIO5_PIN PINA5 #define DIO1_RPORT PINA
#define DIO5_RPORT PINA #define DIO1_WPORT PORTA
#define DIO5_WPORT PORTA #define DIO1_PWM NULL
#define DIO5_PWM NULL #define DIO1_DDR DDRA
#define DIO5_DDR DDRA
#define DIO2_PIN PINA2
#define DIO6_PIN PINA6 #define DIO2_RPORT PINA
#define DIO6_RPORT PINA #define DIO2_WPORT PORTA
#define DIO6_WPORT PORTA #define DIO2_PWM NULL
#define DIO6_PWM NULL #define DIO2_DDR DDRA
#define DIO6_DDR DDRA
#define DIO3_PIN PINA3
#define DIO7_PIN PINA7 #define DIO3_RPORT PINA
#define DIO7_RPORT PINA #define DIO3_WPORT PORTA
#define DIO7_WPORT PORTA #define DIO3_PWM NULL
#define DIO7_PWM NULL #define DIO3_DDR DDRA
#define DIO7_DDR DDRA
#define DIO4_PIN PINA4
#define DIO8_PIN PINB0 #define DIO4_RPORT PINA
#define DIO8_RPORT PINB #define DIO4_WPORT PORTA
#define DIO8_WPORT PORTB #define DIO4_PWM NULL
#define DIO8_PWM NULL #define DIO4_DDR DDRA
#define DIO8_DDR DDRB
#define DIO5_PIN PINA5
#define DIO9_PIN PINB1 #define DIO5_RPORT PINA
#define DIO9_RPORT PINB #define DIO5_WPORT PORTA
#define DIO9_WPORT PORTB #define DIO5_PWM NULL
#define DIO9_PWM NULL #define DIO5_DDR DDRA
#define DIO9_DDR DDRB
#define DIO6_PIN PINA6
#define DIO10_PIN PINB2 #define DIO6_RPORT PINA
#define DIO10_RPORT PINB #define DIO6_WPORT PORTA
#define DIO10_WPORT PORTB #define DIO6_PWM NULL
#define DIO10_PWM NULL #define DIO6_DDR DDRA
#define DIO10_DDR DDRB
#define DIO7_PIN PINA7
#define DIO11_PIN PINB3 #define DIO7_RPORT PINA
#define DIO11_RPORT PINB #define DIO7_WPORT PORTA
#define DIO11_WPORT PORTB #define DIO7_PWM NULL
#define DIO11_PWM NULL #define DIO7_DDR DDRA
#define DIO11_DDR DDRB
#define DIO8_PIN PINB0
#define DIO12_PIN PINB4 #define DIO8_RPORT PINB
#define DIO12_RPORT PINB #define DIO8_WPORT PORTB
#define DIO12_WPORT PORTB #define DIO8_PWM NULL
#define DIO12_PWM NULL #define DIO8_DDR DDRB
#define DIO12_DDR DDRB
#define DIO9_PIN PINB1
#define DIO13_PIN PINB5 #define DIO9_RPORT PINB
#define DIO13_RPORT PINB #define DIO9_WPORT PORTB
#define DIO13_WPORT PORTB #define DIO9_PWM NULL
#define DIO13_PWM NULL #define DIO9_DDR DDRB
#define DIO13_DDR DDRB
#define DIO10_PIN PINB2
#define DIO14_PIN PINB6 #define DIO10_RPORT PINB
#define DIO14_RPORT PINB #define DIO10_WPORT PORTB
#define DIO14_WPORT PORTB #define DIO10_PWM NULL
#define DIO14_PWM NULL #define DIO10_DDR DDRB
#define DIO14_DDR DDRB
#define DIO11_PIN PINB3
#define DIO15_PIN PINB7 #define DIO11_RPORT PINB
#define DIO15_RPORT PINB #define DIO11_WPORT PORTB
#define DIO15_WPORT PORTB #define DIO11_PWM NULL
#define DIO15_PWM NULL #define DIO11_DDR DDRB
#define DIO15_DDR DDRB
#define DIO12_PIN PINB4
#define DIO16_PIN PINC0 #define DIO12_RPORT PINB
#define DIO16_RPORT PINC #define DIO12_WPORT PORTB
#define DIO16_WPORT PORTC #define DIO12_PWM NULL
#define DIO16_PWM NULL #define DIO12_DDR DDRB
#define DIO16_DDR DDRC
#define DIO13_PIN PINB5
#define DIO17_PIN PINC1 #define DIO13_RPORT PINB
#define DIO17_RPORT PINC #define DIO13_WPORT PORTB
#define DIO17_WPORT PORTC #define DIO13_PWM NULL
#define DIO17_PWM NULL #define DIO13_DDR DDRB
#define DIO17_DDR DDRC
#define DIO14_PIN PINB6
#define DIO18_PIN PINC2 #define DIO14_RPORT PINB
#define DIO18_RPORT PINC #define DIO14_WPORT PORTB
#define DIO18_WPORT PORTC #define DIO14_PWM NULL
#define DIO18_PWM NULL #define DIO14_DDR DDRB
#define DIO18_DDR DDRC
#define DIO15_PIN PINB7
#define DIO19_PIN PINC3 #define DIO15_RPORT PINB
#define DIO19_RPORT PINC #define DIO15_WPORT PORTB
#define DIO19_WPORT PORTC #define DIO15_PWM NULL
#define DIO19_PWM NULL #define DIO15_DDR DDRB
#define DIO19_DDR DDRC
#define DIO16_PIN PINC0
#define DIO20_PIN PINC4 #define DIO16_RPORT PINC
#define DIO20_RPORT PINC #define DIO16_WPORT PORTC
#define DIO20_WPORT PORTC #define DIO16_PWM NULL
#define DIO20_PWM NULL #define DIO16_DDR DDRC
#define DIO20_DDR DDRC
#define DIO17_PIN PINC1
#define DIO21_PIN PINC5 #define DIO17_RPORT PINC
#define DIO21_RPORT PINC #define DIO17_WPORT PORTC
#define DIO21_WPORT PORTC #define DIO17_PWM NULL
#define DIO21_PWM NULL #define DIO17_DDR DDRC
#define DIO21_DDR DDRC
#define DIO18_PIN PINC2
#define DIO22_PIN PINC6 #define DIO18_RPORT PINC
#define DIO22_RPORT PINC #define DIO18_WPORT PORTC
#define DIO22_WPORT PORTC #define DIO18_PWM NULL
#define DIO22_PWM NULL #define DIO18_DDR DDRC
#define DIO22_DDR DDRC
#define DIO19_PIN PINC3
#define DIO23_PIN PINC7 #define DIO19_RPORT PINC
#define DIO23_RPORT PINC #define DIO19_WPORT PORTC
#define DIO23_WPORT PORTC #define DIO19_PWM NULL
#define DIO23_PWM NULL #define DIO19_DDR DDRC
#define DIO23_DDR DDRC
#define DIO20_PIN PINC4
#define DIO24_PIN PIND0 #define DIO20_RPORT PINC
#define DIO24_RPORT PIND #define DIO20_WPORT PORTC
#define DIO24_WPORT PORTD #define DIO20_PWM NULL
#define DIO24_PWM NULL #define DIO20_DDR DDRC
#define DIO24_DDR DDRD
#define DIO21_PIN PINC5
#define DIO25_PIN PIND1 #define DIO21_RPORT PINC
#define DIO25_RPORT PIND #define DIO21_WPORT PORTC
#define DIO25_WPORT PORTD #define DIO21_PWM NULL
#define DIO25_PWM NULL #define DIO21_DDR DDRC
#define DIO25_DDR DDRD
#define DIO22_PIN PINC6
#define DIO26_PIN PIND2 #define DIO22_RPORT PINC
#define DIO26_RPORT PIND #define DIO22_WPORT PORTC
#define DIO26_WPORT PORTD #define DIO22_PWM NULL
#define DIO26_PWM NULL #define DIO22_DDR DDRC
#define DIO26_DDR DDRD
#define DIO23_PIN PINC7
#define DIO27_PIN PIND3 #define DIO23_RPORT PINC
#define DIO27_RPORT PIND #define DIO23_WPORT PORTC
#define DIO27_WPORT PORTD #define DIO23_PWM NULL
#define DIO27_PWM NULL #define DIO23_DDR DDRC
#define DIO27_DDR DDRD
#define DIO24_PIN PIND0
#define DIO28_PIN PIND4 #define DIO24_RPORT PIND
#define DIO28_RPORT PIND #define DIO24_WPORT PORTD
#define DIO28_WPORT PORTD #define DIO24_PWM NULL
#define DIO28_PWM NULL #define DIO24_DDR DDRD
#define DIO28_DDR DDRD
#define DIO25_PIN PIND1
#define DIO29_PIN PIND5 #define DIO25_RPORT PIND
#define DIO29_RPORT PIND #define DIO25_WPORT PORTD
#define DIO29_WPORT PORTD #define DIO25_PWM NULL
#define DIO29_PWM NULL #define DIO25_DDR DDRD
#define DIO29_DDR DDRD
#define DIO26_PIN PIND2
#define DIO30_PIN PIND6 #define DIO26_RPORT PIND
#define DIO30_RPORT PIND #define DIO26_WPORT PORTD
#define DIO30_WPORT PORTD #define DIO26_PWM NULL
#define DIO30_PWM NULL #define DIO26_DDR DDRD
#define DIO30_DDR DDRD
#define DIO27_PIN PIND3
#define DIO31_PIN PIND7 #define DIO27_RPORT PIND
#define DIO31_RPORT PIND #define DIO27_WPORT PORTD
#define DIO31_WPORT PORTD #define DIO27_PWM NULL
#define DIO31_PWM NULL #define DIO27_DDR DDRD
#define DIO31_DDR DDRD
#define DIO28_PIN PIND4
#define DIO28_RPORT PIND
#define DIO32_PIN PINE0 #define DIO28_WPORT PORTD
#define DIO32_RPORT PINE #define DIO28_PWM NULL
#define DIO32_WPORT PORTE #define DIO28_DDR DDRD
#define DIO32_PWM NULL
#define DIO32_DDR DDRE #define DIO29_PIN PIND5
#define DIO29_RPORT PIND
#define DIO33_PIN PINE1 #define DIO29_WPORT PORTD
#define DIO33_RPORT PINE #define DIO29_PWM NULL
#define DIO33_WPORT PORTE #define DIO29_DDR DDRD
#define DIO33_PWM NULL
#define DIO33_DDR DDRE #define DIO30_PIN PIND6
#define DIO30_RPORT PIND
#define DIO34_PIN PINE2 #define DIO30_WPORT PORTD
#define DIO34_RPORT PINE #define DIO30_PWM NULL
#define DIO34_WPORT PORTE #define DIO30_DDR DDRD
#define DIO34_PWM NULL
#define DIO34_DDR DDRE #define DIO31_PIN PIND7
#define DIO31_RPORT PIND
#define DIO35_PIN PINE3 #define DIO31_WPORT PORTD
#define DIO35_RPORT PINE #define DIO31_PWM NULL
#define DIO35_WPORT PORTE #define DIO31_DDR DDRD
#define DIO35_PWM NULL
#define DIO35_DDR DDRE
#define DIO32_PIN PINE0
#define DIO36_PIN PINE4 #define DIO32_RPORT PINE
#define DIO36_RPORT PINE #define DIO32_WPORT PORTE
#define DIO36_WPORT PORTE #define DIO32_PWM NULL
#define DIO36_PWM NULL #define DIO32_DDR DDRE
#define DIO36_DDR DDRE
#define DIO33_PIN PINE1
#define DIO37_PIN PINE5 #define DIO33_RPORT PINE
#define DIO37_RPORT PINE #define DIO33_WPORT PORTE
#define DIO37_WPORT PORTE #define DIO33_PWM NULL
#define DIO37_PWM NULL #define DIO33_DDR DDRE
#define DIO37_DDR DDRE
#define DIO34_PIN PINE2
#define DIO38_PIN PINE6 #define DIO34_RPORT PINE
#define DIO38_RPORT PINE #define DIO34_WPORT PORTE
#define DIO38_WPORT PORTE #define DIO34_PWM NULL
#define DIO38_PWM NULL #define DIO34_DDR DDRE
#define DIO38_DDR DDRE
#define DIO35_PIN PINE3
#define DIO39_PIN PINE7 #define DIO35_RPORT PINE
#define DIO39_RPORT PINE #define DIO35_WPORT PORTE
#define DIO39_WPORT PORTE #define DIO35_PWM NULL
#define DIO39_PWM NULL #define DIO35_DDR DDRE
#define DIO39_DDR DDRE
#define DIO36_PIN PINE4
#define AIO0_PIN PINF0 #define DIO36_RPORT PINE
#define AIO0_RPORT PINF #define DIO36_WPORT PORTE
#define AIO0_WPORT PORTF #define DIO36_PWM NULL
#define AIO0_PWM NULL #define DIO36_DDR DDRE
#define AIO0_DDR DDRF
#define DIO37_PIN PINE5
#define AIO1_PIN PINF1 #define DIO37_RPORT PINE
#define AIO1_RPORT PINF #define DIO37_WPORT PORTE
#define AIO1_WPORT PORTF #define DIO37_PWM NULL
#define AIO1_PWM NULL #define DIO37_DDR DDRE
#define AIO1_DDR DDRF
#define DIO38_PIN PINE6
#define AIO2_PIN PINF2 #define DIO38_RPORT PINE
#define AIO2_RPORT PINF #define DIO38_WPORT PORTE
#define AIO2_WPORT PORTF #define DIO38_PWM NULL
#define AIO2_PWM NULL #define DIO38_DDR DDRE
#define AIO2_DDR DDRF
#define DIO39_PIN PINE7
#define AIO3_PIN PINF3 #define DIO39_RPORT PINE
#define AIO3_RPORT PINF #define DIO39_WPORT PORTE
#define AIO3_WPORT PORTF #define DIO39_PWM NULL
#define AIO3_PWM NULL #define DIO39_DDR DDRE
#define AIO3_DDR DDRF
#define AIO0_PIN PINF0
#define AIO4_PIN PINF4 #define AIO0_RPORT PINF
#define AIO4_RPORT PINF #define AIO0_WPORT PORTF
#define AIO4_WPORT PORTF #define AIO0_PWM NULL
#define AIO4_PWM NULL #define AIO0_DDR DDRF
#define AIO4_DDR DDRF
#define AIO1_PIN PINF1
#define AIO5_PIN PINF5 #define AIO1_RPORT PINF
#define AIO5_RPORT PINF #define AIO1_WPORT PORTF
#define AIO5_WPORT PORTF #define AIO1_PWM NULL
#define AIO5_PWM NULL #define AIO1_DDR DDRF
#define AIO5_DDR DDRF
#define AIO2_PIN PINF2
#define AIO6_PIN PINF6 #define AIO2_RPORT PINF
#define AIO6_RPORT PINF #define AIO2_WPORT PORTF
#define AIO6_WPORT PORTF #define AIO2_PWM NULL
#define AIO6_PWM NULL #define AIO2_DDR DDRF
#define AIO6_DDR DDRF
#define AIO3_PIN PINF3
#define AIO7_PIN PINF7 #define AIO3_RPORT PINF
#define AIO7_RPORT PINF #define AIO3_WPORT PORTF
#define AIO7_WPORT PORTF #define AIO3_PWM NULL
#define AIO7_PWM NULL #define AIO3_DDR DDRF
#define AIO7_DDR DDRF
#define AIO4_PIN PINF4
#define DIO40_PIN PINF0 #define AIO4_RPORT PINF
#define DIO40_RPORT PINF #define AIO4_WPORT PORTF
#define DIO40_WPORT PORTF #define AIO4_PWM NULL
#define DIO40_PWM NULL #define AIO4_DDR DDRF
#define DIO40_DDR DDRF
#define AIO5_PIN PINF5
#define DIO41_PIN PINF1 #define AIO5_RPORT PINF
#define DIO41_RPORT PINF #define AIO5_WPORT PORTF
#define DIO41_WPORT PORTF #define AIO5_PWM NULL
#define DIO41_PWM NULL #define AIO5_DDR DDRF
#define DIO41_DDR DDRF
#define AIO6_PIN PINF6
#define DIO42_PIN PINF2 #define AIO6_RPORT PINF
#define DIO42_RPORT PINF #define AIO6_WPORT PORTF
#define DIO42_WPORT PORTF #define AIO6_PWM NULL
#define DIO42_PWM NULL #define AIO6_DDR DDRF
#define DIO42_DDR DDRF
#define AIO7_PIN PINF7
#define DIO43_PIN PINF3 #define AIO7_RPORT PINF
#define DIO43_RPORT PINF #define AIO7_WPORT PORTF
#define DIO43_WPORT PORTF #define AIO7_PWM NULL
#define DIO43_PWM NULL #define AIO7_DDR DDRF
#define DIO43_DDR DDRF
#define DIO40_PIN PINF0
#define DIO44_PIN PINF4 #define DIO40_RPORT PINF
#define DIO44_RPORT PINF #define DIO40_WPORT PORTF
#define DIO44_WPORT PORTF #define DIO40_PWM NULL
#define DIO44_PWM NULL #define DIO40_DDR DDRF
#define DIO44_DDR DDRF
#define DIO41_PIN PINF1
#define DIO45_PIN PINF5 #define DIO41_RPORT PINF
#define DIO45_RPORT PINF #define DIO41_WPORT PORTF
#define DIO45_WPORT PORTF #define DIO41_PWM NULL
#define DIO45_PWM NULL #define DIO41_DDR DDRF
#define DIO45_DDR DDRF
#define DIO42_PIN PINF2
#define DIO46_PIN PINF6 #define DIO42_RPORT PINF
#define DIO46_RPORT PINF #define DIO42_WPORT PORTF
#define DIO46_WPORT PORTF #define DIO42_PWM NULL
#define DIO46_PWM NULL #define DIO42_DDR DDRF
#define DIO46_DDR DDRF
#define DIO43_PIN PINF3
#define DIO47_PIN PINF7 #define DIO43_RPORT PINF
#define DIO47_RPORT PINF #define DIO43_WPORT PORTF
#define DIO47_WPORT PORTF #define DIO43_PWM NULL
#define DIO47_PWM NULL #define DIO43_DDR DDRF
#define DIO47_DDR DDRF
#define DIO44_PIN PINF4
#define DIO44_RPORT PINF
#define DIO44_WPORT PORTF
#undef PA0 #define DIO44_PWM NULL
#define PA0_PIN PINA0 #define DIO44_DDR DDRF
#define PA0_RPORT PINA
#define PA0_WPORT PORTA #define DIO45_PIN PINF5
#define PA0_PWM NULL #define DIO45_RPORT PINF
#define PA0_DDR DDRA #define DIO45_WPORT PORTF
#undef PA1 #define DIO45_PWM NULL
#define PA1_PIN PINA1 #define DIO45_DDR DDRF
#define PA1_RPORT PINA
#define PA1_WPORT PORTA #define DIO46_PIN PINF6
#define PA1_PWM NULL #define DIO46_RPORT PINF
#define PA1_DDR DDRA #define DIO46_WPORT PORTF
#undef PA2 #define DIO46_PWM NULL
#define PA2_PIN PINA2 #define DIO46_DDR DDRF
#define PA2_RPORT PINA
#define PA2_WPORT PORTA #define DIO47_PIN PINF7
#define PA2_PWM NULL #define DIO47_RPORT PINF
#define PA2_DDR DDRA #define DIO47_WPORT PORTF
#undef PA3 #define DIO47_PWM NULL
#define PA3_PIN PINA3 #define DIO47_DDR DDRF
#define PA3_RPORT PINA
#define PA3_WPORT PORTA
#define PA3_PWM NULL
#define PA3_DDR DDRA #undef PA0
#undef PA4 #define PA0_PIN PINA0
#define PA4_PIN PINA4 #define PA0_RPORT PINA
#define PA4_RPORT PINA #define PA0_WPORT PORTA
#define PA4_WPORT PORTA #define PA0_PWM NULL
#define PA4_PWM NULL #define PA0_DDR DDRA
#define PA4_DDR DDRA #undef PA1
#undef PA5 #define PA1_PIN PINA1
#define PA5_PIN PINA5 #define PA1_RPORT PINA
#define PA5_RPORT PINA #define PA1_WPORT PORTA
#define PA5_WPORT PORTA #define PA1_PWM NULL
#define PA5_PWM NULL #define PA1_DDR DDRA
#define PA5_DDR DDRA #undef PA2
#undef PA6 #define PA2_PIN PINA2
#define PA6_PIN PINA6 #define PA2_RPORT PINA
#define PA6_RPORT PINA #define PA2_WPORT PORTA
#define PA6_WPORT PORTA #define PA2_PWM NULL
#define PA6_PWM NULL #define PA2_DDR DDRA
#define PA6_DDR DDRA #undef PA3
#undef PA7 #define PA3_PIN PINA3
#define PA7_PIN PINA7 #define PA3_RPORT PINA
#define PA7_RPORT PINA #define PA3_WPORT PORTA
#define PA7_WPORT PORTA #define PA3_PWM NULL
#define PA7_PWM NULL #define PA3_DDR DDRA
#define PA7_DDR DDRA #undef PA4
#define PA4_PIN PINA4
#undef PB0 #define PA4_RPORT PINA
#define PB0_PIN PINB0 #define PA4_WPORT PORTA
#define PB0_RPORT PINB #define PA4_PWM NULL
#define PB0_WPORT PORTB #define PA4_DDR DDRA
#define PB0_PWM NULL #undef PA5
#define PB0_DDR DDRB #define PA5_PIN PINA5
#undef PB1 #define PA5_RPORT PINA
#define PB1_PIN PINB1 #define PA5_WPORT PORTA
#define PB1_RPORT PINB #define PA5_PWM NULL
#define PB1_WPORT PORTB #define PA5_DDR DDRA
#define PB1_PWM NULL #undef PA6
#define PB1_DDR DDRB #define PA6_PIN PINA6
#undef PB2 #define PA6_RPORT PINA
#define PB2_PIN PINB2 #define PA6_WPORT PORTA
#define PB2_RPORT PINB #define PA6_PWM NULL
#define PB2_WPORT PORTB #define PA6_DDR DDRA
#define PB2_PWM NULL #undef PA7
#define PB2_DDR DDRB #define PA7_PIN PINA7
#undef PB3 #define PA7_RPORT PINA
#define PB3_PIN PINB3 #define PA7_WPORT PORTA
#define PB3_RPORT PINB #define PA7_PWM NULL
#define PB3_WPORT PORTB #define PA7_DDR DDRA
#define PB3_PWM NULL
#define PB3_DDR DDRB #undef PB0
#undef PB4 #define PB0_PIN PINB0
#define PB4_PIN PINB4 #define PB0_RPORT PINB
#define PB4_RPORT PINB #define PB0_WPORT PORTB
#define PB4_WPORT PORTB #define PB0_PWM NULL
#define PB4_PWM NULL #define PB0_DDR DDRB
#define PB4_DDR DDRB #undef PB1
#undef PB5 #define PB1_PIN PINB1
#define PB5_PIN PINB5 #define PB1_RPORT PINB
#define PB5_RPORT PINB #define PB1_WPORT PORTB
#define PB5_WPORT PORTB #define PB1_PWM NULL
#define PB5_PWM NULL #define PB1_DDR DDRB
#define PB5_DDR DDRB #undef PB2
#undef PB6 #define PB2_PIN PINB2
#define PB6_PIN PINB6 #define PB2_RPORT PINB
#define PB6_RPORT PINB #define PB2_WPORT PORTB
#define PB6_WPORT PORTB #define PB2_PWM NULL
#define PB6_PWM NULL #define PB2_DDR DDRB
#define PB6_DDR DDRB #undef PB3
#undef PB7 #define PB3_PIN PINB3
#define PB7_PIN PINB7 #define PB3_RPORT PINB
#define PB7_RPORT PINB #define PB3_WPORT PORTB
#define PB7_WPORT PORTB #define PB3_PWM NULL
#define PB7_PWM NULL #define PB3_DDR DDRB
#define PB7_DDR DDRB #undef PB4
#define PB4_PIN PINB4
#undef PC0 #define PB4_RPORT PINB
#define PC0_PIN PINC0 #define PB4_WPORT PORTB
#define PC0_RPORT PINC #define PB4_PWM NULL
#define PC0_WPORT PORTC #define PB4_DDR DDRB
#define PC0_PWM NULL #undef PB5
#define PC0_DDR DDRC #define PB5_PIN PINB5
#undef PC1 #define PB5_RPORT PINB
#define PC1_PIN PINC1 #define PB5_WPORT PORTB
#define PC1_RPORT PINC #define PB5_PWM NULL
#define PC1_WPORT PORTC #define PB5_DDR DDRB
#define PC1_PWM NULL #undef PB6
#define PC1_DDR DDRC #define PB6_PIN PINB6
#undef PC2 #define PB6_RPORT PINB
#define PC2_PIN PINC2 #define PB6_WPORT PORTB
#define PC2_RPORT PINC #define PB6_PWM NULL
#define PC2_WPORT PORTC #define PB6_DDR DDRB
#define PC2_PWM NULL #undef PB7
#define PC2_DDR DDRC #define PB7_PIN PINB7
#undef PC3 #define PB7_RPORT PINB
#define PC3_PIN PINC3 #define PB7_WPORT PORTB
#define PC3_RPORT PINC #define PB7_PWM NULL
#define PC3_WPORT PORTC #define PB7_DDR DDRB
#define PC3_PWM NULL
#define PC3_DDR DDRC #undef PC0
#undef PC4 #define PC0_PIN PINC0
#define PC4_PIN PINC4 #define PC0_RPORT PINC
#define PC4_RPORT PINC #define PC0_WPORT PORTC
#define PC4_WPORT PORTC #define PC0_PWM NULL
#define PC4_PWM NULL #define PC0_DDR DDRC
#define PC4_DDR DDRC #undef PC1
#undef PC5 #define PC1_PIN PINC1
#define PC5_PIN PINC5 #define PC1_RPORT PINC
#define PC5_RPORT PINC #define PC1_WPORT PORTC
#define PC5_WPORT PORTC #define PC1_PWM NULL
#define PC5_PWM NULL #define PC1_DDR DDRC
#define PC5_DDR DDRC #undef PC2
#undef PC6 #define PC2_PIN PINC2
#define PC6_PIN PINC6 #define PC2_RPORT PINC
#define PC6_RPORT PINC #define PC2_WPORT PORTC
#define PC6_WPORT PORTC #define PC2_PWM NULL
#define PC6_PWM NULL #define PC2_DDR DDRC
#define PC6_DDR DDRC #undef PC3
#undef PC7 #define PC3_PIN PINC3
#define PC7_PIN PINC7 #define PC3_RPORT PINC
#define PC7_RPORT PINC #define PC3_WPORT PORTC
#define PC7_WPORT PORTC #define PC3_PWM NULL
#define PC7_PWM NULL #define PC3_DDR DDRC
#define PC7_DDR DDRC #undef PC4
#define PC4_PIN PINC4
#undef PD0 #define PC4_RPORT PINC
#define PD0_PIN PIND0 #define PC4_WPORT PORTC
#define PD0_RPORT PIND #define PC4_PWM NULL
#define PD0_WPORT PORTD #define PC4_DDR DDRC
#define PD0_PWM NULL #undef PC5
#define PD0_DDR DDRD #define PC5_PIN PINC5
#undef PD1 #define PC5_RPORT PINC
#define PD1_PIN PIND1 #define PC5_WPORT PORTC
#define PD1_RPORT PIND #define PC5_PWM NULL
#define PD1_WPORT PORTD #define PC5_DDR DDRC
#define PD1_PWM NULL #undef PC6
#define PD1_DDR DDRD #define PC6_PIN PINC6
#undef PD2 #define PC6_RPORT PINC
#define PD2_PIN PIND2 #define PC6_WPORT PORTC
#define PD2_RPORT PIND #define PC6_PWM NULL
#define PD2_WPORT PORTD #define PC6_DDR DDRC
#define PD2_PWM NULL #undef PC7
#define PD2_DDR DDRD #define PC7_PIN PINC7
#undef PD3 #define PC7_RPORT PINC
#define PD3_PIN PIND3 #define PC7_WPORT PORTC
#define PD3_RPORT PIND #define PC7_PWM NULL
#define PD3_WPORT PORTD #define PC7_DDR DDRC
#define PD3_PWM NULL
#define PD3_DDR DDRD #undef PD0
#undef PD4 #define PD0_PIN PIND0
#define PD4_PIN PIND4 #define PD0_RPORT PIND
#define PD4_RPORT PIND #define PD0_WPORT PORTD
#define PD4_WPORT PORTD #define PD0_PWM NULL
#define PD4_PWM NULL #define PD0_DDR DDRD
#define PD4_DDR DDRD #undef PD1
#undef PD5 #define PD1_PIN PIND1
#define PD5_PIN PIND5 #define PD1_RPORT PIND
#define PD5_RPORT PIND #define PD1_WPORT PORTD
#define PD5_WPORT PORTD #define PD1_PWM NULL
#define PD5_PWM NULL #define PD1_DDR DDRD
#define PD5_DDR DDRD #undef PD2
#undef PD6 #define PD2_PIN PIND2
#define PD6_PIN PIND6 #define PD2_RPORT PIND
#define PD6_RPORT PIND #define PD2_WPORT PORTD
#define PD6_WPORT PORTD #define PD2_PWM NULL
#define PD6_PWM NULL #define PD2_DDR DDRD
#define PD6_DDR DDRD #undef PD3
#undef PD7 #define PD3_PIN PIND3
#define PD7_PIN PIND7 #define PD3_RPORT PIND
#define PD7_RPORT PIND #define PD3_WPORT PORTD
#define PD7_WPORT PORTD #define PD3_PWM NULL
#define PD7_PWM NULL #define PD3_DDR DDRD
#define PD7_DDR DDRD #undef PD4
#define PD4_PIN PIND4
#undef PE0 #define PD4_RPORT PIND
#define PE0_PIN PINE0 #define PD4_WPORT PORTD
#define PE0_RPORT PINE #define PD4_PWM NULL
#define PE0_WPORT PORTE #define PD4_DDR DDRD
#define PE0_PWM NULL #undef PD5
#define PE0_DDR DDRE #define PD5_PIN PIND5
#undef PE1 #define PD5_RPORT PIND
#define PE1_PIN PINE1 #define PD5_WPORT PORTD
#define PE1_RPORT PINE #define PD5_PWM NULL
#define PE1_WPORT PORTE #define PD5_DDR DDRD
#define PE1_PWM NULL #undef PD6
#define PE1_DDR DDRE #define PD6_PIN PIND6
#undef PE2 #define PD6_RPORT PIND
#define PE2_PIN PINE2 #define PD6_WPORT PORTD
#define PE2_RPORT PINE #define PD6_PWM NULL
#define PE2_WPORT PORTE #define PD6_DDR DDRD
#define PE2_PWM NULL #undef PD7
#define PE2_DDR DDRE #define PD7_PIN PIND7
#undef PE3 #define PD7_RPORT PIND
#define PE3_PIN PINE3 #define PD7_WPORT PORTD
#define PE3_RPORT PINE #define PD7_PWM NULL
#define PE3_WPORT PORTE #define PD7_DDR DDRD
#define PE3_PWM NULL
#define PE3_DDR DDRE #undef PE0
#undef PE4 #define PE0_PIN PINE0
#define PE4_PIN PINE4 #define PE0_RPORT PINE
#define PE4_RPORT PINE #define PE0_WPORT PORTE
#define PE4_WPORT PORTE #define PE0_PWM NULL
#define PE4_PWM NULL #define PE0_DDR DDRE
#define PE4_DDR DDRE #undef PE1
#undef PE5 #define PE1_PIN PINE1
#define PE5_PIN PINE5 #define PE1_RPORT PINE
#define PE5_RPORT PINE #define PE1_WPORT PORTE
#define PE5_WPORT PORTE #define PE1_PWM NULL
#define PE5_PWM NULL #define PE1_DDR DDRE
#define PE5_DDR DDRE #undef PE2
#undef PE6 #define PE2_PIN PINE2
#define PE6_PIN PINE6 #define PE2_RPORT PINE
#define PE6_RPORT PINE #define PE2_WPORT PORTE
#define PE6_WPORT PORTE #define PE2_PWM NULL
#define PE6_PWM NULL #define PE2_DDR DDRE
#define PE6_DDR DDRE #undef PE3
#undef PE7 #define PE3_PIN PINE3
#define PE7_PIN PINE7 #define PE3_RPORT PINE
#define PE7_RPORT PINE #define PE3_WPORT PORTE
#define PE7_WPORT PORTE #define PE3_PWM NULL
#define PE7_PWM NULL #define PE3_DDR DDRE
#define PE7_DDR DDRE #undef PE4
#define PE4_PIN PINE4
#undef PF0 #define PE4_RPORT PINE
#define PF0_PIN PINF0 #define PE4_WPORT PORTE
#define PF0_RPORT PINF #define PE4_PWM NULL
#define PF0_WPORT PORTF #define PE4_DDR DDRE
#define PF0_PWM NULL #undef PE5
#define PF0_DDR DDRF #define PE5_PIN PINE5
#undef PF1 #define PE5_RPORT PINE
#define PF1_PIN PINF1 #define PE5_WPORT PORTE
#define PF1_RPORT PINF #define PE5_PWM NULL
#define PF1_WPORT PORTF #define PE5_DDR DDRE
#define PF1_PWM NULL #undef PE6
#define PF1_DDR DDRF #define PE6_PIN PINE6
#undef PF2 #define PE6_RPORT PINE
#define PF2_PIN PINF2 #define PE6_WPORT PORTE
#define PF2_RPORT PINF #define PE6_PWM NULL
#define PF2_WPORT PORTF #define PE6_DDR DDRE
#define PF2_PWM NULL #undef PE7
#define PF2_DDR DDRF #define PE7_PIN PINE7
#undef PF3 #define PE7_RPORT PINE
#define PF3_PIN PINF3 #define PE7_WPORT PORTE
#define PF3_RPORT PINF #define PE7_PWM NULL
#define PF3_WPORT PORTF #define PE7_DDR DDRE
#define PF3_PWM NULL
#define PF3_DDR DDRF #undef PF0
#undef PF4 #define PF0_PIN PINF0
#define PF4_PIN PINF4 #define PF0_RPORT PINF
#define PF4_RPORT PINF #define PF0_WPORT PORTF
#define PF4_WPORT PORTF #define PF0_PWM NULL
#define PF4_PWM NULL #define PF0_DDR DDRF
#define PF4_DDR DDRF #undef PF1
#undef PF5 #define PF1_PIN PINF1
#define PF5_PIN PINF5 #define PF1_RPORT PINF
#define PF5_RPORT PINF #define PF1_WPORT PORTF
#define PF5_WPORT PORTF #define PF1_PWM NULL
#define PF5_PWM NULL #define PF1_DDR DDRF
#define PF5_DDR DDRF #undef PF2
#undef PF6 #define PF2_PIN PINF2
#define PF6_PIN PINF6 #define PF2_RPORT PINF
#define PF6_RPORT PINF #define PF2_WPORT PORTF
#define PF6_WPORT PORTF #define PF2_PWM NULL
#define PF6_PWM NULL #define PF2_DDR DDRF
#define PF6_DDR DDRF #undef PF3
#undef PF7 #define PF3_PIN PINF3
#define PF7_PIN PINF7 #define PF3_RPORT PINF
#define PF7_RPORT PINF #define PF3_WPORT PORTF
#define PF7_WPORT PORTF #define PF3_PWM NULL
#define PF7_PWM NULL #define PF3_DDR DDRF
#define PF7_DDR DDRF #undef PF4
#endif #define PF4_PIN PINF4
#define PF4_RPORT PINF
#ifndef DIO0_PIN #define PF4_WPORT PORTF
#error pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please submit a pull request #define PF4_PWM NULL
#endif #define PF4_DDR DDRF
#undef PF5
#define PF5_PIN PINF5
#define PF5_RPORT PINF
#define PF5_WPORT PORTF
#define PF5_PWM NULL
#define PF5_DDR DDRF
#undef PF6
#define PF6_PIN PINF6
#define PF6_RPORT PINF
#define PF6_WPORT PORTF
#define PF6_PWM NULL
#define PF6_DDR DDRF
#undef PF7
#define PF7_PIN PINF7
#define PF7_RPORT PINF
#define PF7_WPORT PORTF
#define PF7_PWM NULL
#define PF7_DDR DDRF
#endif
#ifndef DIO0_PIN
#error pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please submit a pull request
#endif
#endif /* _ARDUINO_H */ #endif /* _ARDUINO_H */

View file

@ -1,695 +1,737 @@
#ifndef PINS_H #ifndef PINS_H
#define PINS_H #define PINS_H
/**************************************************************************************** /****************************************************************************************
* Arduino pin assignment * Arduino pin assignment
* *
* ATMega168 * ATMega168
* +-\/-+ * +-\/-+
* PC6 1| |28 PC5 (AI 5 / D19) * PC6 1| |28 PC5 (AI 5 / D19)
* (D 0) PD0 2| |27 PC4 (AI 4 / D18) * (D 0) PD0 2| |27 PC4 (AI 4 / D18)
* (D 1) PD1 3| |26 PC3 (AI 3 / D17) * (D 1) PD1 3| |26 PC3 (AI 3 / D17)
* (D 2) PD2 4| |25 PC2 (AI 2 / D16) * (D 2) PD2 4| |25 PC2 (AI 2 / D16)
* PWM+ (D 3) PD3 5| |24 PC1 (AI 1 / D15) * PWM+ (D 3) PD3 5| |24 PC1 (AI 1 / D15)
* (D 4) PD4 6| |23 PC0 (AI 0 / D14) * (D 4) PD4 6| |23 PC0 (AI 0 / D14)
* VCC 7| |22 GND * VCC 7| |22 GND
* GND 8| |21 AREF * GND 8| |21 AREF
* PB6 9| |20 AVCC * PB6 9| |20 AVCC
* PB7 10| |19 PB5 (D 13) * PB7 10| |19 PB5 (D 13)
* PWM+ (D 5) PD5 11| |18 PB4 (D 12) * PWM+ (D 5) PD5 11| |18 PB4 (D 12)
* PWM+ (D 6) PD6 12| |17 PB3 (D 11) PWM * PWM+ (D 6) PD6 12| |17 PB3 (D 11) PWM
* (D 7) PD7 13| |16 PB2 (D 10) PWM * (D 7) PD7 13| |16 PB2 (D 10) PWM
* (D 8) PB0 14| |15 PB1 (D 9) PWM * (D 8) PB0 14| |15 PB1 (D 9) PWM
* +----+ * +----+
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 0 #if MOTHERBOARD == 0
#define KNOWN_BOARD 1 #define KNOWN_BOARD 1
#ifndef __AVR_ATmega168__ #ifndef __AVR_ATmega168__
#error Oops! Make sure you have 'Arduino Diecimila' selected from the boards menu. #error Oops! Make sure you have 'Arduino Diecimila' selected from the boards menu.
#endif #endif
#define X_STEP_PIN 2 #define X_STEP_PIN 2
#define X_DIR_PIN 3 #define X_DIR_PIN 3
#define X_ENABLE_PIN -1 #define X_ENABLE_PIN -1
#define X_MIN_PIN 4 #define X_MIN_PIN 4
#define X_MAX_PIN 9 #define X_MAX_PIN 9
#define Y_STEP_PIN 10 #define Y_STEP_PIN 10
#define Y_DIR_PIN 7 #define Y_DIR_PIN 7
#define Y_ENABLE_PIN -1 #define Y_ENABLE_PIN -1
#define Y_MIN_PIN 8 #define Y_MIN_PIN 8
#define Y_MAX_PIN 13 #define Y_MAX_PIN 13
#define Z_STEP_PIN 19 #define Z_STEP_PIN 19
#define Z_DIR_PIN 18 #define Z_DIR_PIN 18
#define Z_ENABLE_PIN 5 #define Z_ENABLE_PIN 5
#define Z_MIN_PIN 17 #define Z_MIN_PIN 17
#define Z_MAX_PIN 16 #define Z_MAX_PIN 16
#define E_STEP_PIN 11 #define E0_STEP_PIN 11
#define E_DIR_PIN 12 #define E0_DIR_PIN 12
#define E_ENABLE_PIN -1 #define E0_ENABLE_PIN -1
#define SDPOWER -1 #define SDPOWER -1
#define SDSS -1 #define SDSS -1
#define LED_PIN -1 #define LED_PIN -1
#define FAN_PIN -1 #define FAN_PIN -1
#define PS_ON_PIN 15 #define PS_ON_PIN 15
#define KILL_PIN -1 #define KILL_PIN -1
#define HEATER_0_PIN 6 #define HEATER_0_PIN 6
#define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define HEATER_1_PIN -1
#define HEATER_1_PIN -1 #define HEATER_2_PIN -1
#define HEATER_2_PIN -1 #define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#endif #define TEMP_1_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define TEMP_2_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define HEATER_BED_PIN -1
#define TEMP_BED_PIN -1
/**************************************************************************************** #endif
* Sanguino/RepRap Motherboard with direct-drive extruders
*
* ATMega644P
* /****************************************************************************************
* +---\/---+ * Sanguino/RepRap Motherboard with direct-drive extruders
* (D 0) PB0 1| |40 PA0 (AI 0 / D31) *
* (D 1) PB1 2| |39 PA1 (AI 1 / D30) * ATMega644P
* INT2 (D 2) PB2 3| |38 PA2 (AI 2 / D29) *
* PWM (D 3) PB3 4| |37 PA3 (AI 3 / D28) * +---\/---+
* PWM (D 4) PB4 5| |36 PA4 (AI 4 / D27) * (D 0) PB0 1| |40 PA0 (AI 0 / D31)
* MOSI (D 5) PB5 6| |35 PA5 (AI 5 / D26) * (D 1) PB1 2| |39 PA1 (AI 1 / D30)
* MISO (D 6) PB6 7| |34 PA6 (AI 6 / D25) * INT2 (D 2) PB2 3| |38 PA2 (AI 2 / D29)
* SCK (D 7) PB7 8| |33 PA7 (AI 7 / D24) * PWM (D 3) PB3 4| |37 PA3 (AI 3 / D28)
* RST 9| |32 AREF * PWM (D 4) PB4 5| |36 PA4 (AI 4 / D27)
* VCC 10| |31 GND * MOSI (D 5) PB5 6| |35 PA5 (AI 5 / D26)
* GND 11| |30 AVCC * MISO (D 6) PB6 7| |34 PA6 (AI 6 / D25)
* XTAL2 12| |29 PC7 (D 23) * SCK (D 7) PB7 8| |33 PA7 (AI 7 / D24)
* XTAL1 13| |28 PC6 (D 22) * RST 9| |32 AREF
* RX0 (D 8) PD0 14| |27 PC5 (D 21) TDI * VCC 10| |31 GND
* TX0 (D 9) PD1 15| |26 PC4 (D 20) TDO * GND 11| |30 AVCC
* INT0 RX1 (D 10) PD2 16| |25 PC3 (D 19) TMS * XTAL2 12| |29 PC7 (D 23)
* INT1 TX1 (D 11) PD3 17| |24 PC2 (D 18) TCK * XTAL1 13| |28 PC6 (D 22)
* PWM (D 12) PD4 18| |23 PC1 (D 17) SDA * RX0 (D 8) PD0 14| |27 PC5 (D 21) TDI
* PWM (D 13) PD5 19| |22 PC0 (D 16) SCL * TX0 (D 9) PD1 15| |26 PC4 (D 20) TDO
* PWM (D 14) PD6 20| |21 PD7 (D 15) PWM * INT0 RX1 (D 10) PD2 16| |25 PC3 (D 19) TMS
* +--------+ * INT1 TX1 (D 11) PD3 17| |24 PC2 (D 18) TCK
* * PWM (D 12) PD4 18| |23 PC1 (D 17) SDA
****************************************************************************************/ * PWM (D 13) PD5 19| |22 PC0 (D 16) SCL
#if MOTHERBOARD == 1 * PWM (D 14) PD6 20| |21 PD7 (D 15) PWM
#define KNOWN_BOARD 1 * +--------+
*
#ifndef __AVR_ATmega644P__ ****************************************************************************************/
#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #if MOTHERBOARD == 1
#endif #define KNOWN_BOARD 1
#define X_STEP_PIN 15 #ifndef __AVR_ATmega644P__
#define X_DIR_PIN 18 #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
#define X_ENABLE_PIN 19 #endif
#define X_MIN_PIN 20
#define X_MAX_PIN 21 #define X_STEP_PIN 15
#define X_DIR_PIN 18
#define Y_STEP_PIN 23 #define X_ENABLE_PIN 19
#define Y_DIR_PIN 22 #define X_MIN_PIN 20
#define Y_ENABLE_PIN 19 #define X_MAX_PIN 21
#define Y_MIN_PIN 25
#define Y_MAX_PIN 26 #define Y_STEP_PIN 23
#define Y_DIR_PIN 22
#define Z_STEP_PIN 29 #define Y_ENABLE_PIN 19
#define Z_DIR_PIN 30 #define Y_MIN_PIN 25
#define Z_ENABLE_PIN 31 #define Y_MAX_PIN 26
#define Z_MIN_PIN 2
#define Z_MAX_PIN 1 #define Z_STEP_PIN 29
#define Z_DIR_PIN 30
#define E_STEP_PIN 12 #define Z_ENABLE_PIN 31
#define E_DIR_PIN 16 #define Z_MIN_PIN 2
#define E_ENABLE_PIN 3 #define Z_MAX_PIN 1
#define SDPOWER -1 #define E0_STEP_PIN 12
#define SDSS -1 #define E0_DIR_PIN 16
#define LED_PIN 0 #define E0_ENABLE_PIN 3
#define FAN_PIN -1
#define PS_ON_PIN -1 #define SDPOWER -1
#define KILL_PIN -1 #define SDSS -1
#define LED_PIN 0
#define HEATER_0_PIN 14 #define FAN_PIN -1
#define TEMP_0_PIN 4 //D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define PS_ON_PIN -1
#define HEATER_1_PIN -1 #define KILL_PIN -1
#define HEATER_2_PIN -1
/* Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31) */ #define HEATER_0_PIN 14
#define HEATER_1_PIN -1
#define HEATER_2_PIN -1
#define TEMP_0_PIN 4 //D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#endif #define TEMP_1_PIN -1
#define TEMP_2_PIN -1
#define HEATER_BED_PIN -1
/**************************************************************************************** #define TEMP_BED_PIN -1
* RepRap Motherboard ****---NOOOOOO RS485/EXTRUDER CONTROLLER!!!!!!!!!!!!!!!!!---******* /* Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31) */
*
****************************************************************************************/
#if MOTHERBOARD == 2
#define KNOWN_BOARD 1 #endif
#ifndef __AVR_ATmega644P__
#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. /****************************************************************************************
#endif * RepRap Motherboard ****---NOOOOOO RS485/EXTRUDER CONTROLLER!!!!!!!!!!!!!!!!!---*******
*
#define X_STEP_PIN 15 ****************************************************************************************/
#define X_DIR_PIN 18 #if MOTHERBOARD == 2
#define X_ENABLE_PIN 19 #define KNOWN_BOARD 1
#define X_MIN_PIN 20
#define X_MAX_PIN 21 #ifndef __AVR_ATmega644P__
#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
#define Y_STEP_PIN 23 #endif
#define Y_DIR_PIN 22
#define Y_ENABLE_PIN 24 #define X_STEP_PIN 15
#define Y_MIN_PIN 25 #define X_DIR_PIN 18
#define Y_MAX_PIN 26 #define X_ENABLE_PIN 19
#define X_MIN_PIN 20
#define Z_STEP_PINN 27 #define X_MAX_PIN 21
#define Z_DIR_PINN 28
#define Z_ENABLE_PIN 29 #define Y_STEP_PIN 23
#define Z_MIN_PIN 30 #define Y_DIR_PIN 22
#define Z_MAX_PIN 31 #define Y_ENABLE_PIN 24
#define Y_MIN_PIN 25
#define E_STEP_PIN 17 #define Y_MAX_PIN 26
#define E_DIR_PIN 16
#define E_ENABLE_PIN -1 #define Z_STEP_PINN 27
#define Z_DIR_PINN 28
#define SDPOWER -1 #define Z_ENABLE_PIN 29
#define SDSS 4 #define Z_MIN_PIN 30
#define LED_PIN 0 #define Z_MAX_PIN 31
#define SD_CARD_WRITE 2 #define E0_STEP_PIN 17
#define SD_CARD_DETECT 3 #define E0_DIR_PIN 16
#define SD_CARD_SELECT 4 #define E0_ENABLE_PIN -1
//our RS485 pins #define SDPOWER -1
#define TX_ENABLE_PIN 12 #define SDSS 4
#define RX_ENABLE_PIN 13 #define LED_PIN 0
//pin for controlling the PSU. #define SD_CARD_WRITE 2
#define PS_ON_PIN 14 #define SD_CARD_DETECT 3
#define SD_CARD_SELECT 4
#define FAN_PIN -1
#define KILL_PIN -1 //our RS485 pins
#define TX_ENABLE_PIN 12
#define HEATER_0_PIN -1 #define RX_ENABLE_PIN 13
#define TEMP_0_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define HEATER_1_PIN -1 //pin for controlling the PSU.
#define HEATER_2_PIN -1 #define PS_ON_PIN 14
#define FAN_PIN -1
#define KILL_PIN -1
#endif
#define HEATER_0_PIN -1
/**************************************************************************************** #define HEATER_1_PIN -1
* Arduino Mega pin assignment #define HEATER_2_PIN -1
* #define TEMP_0_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
****************************************************************************************/ #define TEMP_1_PIN -1
#if MOTHERBOARD == 33 #define TEMP_2_PIN -1
#define MOTHERBOARD 3 #define HEATER_BED_PIN -1
#define RAMPS_V_1_3 #define TEMP_BED_PIN -1
#endif
#if MOTHERBOARD == 3 #endif
#define KNOWN_BOARD 1
/****************************************************************************************
//////////////////FIX THIS////////////// * Arduino Mega pin assignment
#ifndef __AVR_ATmega1280__ *
#ifndef __AVR_ATmega2560__ ****************************************************************************************/
#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. #if MOTHERBOARD == 33
#endif #define MOTHERBOARD 3
#endif #define RAMPS_V_1_3
#endif
// uncomment one of the following lines for RAMPS v1.3 or v1.0, comment both for v1.2 or 1.1 #if MOTHERBOARD == 3
// #define RAMPS_V_1_3 #define KNOWN_BOARD 1
// #define RAMPS_V_1_0
//////////////////FIX THIS//////////////
#ifdef RAMPS_V_1_3 #ifndef __AVR_ATmega1280__
#ifndef __AVR_ATmega2560__
#define X_STEP_PIN 54 #error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
#define X_DIR_PIN 55 #endif
#define X_ENABLE_PIN 38 #endif
#define X_MIN_PIN 3
#define X_MAX_PIN -1 //2 //Max endstops default to disabled "-1", set to commented value to enable. // uncomment one of the following lines for RAMPS v1.3 or v1.0, comment both for v1.2 or 1.1
// #define RAMPS_V_1_3
#define Y_STEP_PIN 60 // #define RAMPS_V_1_0
#define Y_DIR_PIN 61
#define Y_ENABLE_PIN 56 #ifdef RAMPS_V_1_3
#define Y_MIN_PIN 14
#define Y_MAX_PIN -1 //15 #define X_STEP_PIN 54
#define X_DIR_PIN 55
#define Z_STEP_PIN 46 #define X_ENABLE_PIN 38
#define Z_DIR_PIN 48 #define X_MIN_PIN 3
#define Z_ENABLE_PIN 62 #define X_MAX_PIN 2 //2 //Max endstops default to disabled "-1", set to commented value to enable.
#define Z_MIN_PIN 18
#define Z_MAX_PIN -1 //19 #define Y_STEP_PIN 60
#define Y_DIR_PIN 61
#define E_STEP_PIN 26 #define Y_ENABLE_PIN 56
#define E_DIR_PIN 28 #define Y_MIN_PIN 14
#define E_ENABLE_PIN 24 #define Y_MAX_PIN 15 //15
#define SDPOWER -1 #define Z_STEP_PIN 46
#define SDSS 53 #define Z_DIR_PIN 48
#define LED_PIN 13 #define Z_ENABLE_PIN 62
#define FAN_PIN 9 #define Z_MIN_PIN 18
#define PS_ON_PIN 12 #define Z_MAX_PIN 19 //19
#define KILL_PIN -1
#define E0_STEP_PIN 26
#define HEATER_0_PIN 10 #define E0_DIR_PIN 28
#define HEATER_1_PIN 8 #define E0_ENABLE_PIN 24
#define HEATER_2_PIN -1
#define TEMP_0_PIN 13 // ANALOG NUMBERING #define E1_STEP_PIN 36
#define TEMP_1_PIN 14 // ANALOG NUMBERING #define E1_DIR_PIN 34
#define TEMP_2_PIN -1 // ANALOG NUMBERING #define E1_ENABLE_PIN 30
#define SDPOWER -1
#else // RAMPS_V_1_1 or RAMPS_V_1_2 as default #define SDSS 53
#define LED_PIN 13
#define X_STEP_PIN 26 #define FAN_PIN 4
#define X_DIR_PIN 28 #define PS_ON_PIN 12
#define X_ENABLE_PIN 24 #define KILL_PIN -1
#define X_MIN_PIN 3
#define X_MAX_PIN -1 //2 #define HEATER_0_PIN 10 // EXTRUDER 1
#define HEATER_1_PIN 9 // EXTRUDER 2
#define Y_STEP_PIN 38 #define HEATER_2_PIN -1 // EXTRUDER 2
#define Y_DIR_PIN 40 #define TEMP_0_PIN 13 // ANALOG NUMBERING
#define Y_ENABLE_PIN 36 #define TEMP_1_PIN 15 // ANALOG NUMBERING
#define Y_MIN_PIN 16 #define TEMP_2_PIN -1 // ANALOG NUMBERING
#define Y_MAX_PIN -1 //17 #define HEATER_BED_PIN 8 // BED
#define TEMP_BED_PIN 14 // ANALOG NUMBERING
#define Z_STEP_PIN 44
#define Z_DIR_PIN 46
#define Z_ENABLE_PIN 42 #else // RAMPS_V_1_1 or RAMPS_V_1_2 as default
#define Z_MIN_PIN 18
#define Z_MAX_PIN -1 //19 #define X_STEP_PIN 26
#define X_DIR_PIN 28
#define E_STEP_PIN 32 #define X_ENABLE_PIN 24
#define E_DIR_PIN 34 #define X_MIN_PIN 3
#define E_ENABLE_PIN 30 #define X_MAX_PIN -1 //2
#define SDPOWER 48 #define Y_STEP_PIN 38
#define SDSS 53 #define Y_DIR_PIN 40
#define LED_PIN 13 #define Y_ENABLE_PIN 36
#define PS_ON_PIN -1 #define Y_MIN_PIN 16
#define KILL_PIN -1 #define Y_MAX_PIN -1 //17
#define Z_STEP_PIN 44
#define Z_DIR_PIN 46
#ifdef RAMPS_V_1_0 // RAMPS_V_1_0 #define Z_ENABLE_PIN 42
#define HEATER_0_PIN 12 // RAMPS 1.0 #define Z_MIN_PIN 18
#define HEATER_1_PIN -1 // RAMPS 1.0 #define Z_MAX_PIN -1 //19
#define FAN_PIN 11 // RAMPS 1.0
#define E0_STEP_PIN 32
#else // RAMPS_V_1_1 or RAMPS_V_1_2 #define E0_DIR_PIN 34
#define HEATER_0_PIN 10 // RAMPS 1.1 #define E0_ENABLE_PIN 30
#define HEATER_1_PIN 8 // RAMPS 1.1
#define FAN_PIN 9 // RAMPS 1.1 #define SDPOWER 48
#endif #define SDSS 53
#define HEATER_2_PIN -1 #define LED_PIN 13
#define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define PS_ON_PIN -1
#define TEMP_1_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define KILL_PIN -1
#define TEMP_2_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#endif
// SPI for Max6675 Thermocouple #ifdef RAMPS_V_1_0 // RAMPS_V_1_0
#define HEATER_0_PIN 12 // RAMPS 1.0
#ifndef SDSUPPORT #define HEATER_BED_PIN -1 // RAMPS 1.0
// these pins are defined in the SD library if building with SD support #define SCK_PIN 52 #define FAN_PIN 11 // RAMPS 1.0
#define MISO_PIN 50 #else // RAMPS_V_1_1 or RAMPS_V_1_2
#define MOSI_PIN 51 #define HEATER_0_PIN 10 // RAMPS 1.1
#define MAX6675_SS 53 #define HEATER_BED_PIN 8 // RAMPS 1.1
#else #define FAN_PIN 9 // RAMPS 1.1
#define MAX6675_SS 49 #endif
#endif #define HEATER_1_PIN -1
#define HEATER_2_PIN -1
#define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#endif #define TEMP_1_PIN -1
/**************************************************************************************** #define TEMP_2_PIN -1
* Duemilanove w/ ATMega328P pin assignment #define TEMP_BED_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
* #endif
****************************************************************************************/
#if MOTHERBOARD == 4 // SPI for Max6675 Thermocouple
#define KNOWN_BOARD 1
#ifndef SDSUPPORT
#ifndef __AVR_ATmega328P__ // these pins are defined in the SD library if building with SD support #define SCK_PIN 52
#error Oops! Make sure you have 'Arduino Duemilanove w/ ATMega328' selected from the 'Tools -> Boards' menu. #define MISO_PIN 50
#endif #define MOSI_PIN 51
#define MAX6675_SS 53
#define X_STEP_PIN 19 #else
#define X_DIR_PIN 18 #define MAX6675_SS 49
#define X_ENABLE_PIN -1 #endif
#define X_MIN_PIN 17
#define X_MAX_PIN -1
#endif
#define Y_STEP_PIN 10 /****************************************************************************************
#define Y_DIR_PIN 7 * Duemilanove w/ ATMega328P pin assignment
#define Y_ENABLE_PIN -1 *
#define Y_MIN_PIN 8 ****************************************************************************************/
#define Y_MAX_PIN -1 #if MOTHERBOARD == 4
#define KNOWN_BOARD 1
#define Z_STEP_PIN 13
#define Z_DIR_PIN 3 #ifndef __AVR_ATmega328P__
#define Z_ENABLE_PIN 2 #error Oops! Make sure you have 'Arduino Duemilanove w/ ATMega328' selected from the 'Tools -> Boards' menu.
#define Z_MIN_PIN 4 #endif
#define Z_MAX_PIN -1
#define X_STEP_PIN 19
#define E_STEP_PIN 11 #define X_DIR_PIN 18
#define E_DIR_PIN 12 #define X_ENABLE_PIN -1
#define E_ENABLE_PIN -1 #define X_MIN_PIN 17
#define X_MAX_PIN -1
#define SDPOWER -1
#define SDSS -1 #define Y_STEP_PIN 10
#define LED_PIN -1 #define Y_DIR_PIN 7
#define FAN_PIN 5 #define Y_ENABLE_PIN -1
#define PS_ON_PIN -1 #define Y_MIN_PIN 8
#define KILL_PIN -1 #define Y_MAX_PIN -1
#define HEATER_0_PIN 6 #define Z_STEP_PIN 13
#define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define Z_DIR_PIN 3
#define HEATER_1_PIN -1 #define Z_ENABLE_PIN 2
#define HEATER_2_PIN -1 #define Z_MIN_PIN 4
#define Z_MAX_PIN -1
#endif
#define E0_STEP_PIN 11
/**************************************************************************************** #define E0_DIR_PIN 12
* Gen6 pin assignment #define E0_ENABLE_PIN -1
*
****************************************************************************************/ #define SDPOWER -1
#if MOTHERBOARD == 5 #define SDSS -1
#define KNOWN_BOARD 1 #define LED_PIN -1
#define FAN_PIN 5
#ifndef __AVR_ATmega644P__ #define PS_ON_PIN -1
#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #define KILL_PIN -1
#endif
#define HEATER_0_PIN 6
//x axis pins #define HEATER_1_PIN -1
#define X_STEP_PIN 15 #define HEATER_2_PIN -1
#define X_DIR_PIN 18 #define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define X_ENABLE_PIN 19 #define TEMP_1_PIN -1
#define X_MIN_PIN 20 #define TEMP_2_PIN -1
#define X_MAX_PIN -1 #define HEATER_BED_PIN -1
#define TEMP_BED_PIN -1
//y axis pins
#define Y_STEP_PIN 23 #endif
#define Y_DIR_PIN 22
#define Y_ENABLE_PIN 24 /****************************************************************************************
#define Y_MIN_PIN 25 * Gen6 pin assignment
#define Y_MAX_PIN -1 *
****************************************************************************************/
//z axis pins #if MOTHERBOARD == 5
#define Z_STEP_PIN 27 #define KNOWN_BOARD 1
#define Z_DIR_PIN 28
#define Z_ENABLE_PIN 29 #ifndef __AVR_ATmega644P__
#define Z_MIN_PIN 30 #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
#define Z_MAX_PIN -1 #endif
//extruder pins //x axis pins
#define E_STEP_PIN 4 //Edited @ EJE Electronics 20100715 #define X_STEP_PIN 15
#define E_DIR_PIN 2 //Edited @ EJE Electronics 20100715 #define X_DIR_PIN 18
#define E_ENABLE_PIN 3 //Added @ EJE Electronics 20100715 #define X_ENABLE_PIN 19
#define TEMP_0_PIN 5 //changed @ rkoeppl 20110410 #define X_MIN_PIN 20
#define HEATER_0_PIN 14 //changed @ rkoeppl 20110410 #define X_MAX_PIN -1
#define HEATER_1_PIN -1 //changed @ rkoeppl 20110410
#define HEATER_2_PIN -1 //y axis pins
#define Y_STEP_PIN 23
#define SDPOWER -1 #define Y_DIR_PIN 22
#define SDSS 17 #define Y_ENABLE_PIN 24
#define LED_PIN -1 //changed @ rkoeppl 20110410 #define Y_MIN_PIN 25
#define TEMP_1_PIN -1 //changed @ rkoeppl 20110410 #define Y_MAX_PIN -1
#define TEMP_2_PIN -1
#define FAN_PIN -1 //changed @ rkoeppl 20110410 //z axis pins
#define PS_ON_PIN -1 //changed @ rkoeppl 20110410 #define Z_STEP_PIN 27
//our pin for debugging. #define Z_DIR_PIN 28
#define Z_ENABLE_PIN 29
#define DEBUG_PIN 0 #define Z_MIN_PIN 30
#define Z_MAX_PIN -1
//our RS485 pins
#define TX_ENABLE_PIN 12 //extruder pins
#define RX_ENABLE_PIN 13 #define E0_STEP_PIN 4 //Edited @ EJE Electronics 20100715
#define E0_DIR_PIN 2 //Edited @ EJE Electronics 20100715
#define E0_ENABLE_PIN 3 //Added @ EJE Electronics 20100715
#endif #define TEMP_0_PIN 5 //changed @ rkoeppl 20110410
#define TEMP_1_PIN -1 //changed @ rkoeppl 20110410
/**************************************************************************************** #define TEMP_2_PIN -1 //changed @ rkoeppl 20110410
* Sanguinololu pin assignment #define HEATER_0_PIN 14 //changed @ rkoeppl 20110410
* #define HEATER_1_PIN -1
****************************************************************************************/ #define HEATER_2_PIN -1
#if MOTHERBOARD == 62 #define HEATER_BED_PIN -1 //changed @ rkoeppl 20110410
#define MOTHERBOARD 6 #define TEMP_BED_PIN -1 //changed @ rkoeppl 20110410
#define SANGUINOLOLU_V_1_2
#endif #define SDPOWER -1
#if MOTHERBOARD == 6 #define SDSS 17
#define KNOWN_BOARD 1 #define LED_PIN -1 //changed @ rkoeppl 20110410
#ifndef __AVR_ATmega644P__ #define FAN_PIN -1 //changed @ rkoeppl 20110410
#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #define PS_ON_PIN -1 //changed @ rkoeppl 20110410
#endif //our pin for debugging.
#define X_STEP_PIN 15 #define DEBUG_PIN 0
#define X_DIR_PIN 21
#define X_MIN_PIN 18 //our RS485 pins
#define X_MAX_PIN -2 #define TX_ENABLE_PIN 12
#define RX_ENABLE_PIN 13
#define Y_STEP_PIN 22
#define Y_DIR_PIN 23
#define Y_MIN_PIN 19 #endif
#define Y_MAX_PIN -1
/****************************************************************************************
#define Z_STEP_PIN 3 * Sanguinololu pin assignment
#define Z_DIR_PIN 2 *
#define Z_MIN_PIN 20 ****************************************************************************************/
#define Z_MAX_PIN -1 #if MOTHERBOARD == 62
#define MOTHERBOARD 6
#define E_STEP_PIN 1 #define SANGUINOLOLU_V_1_2
#define E_DIR_PIN 0 #endif
#if MOTHERBOARD == 6
#define LED_PIN -1 #define KNOWN_BOARD 1
#ifndef __AVR_ATmega644P__
#define FAN_PIN -1 #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
#endif
#define PS_ON_PIN -1
#define KILL_PIN -1 #define X_STEP_PIN 15
#define X_DIR_PIN 21
#define HEATER_0_PIN 13 // (extruder) #define X_MIN_PIN 18
#define X_MAX_PIN -2
#ifdef SANGUINOLOLU_V_1_2
#define Y_STEP_PIN 22
#define HEATER_1_PIN 12 // (bed) #define Y_DIR_PIN 23
#define X_ENABLE_PIN 14 #define Y_MIN_PIN 19
#define Y_ENABLE_PIN 14 #define Y_MAX_PIN -1
#define Z_ENABLE_PIN 26
#define E_ENABLE_PIN 14 #define Z_STEP_PIN 3
#define Z_DIR_PIN 2
#else #define Z_MIN_PIN 20
#define Z_MAX_PIN -1
#define HEATER_1_PIN 14 // (bed)
#define X_ENABLE_PIN -1 #define E0_STEP_PIN 1
#define Y_ENABLE_PIN -1 #define E0_DIR_PIN 0
#define Z_ENABLE_PIN -1
#define E_ENABLE_PIN -1 #define LED_PIN -1
#endif #define FAN_PIN -1
#define TEMP_0_PIN 7 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) #define PS_ON_PIN -1
#define TEMP_1_PIN 6 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) #define KILL_PIN -1
#define TEMP_2_PIN -1
#define SDPOWER -1 #define HEATER_0_PIN 13 // (extruder)
#define SDSS 31 #define HEATER_1_PIN -1
#define HEATER_2_PIN -1 #define HEATER_2_PIN -1
#endif #ifdef SANGUINOLOLU_V_1_2
#define HEATER_BED_PIN 12 // (bed)
#if MOTHERBOARD == 7 #define X_ENABLE_PIN 14
#define KNOWN_BOARD #define Y_ENABLE_PIN 14
/***************************************************************** #define Z_ENABLE_PIN 26
* Ultimaker pin assignment #define E0_ENABLE_PIN 14
******************************************************************/
#else
#ifndef __AVR_ATmega1280__
#ifndef __AVR_ATmega2560__ #define HEATER_BED_PIN 14 // (bed)
#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. #define X_ENABLE_PIN -1
#endif #define Y_ENABLE_PIN -1
#endif #define Z_ENABLE_PIN -1
#define E0_ENABLE_PIN -1
#define X_STEP_PIN 25
#define X_DIR_PIN 23 #endif
#define X_MIN_PIN 22
#define X_MAX_PIN 24 #define TEMP_0_PIN 7 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder)
#define X_ENABLE_PIN 27 #define TEMP_1_PIN -1
#define TEMP_2_PIN -1
#define Y_STEP_PIN 31 #define TEMP_BED_PIN 6 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
#define Y_DIR_PIN 33 #define SDPOWER -1
#define Y_MIN_PIN 26 #define SDSS 31
#define Y_MAX_PIN 28
#define Y_ENABLE_PIN 29 #endif
#define Z_STEP_PIN 37
#define Z_DIR_PIN 39 #if MOTHERBOARD == 7
#define Z_MIN_PIN 30 #define KNOWN_BOARD
#define Z_MAX_PIN 32 /*****************************************************************
#define Z_ENABLE_PIN 35 * Ultimaker pin assignment
******************************************************************/
#define HEATER_1_PIN 4
#define TEMP_1_PIN 11 #ifndef __AVR_ATmega1280__
#ifndef __AVR_ATmega2560__
#define EXTRUDER_0_STEP_PIN 43 #error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
#define EXTRUDER_0_DIR_PIN 45 #endif
#define EXTRUDER_0_ENABLE_PIN 41 #endif
#define HEATER_0_PIN 2
#define TEMP_0_PIN 8 #define X_STEP_PIN 25
#define X_DIR_PIN 23
#define EXTRUDER_1_STEP_PIN 49 #define X_MIN_PIN 22
#define EXTRUDER_1_DIR_PIN 47 #define X_MAX_PIN 24
#define EXTRUDER_1_ENABLE_PIN 51 #define X_ENABLE_PIN 27
#define EXTRUDER_1_HEATER_PIN 3
#define EXTRUDER_1_TEMPERATURE_PIN 10 #define Y_STEP_PIN 31
#define HEATER_2_PIN 51 #define Y_DIR_PIN 33
#define TEMP_2_PIN 3 #define Y_MIN_PIN 26
#define Y_MAX_PIN 28
#define Y_ENABLE_PIN 29
#define E_STEP_PIN EXTRUDER_0_STEP_PIN #define Z_STEP_PIN 37
#define E_DIR_PIN EXTRUDER_0_DIR_PIN #define Z_DIR_PIN 39
#define E_ENABLE_PIN EXTRUDER_0_ENABLE_PIN #define Z_MIN_PIN 30
#define Z_MAX_PIN 32
#define SDPOWER -1 #define Z_ENABLE_PIN 35
#define SDSS 53
#define LED_PIN 13 #define HEATER_BED_PIN 4
#define FAN_PIN 7 #define TEMP_BED_PIN 11
#define PS_ON_PIN 12
#define KILL_PIN -1 #define HEATER_0_PIN 2
#define TEMP_0_PIN 8
#ifdef ULTRA_LCD
#define EXTRUDER_1_HEATER_PIN 3
#ifdef NEWPANEL #define EXTRUDER_1_TEMPERATURE_PIN 10
//arduino pin witch triggers an piezzo beeper #define HEATER_1_PIN 51
#define BEEPER 18 #define TEMP_1_PIN 3
#define LCD_PINS_RS 20 #define HEATER_2_PIN -1
#define LCD_PINS_ENABLE 17 #define TEMP_2_PIN -1
#define LCD_PINS_D4 16
#define LCD_PINS_D5 21 #define E0_STEP_PIN 43
#define LCD_PINS_D6 5 #define E0_DIR_PIN 45
#define LCD_PINS_D7 6 #define E0_ENABLE_PIN 41
//buttons are directly attached #define E1_STEP_PIN 49
#define BTN_EN1 40 #define E1_DIR_PIN 47
#define BTN_EN2 42 #define E1_ENABLE_PIN 51
#define BTN_ENC 19 //the click
#define SDPOWER -1
#define BLEN_C 2 #define SDSS 53
#define BLEN_B 1 #define LED_PIN 13
#define BLEN_A 0 #define FAN_PIN 7
#define PS_ON_PIN 12
#define SDCARDDETECT 38 #define KILL_PIN -1
//encoder rotation values #ifdef ULTRA_LCD
#define encrot0 0
#define encrot1 2 #ifdef NEWPANEL
#define encrot2 3 //arduino pin witch triggers an piezzo beeper
#define encrot3 1 #define BEEPER 18
#else //old style panel with shift register
//arduino pin witch triggers an piezzo beeper #define LCD_PINS_RS 20
#define BEEPER 18 #define LCD_PINS_ENABLE 17
#define LCD_PINS_D4 16
//buttons are attached to a shift register #define LCD_PINS_D5 21
#define SHIFT_CLK 38 #define LCD_PINS_D6 5
#define SHIFT_LD 42 #define LCD_PINS_D7 6
#define SHIFT_OUT 40
#define SHIFT_EN 17 //buttons are directly attached
#define BTN_EN1 40
#define LCD_PINS_RS 16 #define BTN_EN2 42
#define LCD_PINS_ENABLE 5 #define BTN_ENC 19 //the click
#define LCD_PINS_D4 6
#define LCD_PINS_D5 21 #define BLEN_C 2
#define LCD_PINS_D6 20 #define BLEN_B 1
#define LCD_PINS_D7 19 #define BLEN_A 0
//encoder rotation values #define SDCARDDETECT 38
#define encrot0 0
#define encrot1 2 //encoder rotation values
#define encrot2 3 #define encrot0 0
#define encrot3 1 #define encrot1 2
#define encrot2 3
#define encrot3 1
//bits in the shift register that carry the buttons for: #else //old style panel with shift register
// left up center down right red //arduino pin witch triggers an piezzo beeper
#define BL_LE 7 #define BEEPER 18
#define BL_UP 6
#define BL_MI 5 //buttons are attached to a shift register
#define BL_DW 4 #define SHIFT_CLK 38
#define BL_RI 3 #define SHIFT_LD 42
#define BL_ST 2 #define SHIFT_OUT 40
#define SHIFT_EN 17
#define BLEN_B 1
#define BLEN_A 0 #define LCD_PINS_RS 16
#endif #define LCD_PINS_ENABLE 5
#endif //ULTRA_LCD #define LCD_PINS_D4 6
#define LCD_PINS_D5 21
#endif #define LCD_PINS_D6 20
#define LCD_PINS_D7 19
/****************************************************************************************
* Teensylu 0.7 pin assingments (ATMEGA90USB) //encoder rotation values
* Requires the Teensyduino software with Teensy2.0++ selected in arduino IDE! #define encrot0 0
****************************************************************************************/ #define encrot1 2
#if MOTHERBOARD == 8 #define encrot2 3
#define MOTHERBOARD 8 #define encrot3 1
#define KNOWN_BOARD 1
//bits in the shift register that carry the buttons for:
#define X_STEP_PIN 0 // left up center down right red
#define X_DIR_PIN 1 #define BL_LE 7
#define X_ENABLE_PIN 39 #define BL_UP 6
#define X_MIN_PIN 13 #define BL_MI 5
#define X_MAX_PIN -1 #define BL_DW 4
#define BL_RI 3
#define Y_STEP_PIN 2 #define BL_ST 2
#define Y_DIR_PIN 3
#define Y_ENABLE_PIN 38 #define BLEN_B 1
#define Y_MIN_PIN 14 #define BLEN_A 0
#define Y_MAX_PIN -1 #endif
#endif //ULTRA_LCD
#define Z_STEP_PIN 4
#define Z_DIR_PIN 5 #endif
#define Z_ENABLE_PIN 23
#define Z_MIN_PIN 15 /****************************************************************************************
#define Z_MAX_PIN -1 * Teensylu 0.7 pin assingments (ATMEGA90USB)
* Requires the Teensyduino software with Teensy2.0++ selected in arduino IDE!
#define E_STEP_PIN 6 ****************************************************************************************/
#define E_DIR_PIN 7 #if MOTHERBOARD == 8
#define E_ENABLE_PIN 19 #define MOTHERBOARD 8
#define KNOWN_BOARD 1
#define HEATER_0_PIN 21 // Extruder #define X_STEP_PIN 0
#define HEATER_1_PIN 20 // Bed #define X_DIR_PIN 1
#define HEATER_2_PIN -1 #define X_ENABLE_PIN 39
#define FAN_PIN 22 // Fan #define X_MIN_PIN 13
#define X_MAX_PIN -1
#define TEMP_0_PIN 7 // Extruder
#define TEMP_1_PIN 6 // Bed #define Y_STEP_PIN 2
#define TEMP_2_PIN -1 #define Y_DIR_PIN 3
#define Y_ENABLE_PIN 38
#define SDPOWER -1 #define Y_MIN_PIN 14
#define SDSS 8 #define Y_MAX_PIN -1
#define LED_PIN -1
#define PS_ON_PIN -1 #define Z_STEP_PIN 4
#define KILL_PIN -1 #define Z_DIR_PIN 5
#define ALARM_PIN -1 #define Z_ENABLE_PIN 23
#define Z_MIN_PIN 15
#ifndef SDSUPPORT #define Z_MAX_PIN -1
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 9 #define E0_STEP_PIN 6
#define MISO_PIN 11 #define E0_DIR_PIN 7
#define MOSI_PIN 10 #define E0_ENABLE_PIN 19
#endif
#endif
#ifndef KNOWN_BOARD #define HEATER_0_PIN 21 // Extruder
#error Unknown MOTHERBOARD value in configuration.h #define HEATER_1_PIN -1
#endif #define HEATER_2_PIN -1
#define HEATER_BED_PIN 20 // Bed
//List of pins which to ignore when asked to change by gcode, 0 and 1 are RX and TX, do not mess with those! #define FAN_PIN 22 // Fan
#define SENSITIVE_PINS {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, E_STEP_PIN, E_DIR_PIN, E_ENABLE_PIN, LED_PIN, PS_ON_PIN, HEATER_0_PIN, HEATER_1_PIN, HEATER_2_PIN, FAN_PIN, TEMP_0_PIN, TEMP_1_PIN, TEMP_2_PIN}
#define TEMP_0_PIN 7 // Extruder
#define TEMP_1_PIN -1
#define TEMP_2_PIN -1
#define TEMP_BED_PIN 6 // Bed
#define SDPOWER -1
#define SDSS 8
#define LED_PIN -1
#define PS_ON_PIN -1
#define KILL_PIN -1
#define ALARM_PIN -1
#ifndef SDSUPPORT
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 9
#define MISO_PIN 11
#define MOSI_PIN 10
#endif
#endif
#ifndef KNOWN_BOARD
#error Unknown MOTHERBOARD value in configuration.h
#endif
//List of pins which to ignore when asked to change by gcode, 0 and 1 are RX and TX, do not mess with those!
#define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN
#if EXTRUDERS == 3
#define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN
#define _E2_PINS E2_STEP_PIN, E2_DIR_PIN, E2_ENABLE_PIN
#elif EXTRUDERS == 2
#define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN
#define _E2_PINS -1
#elif EXTRUDERS == 1
#define _E1_PINS -1
#define _E2_PINS -1
#else
#error Unsupported number of extruders
#endif
#define SENSITIVE_PINS {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, LED_PIN, PS_ON_PIN, \
HEATER_0_PIN, HEATER_1_PIN, HEATER_2_PIN, \
HEATER_BED_PIN, FAN_PIN, \
_E0_PINS, _E1_PINS, _E2_PINS, \
TEMP_0_PIN, TEMP_1_PIN, TEMP_2_PIN, TEMP_BED_PIN }
#endif #endif

View file

@ -56,9 +56,9 @@
//#include <math.h> //#include <math.h>
//#include <stdlib.h> //#include <stdlib.h>
#include "Marlin.h"
#include "Configuration.h" #include "Configuration.h"
#include "pins.h" #include "pins.h"
#include "Marlin.h"
#include "fastio.h" #include "fastio.h"
#include "planner.h" #include "planner.h"
#include "stepper.h" #include "stepper.h"
@ -81,8 +81,6 @@ float max_z_jerk;
float mintravelfeedrate; float mintravelfeedrate;
unsigned long axis_steps_per_sqr_second[NUM_AXIS]; unsigned long axis_steps_per_sqr_second[NUM_AXIS];
uint8_t active_extruder = 0;
// The current position of the tool in absolute steps // The current position of the tool in absolute steps
long position[4]; //rescaled from extern when axis_steps_per_unit are changed by gcode long position[4]; //rescaled from extern when axis_steps_per_unit are changed by gcode
static float previous_speed[4]; // Speed of previous path line segment static float previous_speed[4]; // Speed of previous path line segment
@ -95,7 +93,6 @@ static float previous_nominal_speed; // Nominal speed of previous path line segm
bool autotemp_enabled=false; bool autotemp_enabled=false;
#endif #endif
//=========================================================================== //===========================================================================
//=================semi-private variables, used in inline functions ===== //=================semi-private variables, used in inline functions =====
//=========================================================================== //===========================================================================
@ -196,8 +193,8 @@ void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exi
} }
#ifdef ADVANCE #ifdef ADVANCE
long initial_advance = block->advance*entry_factor*entry_factor; volatile long initial_advance = block->advance*entry_factor*entry_factor;
long final_advance = block->advance*exit_factor*exit_factor; volatile long final_advance = block->advance*exit_factor*exit_factor;
#endif // ADVANCE #endif // ADVANCE
// block->accelerate_until = accelerate_steps; // block->accelerate_until = accelerate_steps;
@ -439,7 +436,7 @@ void check_axes_activity() {
if((DISABLE_X) && (x_active == 0)) disable_x(); if((DISABLE_X) && (x_active == 0)) disable_x();
if((DISABLE_Y) && (y_active == 0)) disable_y(); if((DISABLE_Y) && (y_active == 0)) disable_y();
if((DISABLE_Z) && (z_active == 0)) disable_z(); if((DISABLE_Z) && (z_active == 0)) disable_z();
if((DISABLE_E) && (e_active == 0)) disable_e(); if((DISABLE_E) && (e_active == 0)) { disable_e0();disable_e1();disable_e2(); }
} }
@ -514,15 +511,10 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
if(block->steps_x != 0) enable_x(); if(block->steps_x != 0) enable_x();
if(block->steps_y != 0) enable_y(); if(block->steps_y != 0) enable_y();
if(block->steps_z != 0) enable_z(); if(block->steps_z != 0) enable_z();
if(extruder == 0) {
if(block->steps_e != 0) enable_e(); // Enable all
} if(block->steps_e != 0) { enable_e0();enable_e1();enable_e2(); }
#if (EXTRUDERS > 1)
if(extruder == 1) {
if(block->steps_e != 0) enable_e1();
}
#endif
float delta_mm[4]; float delta_mm[4];
delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS]; delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]; delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
@ -809,4 +801,4 @@ void allow_cold_extrudes(bool allow)
#ifdef PREVENT_DANGEROUS_EXTRUDE #ifdef PREVENT_DANGEROUS_EXTRUDE
allow_cold_extrude=allow; allow_cold_extrude=allow;
#endif #endif
} }

View file

@ -91,8 +91,6 @@ extern float max_z_jerk;
extern float mintravelfeedrate; extern float mintravelfeedrate;
extern unsigned long axis_steps_per_sqr_second[NUM_AXIS]; extern unsigned long axis_steps_per_sqr_second[NUM_AXIS];
extern uint8_t active_extruder;
#ifdef AUTOTEMP #ifdef AUTOTEMP
extern bool autotemp_enabled; extern bool autotemp_enabled;
extern float autotemp_max; extern float autotemp_max;

View file

@ -24,9 +24,9 @@
#include "stepper.h" #include "stepper.h"
#include "Configuration.h" #include "Configuration.h"
#include "pins.h"
#include "Marlin.h" #include "Marlin.h"
#include "planner.h" #include "planner.h"
#include "pins.h"
#include "fastio.h" #include "fastio.h"
#include "temperature.h" #include "temperature.h"
#include "ultralcd.h" #include "ultralcd.h"
@ -41,7 +41,6 @@
block_t *current_block; // A pointer to the block currently being traced block_t *current_block; // A pointer to the block currently being traced
//=========================================================================== //===========================================================================
//=============================private variables ============================ //=============================private variables ============================
//=========================================================================== //===========================================================================
@ -58,7 +57,7 @@ volatile static unsigned long step_events_completed; // The number of step event
static long advance_rate, advance, final_advance = 0; static long advance_rate, advance, final_advance = 0;
static long old_advance = 0; static long old_advance = 0;
#endif #endif
static long e_steps; static long e_steps[3];
static unsigned char busy = false; // TRUE when SIG_OUTPUT_COMPARE1A is being serviced. Used to avoid retriggering that handler. static unsigned char busy = false; // TRUE when SIG_OUTPUT_COMPARE1A is being serviced. Used to avoid retriggering that handler.
static long acceleration_time, deceleration_time; static long acceleration_time, deceleration_time;
//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate; //static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
@ -267,7 +266,7 @@ FORCE_INLINE void trapezoid_generator_reset() {
advance = current_block->initial_advance; advance = current_block->initial_advance;
final_advance = current_block->final_advance; final_advance = current_block->final_advance;
// Do E steps + advance steps // Do E steps + advance steps
e_steps += ((advance >>8) - old_advance); e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
old_advance = advance >>8; old_advance = advance >>8;
#endif #endif
deceleration_time = 0; deceleration_time = 0;
@ -304,8 +303,8 @@ ISR(TIMER1_COMPA_vect)
counter_z = counter_x; counter_z = counter_x;
counter_e = counter_x; counter_e = counter_x;
step_events_completed = 0; step_events_completed = 0;
// #ifdef ADVANCE // #ifdef ADVANCE
e_steps = 0; // e_steps[current_block->active_extruder] = 0;
// #endif // #endif
} }
else { else {
@ -419,11 +418,11 @@ ISR(TIMER1_COMPA_vect)
#ifndef ADVANCE #ifndef ADVANCE
if ((out_bits & (1<<E_AXIS)) != 0) { // -direction if ((out_bits & (1<<E_AXIS)) != 0) { // -direction
WRITE(E_DIR_PIN,INVERT_E_DIR); REV_E_DIR();
count_direction[E_AXIS]=-1; count_direction[E_AXIS]=-1;
} }
else { // +direction else { // +direction
WRITE(E_DIR_PIN,!INVERT_E_DIR); NORM_E_DIR();
count_direction[E_AXIS]=-1; count_direction[E_AXIS]=-1;
} }
#endif //!ADVANCE #endif //!ADVANCE
@ -438,10 +437,10 @@ ISR(TIMER1_COMPA_vect)
if (counter_e > 0) { if (counter_e > 0) {
counter_e -= current_block->step_event_count; counter_e -= current_block->step_event_count;
if ((out_bits & (1<<E_AXIS)) != 0) { // - direction if ((out_bits & (1<<E_AXIS)) != 0) { // - direction
e_steps--; e_steps[current_block->active_extruder]--;
} }
else { else {
e_steps++; e_steps[current_block->active_extruder]++;
} }
} }
#endif //ADVANCE #endif //ADVANCE
@ -473,9 +472,9 @@ ISR(TIMER1_COMPA_vect)
#ifndef ADVANCE #ifndef ADVANCE
counter_e += current_block->steps_e; counter_e += current_block->steps_e;
if (counter_e > 0) { if (counter_e > 0) {
WRITE(E_STEP_PIN, HIGH); WRITE_E_STEP(HIGH);
counter_e -= current_block->step_event_count; counter_e -= current_block->step_event_count;
WRITE(E_STEP_PIN, LOW); WRITE_E_STEP(LOW);
count_position[E_AXIS]+=count_direction[E_AXIS]; count_position[E_AXIS]+=count_direction[E_AXIS];
} }
#endif //!ADVANCE #endif //!ADVANCE
@ -504,7 +503,7 @@ ISR(TIMER1_COMPA_vect)
} }
//if(advance > current_block->advance) advance = current_block->advance; //if(advance > current_block->advance) advance = current_block->advance;
// Do E steps + advance steps // Do E steps + advance steps
e_steps += ((advance >>8) - old_advance); e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
old_advance = advance >>8; old_advance = advance >>8;
#endif #endif
@ -533,7 +532,7 @@ ISR(TIMER1_COMPA_vect)
} }
if(advance < final_advance) advance = final_advance; if(advance < final_advance) advance = final_advance;
// Do E steps + advance steps // Do E steps + advance steps
e_steps += ((advance >>8) - old_advance); e_steps[current_block->active_extruder] += ((advance >>8) - old_advance);
old_advance = advance >>8; old_advance = advance >>8;
#endif //ADVANCE #endif //ADVANCE
} }
@ -558,27 +557,57 @@ ISR(TIMER1_COMPA_vect)
old_OCR0A += 52; // ~10kHz interrupt (250000 / 26 = 9615kHz) old_OCR0A += 52; // ~10kHz interrupt (250000 / 26 = 9615kHz)
OCR0A = old_OCR0A; OCR0A = old_OCR0A;
// Set E direction (Depends on E direction + advance) // Set E direction (Depends on E direction + advance)
for(unsigned char i=0; i<4;) { for(unsigned char i=0; i<4;i++) {
WRITE(E_STEP_PIN, LOW); if (e_steps[0] != 0) {
if (e_steps == 0) break; WRITE(E0_STEP_PIN, LOW);
i++; if (e_steps[0] < 0) {
if (e_steps < 0) { WRITE(E0_DIR_PIN, INVERT_E0_DIR);
WRITE(E_DIR_PIN,INVERT_E_DIR); e_steps[0]++;
e_steps++; WRITE(E0_STEP_PIN, HIGH);
WRITE(E_STEP_PIN, HIGH); }
} else if (e_steps[0] > 0) {
else if (e_steps > 0) { WRITE(E0_DIR_PIN, !INVERT_E0_DIR);
WRITE(E_DIR_PIN,!INVERT_E_DIR); e_steps[0]--;
e_steps--; WRITE(E0_STEP_PIN, HIGH);
WRITE(E_STEP_PIN, HIGH); }
} }
#if EXTRUDERS > 1
if (e_steps[1] != 0) {
WRITE(E1_STEP_PIN, LOW);
if (e_steps[1] < 0) {
WRITE(E1_DIR_PIN, INVERT_E1_DIR);
e_steps[1]++;
WRITE(E1_STEP_PIN, HIGH);
}
else if (e_steps[1] > 0) {
WRITE(E1_DIR_PIN, !INVERT_E1_DIR);
e_steps[1]--;
WRITE(E1_STEP_PIN, HIGH);
}
}
#endif
#if EXTRUDERS > 2
if (e_steps[2] != 0) {
WRITE(E2_STEP_PIN, LOW);
if (e_steps[2] < 0) {
WRITE(E2_DIR_PIN, INVERT_E2_DIR);
e_steps[2]++;
WRITE(E2_STEP_PIN, HIGH);
}
else if (e_steps[2] > 0) {
WRITE(E2_DIR_PIN, !INVERT_E2_DIR);
e_steps[2]--;
WRITE(E2_STEP_PIN, HIGH);
}
}
#endif
} }
} }
#endif // ADVANCE #endif // ADVANCE
void st_init() void st_init()
{ {
//Initialize Dir Pins //Initialize Dir Pins
#if X_DIR_PIN > -1 #if X_DIR_PIN > -1
SET_OUTPUT(X_DIR_PIN); SET_OUTPUT(X_DIR_PIN);
#endif #endif
@ -588,8 +617,14 @@ void st_init()
#if Z_DIR_PIN > -1 #if Z_DIR_PIN > -1
SET_OUTPUT(Z_DIR_PIN); SET_OUTPUT(Z_DIR_PIN);
#endif #endif
#if E_DIR_PIN > -1 #if E0_DIR_PIN > -1
SET_OUTPUT(E_DIR_PIN); SET_OUTPUT(E0_DIR_PIN);
#endif
#if defined(E1_DIR_PIN) && (E1_DIR_PIN > -1)
SET_OUTPUT(E1_DIR_PIN);
#endif
#if defined(E2_DIR_PIN) && (E2_DIR_PIN > -1)
SET_OUTPUT(E2_DIR_PIN);
#endif #endif
//Initialize Enable Pins - steppers default to disabled. //Initialize Enable Pins - steppers default to disabled.
@ -606,9 +641,17 @@ void st_init()
SET_OUTPUT(Z_ENABLE_PIN); SET_OUTPUT(Z_ENABLE_PIN);
if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH); if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
#endif #endif
#if (E_ENABLE_PIN > -1) #if (E0_ENABLE_PIN > -1)
SET_OUTPUT(E_ENABLE_PIN); SET_OUTPUT(E0_ENABLE_PIN);
if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH); if(!E_ENABLE_ON) WRITE(E0_ENABLE_PIN,HIGH);
#endif
#if defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
SET_OUTPUT(E1_ENABLE_PIN);
if(!E_ENABLE_ON) WRITE(E1_ENABLE_PIN,HIGH);
#endif
#if defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
SET_OUTPUT(E2_ENABLE_PIN);
if(!E_ENABLE_ON) WRITE(E2_ENABLE_PIN,HIGH);
#endif #endif
//endstops and pullups //endstops and pullups
@ -669,8 +712,14 @@ void st_init()
#if (Z_STEP_PIN > -1) #if (Z_STEP_PIN > -1)
SET_OUTPUT(Z_STEP_PIN); SET_OUTPUT(Z_STEP_PIN);
#endif #endif
#if (E_STEP_PIN > -1) #if (E0_STEP_PIN > -1)
SET_OUTPUT(E_STEP_PIN); SET_OUTPUT(E0_STEP_PIN);
#endif
#if defined(E1_STEP_PIN) && (E1_STEP_PIN > -1)
SET_OUTPUT(E1_STEP_PIN);
#endif
#if defined(E2_STEP_PIN) && (E2_STEP_PIN > -1)
SET_OUTPUT(E2_STEP_PIN);
#endif #endif
// waveform generation = 0100 = CTC // waveform generation = 0100 = CTC
@ -693,7 +742,9 @@ void st_init()
TCCR0A &= ~(1<<WGM01); TCCR0A &= ~(1<<WGM01);
TCCR0A &= ~(1<<WGM00); TCCR0A &= ~(1<<WGM00);
#endif #endif
e_steps = 0; e_steps[0] = 0;
e_steps[1] = 0;
e_steps[2] = 0;
TIMSK0 |= (1<<OCIE0A); TIMSK0 |= (1<<OCIE0A);
#endif //ADVANCE #endif //ADVANCE
@ -750,7 +801,9 @@ void finishAndDisableSteppers()
disable_x(); disable_x();
disable_y(); disable_y();
disable_z(); disable_z();
disable_e(); disable_e0();
disable_e1();
disable_e2();
} }
void quickStop() void quickStop()

View file

@ -23,6 +23,21 @@
#include "planner.h" #include "planner.h"
#if EXTRUDERS > 2
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 2) { WRITE(E2_STEP_PIN, v); } else { if(current_block->active_extruder == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}}
#define NORM_E_DIR() { if(current_block->active_extruder == 2) { WRITE(!E2_DIR_PIN, INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(!E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}}
#define REV_E_DIR() { if(current_block->active_extruder == 2) { WRITE(E2_DIR_PIN, INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}}
#elif EXTRUDERS > 1
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}
#define NORM_E_DIR() { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}
#define REV_E_DIR() { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}
#else
#define WRITE_E_STEP(v) WRITE(E0_STEP_PIN, v)
#define NORM_E_DIR() WRITE(E0_DIR_PIN, !INVERT_E0_DIR)
#define REV_E_DIR() WRITE(E0_DIR_PIN, INVERT_E0_DIR)
#endif
// Initialize and start the stepper motor subsystem // Initialize and start the stepper motor subsystem
void st_init(); void st_init();

View file

@ -26,7 +26,6 @@
It has preliminary support for Matthew Roberts advance algorithm It has preliminary support for Matthew Roberts advance algorithm
http://reprap.org/pipermail/reprap-dev/2011-May/003323.html http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
This firmware is optimized for gen6 electronics.
*/ */
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
@ -41,17 +40,14 @@
//=========================================================================== //===========================================================================
//=============================public variables============================ //=============================public variables============================
//=========================================================================== //===========================================================================
int target_raw[3] = {0, 0, 0}; int target_raw[EXTRUDERS] = { 0 };
int current_raw[3] = {0, 0, 0}; int target_raw_bed = 0;
int heatingtarget_raw[3]= {0, 0, 0}; int current_raw[EXTRUDERS] = { 0 };
int current_raw_bed = 0;
#ifdef PIDTEMP #ifdef PIDTEMP
// used external
// probably used external float pid_setpoint[EXTRUDERS] = { 0.0 };
float HeaterPower;
float pid_setpoint = 0.0;
float Kp=DEFAULT_Kp; float Kp=DEFAULT_Kp;
float Ki=DEFAULT_Ki; float Ki=DEFAULT_Ki;
@ -72,45 +68,83 @@ static unsigned long previous_millis_bed_heater;
#ifdef PIDTEMP #ifdef PIDTEMP
//static cannot be external: //static cannot be external:
static float temp_iState = 0; static float temp_iState[EXTRUDERS] = { 0 };
static float temp_dState = 0; static float temp_dState[EXTRUDERS] = { 0 };
static float pTerm; static float pTerm[EXTRUDERS];
static float iTerm; static float iTerm[EXTRUDERS];
static float dTerm; static float dTerm[EXTRUDERS];
//int output; //int output;
static float pid_error; static float pid_error[EXTRUDERS];
static float temp_iState_min; static float temp_iState_min[EXTRUDERS];
static float temp_iState_max; static float temp_iState_max[EXTRUDERS];
// static float pid_input; // static float pid_input[EXTRUDERS];
// static float pid_output; // static float pid_output[EXTRUDERS];
static bool pid_reset; static bool pid_reset[EXTRUDERS];
#endif //PIDTEMP #endif //PIDTEMP
static unsigned char soft_pwm[EXTRUDERS];
#ifdef WATCHPERIOD #ifdef WATCHPERIOD
static int watch_raw[EXTRUDERS] = { -1000 }; // the first value used for all
static int watch_oldtemp[3] = {0,0,0}; static int watch_oldtemp[3] = {0,0,0};
static unsigned long watchmillis = 0; static unsigned long watchmillis = 0;
#endif //WATCHPERIOD #endif //WATCHPERIOD
// Init min and max temp with extreme values to prevent false errors during startup // Init min and max temp with extreme values to prevent false errors during startup
static int minttemp_0 = 0; static int minttemp[EXTRUDERS] = { 0 };
static int maxttemp_0 = 16383; static int maxttemp[EXTRUDERS] = { 16383 }; // the first value used for all
//static int minttemp_1 = 0;
//static int maxttemp_1 = 16383;
static int bed_minttemp = 0; static int bed_minttemp = 0;
static int bed_maxttemp = 16383; static int bed_maxttemp = 16383;
static int heater_pin_map[EXTRUDERS] = { HEATER_0_PIN
#if EXTRUDERS > 1
, HEATER_1_PIN
#endif
#if EXTRUDERS > 2
, HEATER_2_PIN
#endif
#if EXTRUDERS > 3
#error Unsupported number of extruders
#endif
};
static void *heater_ttbl_map[EXTRUDERS] = { (void *)heater_0_temptable
#if EXTRUDERS > 1
, (void *)heater_1_temptable
#endif
#if EXTRUDERS > 2
, (void *)heater_2_temptable
#endif
#if EXTRUDERS > 3
#error Unsupported number of extruders
#endif
};
static int heater_ttbllen_map[EXTRUDERS] = { heater_0_temptable_len
#if EXTRUDERS > 1
, heater_1_temptable_len
#endif
#if EXTRUDERS > 2
, heater_2_temptable_len
#endif
#if EXTRUDERS > 3
#error Unsupported number of extruders
#endif
};
//=========================================================================== //===========================================================================
//=============================functions ============================ //============================= functions ============================
//=========================================================================== //===========================================================================
void updatePID() void updatePID()
{ {
#ifdef PIDTEMP #ifdef PIDTEMP
temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki; for(int e = 0; e < EXTRUDERS; e++) {
temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / Ki;
}
#endif #endif
} }
int getHeaterPower(int heater) {
return soft_pwm[heater];
}
void manage_heater() void manage_heater()
{ {
#ifdef USE_WATCHDOG #ifdef USE_WATCHDOG
@ -119,73 +153,67 @@ void manage_heater()
float pid_input; float pid_input;
float pid_output; float pid_output;
if(temp_meas_ready != true) //better readability if(temp_meas_ready != true) //better readability
return; return;
CRITICAL_SECTION_START; CRITICAL_SECTION_START;
temp_meas_ready = false; temp_meas_ready = false;
CRITICAL_SECTION_END; CRITICAL_SECTION_END;
for(int e = 0; e < EXTRUDERS; e++)
{
#ifdef PIDTEMP #ifdef PIDTEMP
pid_input = analog2temp(current_raw[TEMPSENSOR_HOTEND_0]); pid_input = analog2temp(current_raw[e], e);
#ifndef PID_OPENLOOP #ifndef PID_OPENLOOP
pid_error = pid_setpoint - pid_input; pid_error[e] = pid_setpoint[e] - pid_input;
if(pid_error > 10){ if(pid_error[e] > 10) {
pid_output = PID_MAX; pid_output = PID_MAX;
pid_reset = true; pid_reset[e] = true;
} }
else if(pid_error < -10) { else if(pid_error[e] < -10) {
pid_output = 0; pid_output = 0;
pid_reset = true; pid_reset[e] = true;
} }
else { else {
if(pid_reset == true) { if(pid_reset[e] == true) {
temp_iState = 0.0; temp_iState[e] = 0.0;
pid_reset = false; pid_reset[e] = false;
} }
pTerm = Kp * pid_error; pTerm[e] = Kp * pid_error[e];
temp_iState += pid_error; temp_iState[e] += pid_error[e];
temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max); temp_iState[e] = constrain(temp_iState[e], temp_iState_min[e], temp_iState_max[e]);
iTerm = Ki * temp_iState; iTerm[e] = Ki * temp_iState[e];
//K1 defined in Configuration.h in the PID settings //K1 defined in Configuration.h in the PID settings
#define K2 (1.0-K1) #define K2 (1.0-K1)
dTerm = (Kd * (pid_input - temp_dState))*K2 + (K1 * dTerm); dTerm[e] = (Kd * (pid_input - temp_dState[e]))*K2 + (K1 * dTerm[e]);
temp_dState = pid_input; temp_dState[e] = pid_input;
// #ifdef PID_ADD_EXTRUSION_RATE pid_output = constrain(pTerm[e] + iTerm[e] - dTerm[e], 0, PID_MAX);
// pTerm+=Kc*current_block->speed_e; //additional heating if extrusion speed is high
// #endif
pid_output = constrain(pTerm + iTerm - dTerm, 0, PID_MAX);
} }
#endif //PID_OPENLOOP #endif //PID_OPENLOOP
#ifdef PID_DEBUG #ifdef PID_DEBUG
//SERIAL_ECHOLN(" PIDDEBUG Input "<<pid_input<<" Output "<<pid_output" pTerm "<<pTerm<<" iTerm "<<iTerm<<" dTerm "<<dTerm); SERIAL_ECHOLN(" PIDDEBUG "<<e<<": Input "<<pid_input<<" Output "<<pid_output" pTerm "<<pTerm[e]<<" iTerm "<<iTerm[e]<<" dTerm "<<dTerm[e]);
#endif //PID_DEBUG #endif //PID_DEBUG
HeaterPower=pid_output; #else /* PID off */
// Check if temperature is within the correct range pid_output = 0;
if((current_raw[TEMPSENSOR_HOTEND_0] > minttemp_0) && (current_raw[TEMPSENSOR_HOTEND_0] < maxttemp_0)) { if(current_raw[e] < target_raw[e]) {
analogWrite(HEATER_0_PIN, pid_output); pid_output = PID_MAX;
} }
else {
analogWrite(HEATER_0_PIN, 0);
}
#endif //PIDTEMP
#ifndef PIDTEMP
// Check if temperature is within the correct range
if((current_raw[TEMPSENSOR_HOTEND_0] > minttemp_0) && (current_raw[TEMPSENSOR_HOTEND_0] < maxttemp_0)) {
if(current_raw[TEMPSENSOR_HOTEND_0] >= target_raw[TEMPSENSOR_HOTEND_0]) {
WRITE(HEATER_0_PIN,LOW);
}
else {
WRITE(HEATER_0_PIN,HIGH);
}
}
else {
WRITE(HEATER_0_PIN,LOW);
}
#endif #endif
// Check if temperature is within the correct range
if((current_raw[e] > minttemp[e]) && (current_raw[e] < maxttemp[e]))
{
//analogWrite(heater_pin_map[e], pid_output);
soft_pwm[e] = (int)pid_output >> 1;
}
else {
//analogWrite(heater_pin_map[e], 0);
soft_pwm[e] = 0;
}
} // End extruder for loop
#ifdef WATCHPERIOD #ifdef WATCHPERIOD
if(watchmillis && millis() - watchmillis > WATCHPERIOD){ if(watchmillis && millis() - watchmillis > WATCHPERIOD){
@ -204,20 +232,20 @@ void manage_heater()
return; return;
previous_millis_bed_heater = millis(); previous_millis_bed_heater = millis();
#if TEMP_1_PIN > -1 #if TEMP_BED_PIN > -1
// Check if temperature is within the correct range // Check if temperature is within the correct range
if((current_raw[TEMPSENSOR_BED] > bed_minttemp) && (current_raw[TEMPSENSOR_BED] < bed_maxttemp)) { if((current_raw_bed > bed_minttemp) && (current_raw_bed < bed_maxttemp)) {
if(current_raw[TEMPSENSOR_BED] >= target_raw[TEMPSENSOR_BED]) if(current_raw_bed >= target_raw_bed)
{ {
WRITE(HEATER_1_PIN,LOW); WRITE(HEATER_BED_PIN,LOW);
} }
else else
{ {
WRITE(HEATER_1_PIN,HIGH); WRITE(HEATER_BED_PIN,HIGH);
} }
} }
else { else {
WRITE(HEATER_1_PIN,LOW); WRITE(HEATER_BED_PIN,LOW);
} }
#endif #endif
} }
@ -227,30 +255,38 @@ void manage_heater()
// For a thermistor, it uses the RepRap thermistor temp table. // For a thermistor, it uses the RepRap thermistor temp table.
// This is needed because PID in hydra firmware hovers around a given analog value, not a temp value. // This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
// This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware. // This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
int temp2analog(int celsius) { int temp2analog(int celsius, uint8_t e) {
#ifdef HEATER_0_USES_THERMISTOR if(e >= EXTRUDERS)
{
SERIAL_ERROR_START;
SERIAL_ERROR((int)e);
SERIAL_ERRORLNPGM(" - Invalid extruder number!");
kill();
}
if(heater_ttbl_map[e] != 0)
{
int raw = 0; int raw = 0;
byte i; byte i;
short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]);
for (i=1; i<NUMTEMPS_HEATER_0; i++) for (i=1; i<heater_ttbllen_map[e]; i++)
{ {
if (PGM_RD_W(heater_0_temptable[i][1]) < celsius) if (PGM_RD_W((*tt)[i][1]) < celsius)
{ {
raw = PGM_RD_W(heater_0_temptable[i-1][0]) + raw = PGM_RD_W((*tt)[i-1][0]) +
(celsius - PGM_RD_W(heater_0_temptable[i-1][1])) * (celsius - PGM_RD_W((*tt)[i-1][1])) *
(PGM_RD_W(heater_0_temptable[i][0]) - PGM_RD_W(heater_0_temptable[i-1][0])) / (PGM_RD_W((*tt)[i][0]) - PGM_RD_W((*tt)[i-1][0])) /
(PGM_RD_W(heater_0_temptable[i][1]) - PGM_RD_W(heater_0_temptable[i-1][1])); (PGM_RD_W((*tt)[i][1]) - PGM_RD_W((*tt)[i-1][1]));
break; break;
} }
} }
// Overflow: Set to last value in the table // Overflow: Set to last value in the table
if (i == NUMTEMPS_HEATER_0) raw = PGM_RD_W(heater_0_temptable[i-1][0]); if (i == heater_ttbllen_map[e]) raw = PGM_RD_W((*tt)[i-1][0]);
return (1023 * OVERSAMPLENR) - raw; return (1023 * OVERSAMPLENR) - raw;
#elif defined HEATER_0_USES_AD595 }
return celsius * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR; return celsius * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
#endif
} }
// Takes bed temperature value as input and returns corresponding raw value. // Takes bed temperature value as input and returns corresponding raw value.
@ -258,12 +294,11 @@ int temp2analog(int celsius) {
// This is needed because PID in hydra firmware hovers around a given analog value, not a temp value. // This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
// This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware. // This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
int temp2analogBed(int celsius) { int temp2analogBed(int celsius) {
#ifdef BED_USES_THERMISTOR #ifdef BED_USES_THERMISTOR
int raw = 0; int raw = 0;
byte i; byte i;
for (i=1; i<BNUMTEMPS; i++) for (i=1; i<bedtemptable_len; i++)
{ {
if (PGM_RD_W(bedtemptable[i][1]) < celsius) if (PGM_RD_W(bedtemptable[i][1]) < celsius)
{ {
@ -277,45 +312,52 @@ int temp2analogBed(int celsius) {
} }
// Overflow: Set to last value in the table // Overflow: Set to last value in the table
if (i == BNUMTEMPS) raw = PGM_RD_W(bedtemptable[i-1][0]); if (i == bedtemptable_len) raw = PGM_RD_W(bedtemptable[i-1][0]);
return (1023 * OVERSAMPLENR) - raw; return (1023 * OVERSAMPLENR) - raw;
#elif defined BED_USES_AD595 #elif defined BED_USES_AD595
return lround(celsius * (1024.0 * OVERSAMPLENR/ (5.0 * 100.0) ) ); return lround(celsius * (1024.0 * OVERSAMPLENR/ (5.0 * 100.0) ) );
#else #else
#warning No heater-type defined for the bed. #warning No heater-type defined for the bed.
#endif return 0;
return 0; #endif
} }
// Derived from RepRap FiveD extruder::getTemperature() // Derived from RepRap FiveD extruder::getTemperature()
// For hot end temperature measurement. // For hot end temperature measurement.
float analog2temp(int raw) { float analog2temp(int raw, uint8_t e) {
#ifdef HEATER_0_USES_THERMISTOR if(e >= EXTRUDERS)
{
SERIAL_ERROR_START;
SERIAL_ERROR((int)e);
SERIAL_ERRORLNPGM(" - Invalid extruder number !");
kill();
}
if(heater_ttbl_map[e] != 0)
{
float celsius = 0; float celsius = 0;
byte i; byte i;
short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]);
raw = (1023 * OVERSAMPLENR) - raw; raw = (1023 * OVERSAMPLENR) - raw;
for (i=1; i<NUMTEMPS_HEATER_0; i++) for (i=1; i<heater_ttbllen_map[e]; i++)
{ {
if (PGM_RD_W(heater_0_temptable[i][0]) > raw) if (PGM_RD_W((*tt)[i][0]) > raw)
{ {
celsius = PGM_RD_W(heater_0_temptable[i-1][1]) + celsius = PGM_RD_W((*tt)[i-1][1]) +
(raw - PGM_RD_W(heater_0_temptable[i-1][0])) * (raw - PGM_RD_W((*tt)[i-1][0])) *
(float)(PGM_RD_W(heater_0_temptable[i][1]) - PGM_RD_W(heater_0_temptable[i-1][1])) / (float)(PGM_RD_W((*tt)[i][1]) - PGM_RD_W((*tt)[i-1][1])) /
(float)(PGM_RD_W(heater_0_temptable[i][0]) - PGM_RD_W(heater_0_temptable[i-1][0])); (float)(PGM_RD_W((*tt)[i][0]) - PGM_RD_W((*tt)[i-1][0]));
break; break;
} }
} }
// Overflow: Set to last value in the table // Overflow: Set to last value in the table
if (i == NUMTEMPS_HEATER_0) celsius = PGM_RD_W(heater_0_temptable[i-1][1]); if (i == heater_ttbllen_map[e]) celsius = PGM_RD_W((*tt)[i-1][1]);
return celsius; return celsius;
#elif defined HEATER_0_USES_AD595 }
return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR; return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
#else
#error PLEASE DEFINE HEATER TYPE
#endif
} }
// Derived from RepRap FiveD extruder::getTemperature() // Derived from RepRap FiveD extruder::getTemperature()
@ -327,7 +369,7 @@ float analog2tempBed(int raw) {
raw = (1023 * OVERSAMPLENR) - raw; raw = (1023 * OVERSAMPLENR) - raw;
for (i=1; i<BNUMTEMPS; i++) for (i=1; i<bedtemptable_len; i++)
{ {
if (PGM_RD_W(bedtemptable[i][0]) > raw) if (PGM_RD_W(bedtemptable[i][0]) > raw)
{ {
@ -341,7 +383,7 @@ float analog2tempBed(int raw) {
} }
// Overflow: Set to last value in the table // Overflow: Set to last value in the table
if (i == BNUMTEMPS) celsius = PGM_RD_W(bedtemptable[i-1][1]); if (i == bedtemptable_len) celsius = PGM_RD_W(bedtemptable[i-1][1]);
return celsius; return celsius;
@ -355,6 +397,19 @@ float analog2tempBed(int raw) {
void tp_init() void tp_init()
{ {
// Finish init of mult extruder arrays
for(int e = 0; e < EXTRUDERS; e++) {
// populate with the first value
#ifdef WATCHPERIOD
watch_raw[e] = watch_raw[0];
#endif
maxttemp[e] = maxttemp[0];
#ifdef PIDTEMP
temp_iState_min[e] = 0.0;
temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / Ki;
#endif //PIDTEMP
}
#if (HEATER_0_PIN > -1) #if (HEATER_0_PIN > -1)
SET_OUTPUT(HEATER_0_PIN); SET_OUTPUT(HEATER_0_PIN);
#endif #endif
@ -364,11 +419,12 @@ void tp_init()
#if (HEATER_2_PIN > -1) #if (HEATER_2_PIN > -1)
SET_OUTPUT(HEATER_2_PIN); SET_OUTPUT(HEATER_2_PIN);
#endif #endif
#if (HEATER_BED_PIN > -1)
#ifdef PIDTEMP SET_OUTPUT(HEATER_BED_PIN);
temp_iState_min = 0.0; #endif
temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki; #if (FAN_PIN > -1)
#endif //PIDTEMP SET_OUTPUT(FAN_PIN);
#endif
// Set analog inputs // Set analog inputs
ADCSRA = 1<<ADEN | 1<<ADSC | 1<<ADIF | 0x07; ADCSRA = 1<<ADEN | 1<<ADSC | 1<<ADIF | 0x07;
@ -381,7 +437,6 @@ void tp_init()
DIDR0 |= 1 << TEMP_0_PIN; DIDR0 |= 1 << TEMP_0_PIN;
#else #else
DIDR2 |= 1<<(TEMP_0_PIN - 8); DIDR2 |= 1<<(TEMP_0_PIN - 8);
ADCSRB = 1<<MUX5;
#endif #endif
#endif #endif
#if (TEMP_1_PIN > -1) #if (TEMP_1_PIN > -1)
@ -389,7 +444,6 @@ void tp_init()
DIDR0 |= 1<<TEMP_1_PIN; DIDR0 |= 1<<TEMP_1_PIN;
#else #else
DIDR2 |= 1<<(TEMP_1_PIN - 8); DIDR2 |= 1<<(TEMP_1_PIN - 8);
ADCSRB = 1<<MUX5;
#endif #endif
#endif #endif
#if (TEMP_2_PIN > -1) #if (TEMP_2_PIN > -1)
@ -397,7 +451,13 @@ void tp_init()
DIDR0 |= 1 << TEMP_2_PIN; DIDR0 |= 1 << TEMP_2_PIN;
#else #else
DIDR2 = 1<<(TEMP_2_PIN - 8); DIDR2 = 1<<(TEMP_2_PIN - 8);
ADCSRB = 1<<MUX5; #endif
#endif
#if (TEMP_BED_PIN > -1)
#if TEMP_BED_PIN < 8
DIDR0 |= 1<<TEMP_BED_PIN;
#else
DIDR2 |= 1<<(TEMP_BED_PIN - 8);
#endif #endif
#endif #endif
@ -407,27 +467,34 @@ void tp_init()
TIMSK0 |= (1<<OCIE0B); TIMSK0 |= (1<<OCIE0B);
// Wait for temperature measurement to settle // Wait for temperature measurement to settle
delay(200); delay(250);
#ifdef HEATER_0_MINTEMP #ifdef HEATER_0_MINTEMP
minttemp_0 = temp2analog(HEATER_0_MINTEMP); minttemp[0] = temp2analog(HEATER_0_MINTEMP, 0);
#endif //MINTEMP #endif //MINTEMP
#ifdef HEATER_0_MAXTEMP #ifdef HEATER_0_MAXTEMP
maxttemp_0 = temp2analog(HEATER_0_MAXTEMP); maxttemp[0] = temp2analog(HEATER_0_MAXTEMP, 0);
#endif //MAXTEMP #endif //MAXTEMP
#ifdef HEATER_1_MINTEMP #if (EXTRUDERS > 1) && defined(HEATER_1_MINTEMP)
minttemp_1 = temp2analog(HEATER_1_MINTEMP); minttemp[1] = temp2analog(HEATER_1_MINTEMP, 1);
#endif //MINTEMP #endif // MINTEMP 1
#ifdef HEATER_1_MAXTEMP #if (EXTRUDERS > 1) && defined(HEATER_1_MAXTEMP)
maxttemp_1 = temp2analog(HEATER_1_MAXTEMP); maxttemp[1] = temp2analog(HEATER_1_MAXTEMP, 1);
#endif //MAXTEMP #endif //MAXTEMP 1
#if (EXTRUDERS > 2) && defined(HEATER_2_MINTEMP)
minttemp[2] = temp2analog(HEATER_2_MINTEMP, 2);
#endif //MINTEMP 2
#if (EXTRUDERS > 2) && defined(HEATER_2_MAXTEMP)
maxttemp[2] = temp2analog(HEATER_2_MAXTEMP, 2);
#endif //MAXTEMP 2
#ifdef BED_MINTEMP #ifdef BED_MINTEMP
bed_minttemp = temp2analog(BED_MINTEMP); bed_minttemp = temp2analogBed(BED_MINTEMP);
#endif //BED_MINTEMP #endif //BED_MINTEMP
#ifdef BED_MAXTEMP #ifdef BED_MAXTEMP
bed_maxttemp = temp2analog(BED_MAXTEMP); bed_maxttemp = temp2analogBed(BED_MAXTEMP);
#endif //BED_MAXTEMP #endif //BED_MAXTEMP
} }
@ -436,15 +503,17 @@ void tp_init()
void setWatch() void setWatch()
{ {
#ifdef WATCHPERIOD #ifdef WATCHPERIOD
if(isHeatingHotend0()) int t = 0;
for (int e = 0; e < EXTRUDERS; e++)
{ {
watchmillis = max(1,millis()); if(isHeatingHotend(e))
watch_oldtemp[TEMPSENSOR_HOTEND_0] = degHotend(0); watch_oldtemp[TEMPSENSOR_HOTEND_0] = degHotend(0);
{
t = max(t,millis());
watch_raw[e] = current_raw[e];
}
} }
else watchmillis = t;
{
watchmillis = 0;
}
#endif #endif
} }
@ -453,6 +522,7 @@ void disable_heater()
{ {
#if TEMP_0_PIN > -1 #if TEMP_0_PIN > -1
target_raw[0]=0; target_raw[0]=0;
soft_pwm[0]=0;
#if HEATER_0_PIN > -1 #if HEATER_0_PIN > -1
digitalWrite(HEATER_0_PIN,LOW); digitalWrite(HEATER_0_PIN,LOW);
#endif #endif
@ -460,6 +530,7 @@ void disable_heater()
#if TEMP_1_PIN > -1 #if TEMP_1_PIN > -1
target_raw[1]=0; target_raw[1]=0;
soft_pwm[1]=0;
#if HEATER_1_PIN > -1 #if HEATER_1_PIN > -1
digitalWrite(HEATER_1_PIN,LOW); digitalWrite(HEATER_1_PIN,LOW);
#endif #endif
@ -467,10 +538,38 @@ void disable_heater()
#if TEMP_2_PIN > -1 #if TEMP_2_PIN > -1
target_raw[2]=0; target_raw[2]=0;
soft_pwm[2]=0;
#if HEATER_2_PIN > -1 #if HEATER_2_PIN > -1
digitalWrite(HEATER_2_PIN,LOW); digitalWrite(HEATER_2_PIN,LOW);
#endif #endif
#endif #endif
#if TEMP_BED_PIN > -1
target_raw_bed=0;
#if HEATER_BED_PIN > -1
digitalWrite(HEATER_BED_PIN,LOW);
#endif
#endif
}
void max_temp_error(uint8_t e) {
digitalWrite(heater_pin_map[e], 0);
SERIAL_ERROR_START;
SERIAL_ERRORLN(e);
SERIAL_ERRORLNPGM(": Extruder switched off. MAXTEMP triggered !");
}
void min_temp_error(uint8_t e) {
digitalWrite(heater_pin_map[e], 0);
SERIAL_ERROR_START;
SERIAL_ERRORLN(e);
SERIAL_ERRORLNPGM(": Extruder switched off. MINTEMP triggered !");
}
void bed_max_temp_error(void) {
digitalWrite(HEATER_BED_PIN, 0);
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !!");
} }
// Timer 0 is shared with millies // Timer 0 is shared with millies
@ -481,7 +580,35 @@ ISR(TIMER0_COMPB_vect)
static unsigned long raw_temp_0_value = 0; static unsigned long raw_temp_0_value = 0;
static unsigned long raw_temp_1_value = 0; static unsigned long raw_temp_1_value = 0;
static unsigned long raw_temp_2_value = 0; static unsigned long raw_temp_2_value = 0;
static unsigned long raw_temp_bed_value = 0;
static unsigned char temp_state = 0; static unsigned char temp_state = 0;
static unsigned char pwm_count = 1;
static unsigned char soft_pwm_0;
static unsigned char soft_pwm_1;
static unsigned char soft_pwm_2;
if(pwm_count == 0){
soft_pwm_0 = soft_pwm[0];
if(soft_pwm_0 > 0) WRITE(HEATER_0_PIN,1);
#if EXTRUDERS > 1
soft_pwm_1 = soft_pwm[1];
if(soft_pwm_1 > 0) WRITE(HEATER_1_PIN,1);
#endif
#if EXTRUDERS > 2
soft_pwm_2 = soft_pwm[2];
if(soft_pwm_2 > 0) WRITE(HEATER_2_PIN,1);
#endif
}
if(soft_pwm_0 <= pwm_count) WRITE(HEATER_0_PIN,0);
#if EXTRUDERS > 1
if(soft_pwm_1 <= pwm_count) WRITE(HEATER_1_PIN,0);
#endif
#if EXTRUDERS > 2
if(soft_pwm_2 <= pwm_count) WRITE(HEATER_2_PIN,0);
#endif
pwm_count++;
pwm_count &= 0x7f;
switch(temp_state) { switch(temp_state) {
case 0: // Prepare TEMP_0 case 0: // Prepare TEMP_0
@ -505,7 +632,26 @@ ISR(TIMER0_COMPB_vect)
#endif #endif
temp_state = 2; temp_state = 2;
break; break;
case 2: // Prepare TEMP_1 case 2: // Prepare TEMP_BED
#if (TEMP_BED_PIN > -1)
#if TEMP_BED_PIN > 7
ADCSRB = 1<<MUX5;
#endif
ADMUX = ((1 << REFS0) | (TEMP_BED_PIN & 0x07));
ADCSRA |= 1<<ADSC; // Start conversion
#endif
#ifdef ULTIPANEL
buttons_check();
#endif
temp_state = 3;
break;
case 3: // Measure TEMP_BED
#if (TEMP_BED_PIN > -1)
raw_temp_bed_value += ADC;
#endif
temp_state = 4;
break;
case 4: // Prepare TEMP_1
#if (TEMP_1_PIN > -1) #if (TEMP_1_PIN > -1)
#if TEMP_1_PIN > 7 #if TEMP_1_PIN > 7
ADCSRB = 1<<MUX5; ADCSRB = 1<<MUX5;
@ -518,15 +664,15 @@ ISR(TIMER0_COMPB_vect)
#ifdef ULTIPANEL #ifdef ULTIPANEL
buttons_check(); buttons_check();
#endif #endif
temp_state = 3; temp_state = 5;
break; break;
case 3: // Measure TEMP_1 case 5: // Measure TEMP_1
#if (TEMP_1_PIN > -1) #if (TEMP_1_PIN > -1)
raw_temp_1_value += ADC; raw_temp_1_value += ADC;
#endif #endif
temp_state = 4; temp_state = 6;
break; break;
case 4: // Prepare TEMP_2 case 6: // Prepare TEMP_2
#if (TEMP_2_PIN > -1) #if (TEMP_2_PIN > -1)
#if TEMP_2_PIN > 7 #if TEMP_2_PIN > 7
ADCSRB = 1<<MUX5; ADCSRB = 1<<MUX5;
@ -539,39 +685,49 @@ ISR(TIMER0_COMPB_vect)
#ifdef ULTIPANEL #ifdef ULTIPANEL
buttons_check(); buttons_check();
#endif #endif
temp_state = 5; temp_state = 7;
break; break;
case 5: // Measure TEMP_2 case 7: // Measure TEMP_2
#if (TEMP_2_PIN > -1) #if (TEMP_2_PIN > -1)
raw_temp_2_value += ADC; raw_temp_2_value += ADC;
#endif #endif
temp_state = 0; temp_state = 0;
temp_count++; temp_count++;
break; break;
default: // default:
SERIAL_ERROR_START; // SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Temp measurement error!"); // SERIAL_ERRORLNPGM("Temp measurement error!");
break; // break;
} }
if(temp_count >= 16) // 6 ms * 16 = 96ms. if(temp_count >= 16) // 8 ms * 16 = 128ms.
{ {
#ifdef HEATER_0_USES_AD595 #ifdef HEATER_0_USES_AD595
current_raw[0] = raw_temp_0_value; current_raw[0] = raw_temp_0_value;
#else #else
current_raw[0] = 16383 - raw_temp_0_value; current_raw[0] = 16383 - raw_temp_0_value;
#endif #endif
#if EXTRUDERS > 1
#ifdef HEATER_1_USES_AD595 #ifdef HEATER_1_USES_AD595
current_raw[1] = raw_temp_1_value;
#else
current_raw[1] = 16383 - raw_temp_1_value;
#endif
#endif
#if EXTRUDERS > 2
#ifdef HEATER_2_USES_AD595
current_raw[2] = raw_temp_2_value; current_raw[2] = raw_temp_2_value;
#else #else
current_raw[2] = 16383 - raw_temp_2_value; current_raw[2] = 16383 - raw_temp_2_value;
#endif #endif
#endif
#ifdef BED_USES_AD595 #ifdef BED_USES_AD595
current_raw[1] = raw_temp_1_value; current_raw_bed = raw_temp_bed_value;
#else #else
current_raw[1] = 16383 - raw_temp_1_value; current_raw_bed = 16383 - raw_temp_bed_value;
#endif #endif
temp_meas_ready = true; temp_meas_ready = true;
@ -579,77 +735,28 @@ ISR(TIMER0_COMPB_vect)
raw_temp_0_value = 0; raw_temp_0_value = 0;
raw_temp_1_value = 0; raw_temp_1_value = 0;
raw_temp_2_value = 0; raw_temp_2_value = 0;
#ifdef HEATER_0_MAXTEMP raw_temp_bed_value = 0;
#if (HEATER_0_PIN > -1)
if(current_raw[TEMPSENSOR_HOTEND_0] >= maxttemp_0) { for(unsigned char e = 0; e < EXTRUDERS; e++) {
target_raw[TEMPSENSOR_HOTEND_0] = 0; if(current_raw[e] >= maxttemp[e]) {
digitalWrite(HEATER_0_PIN, 0); target_raw[e] = 0;
SERIAL_ERROR_START; max_temp_error(e);
SERIAL_ERRORLNPGM("Temperature extruder 0 switched off. MAXTEMP triggered !!"); kill();;
}
if(current_raw[e] <= minttemp[e]) {
target_raw[e] = 0;
min_temp_error(e);
kill(); kill();
} }
#endif }
#endif
#ifdef HEATER_1_MAXTEMP
#if (HEATER_1_PIN > -1)
if(current_raw[TEMPSENSOR_HOTEND_1] >= maxttemp_1) {
target_raw[TEMPSENSOR_HOTEND_1] = 0;
digitalWrite(HEATER_2_PIN, 0);
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Temperature extruder 1 switched off. MAXTEMP triggered !!");
kill();
}
#endif
#endif //MAXTEMP
#ifdef HEATER_0_MINTEMP #if defined(BED_MAXTEMP) && (HEATER_BED_PIN > -1)
#if (HEATER_0_PIN > -1) if(current_raw_bed >= bed_maxttemp) {
if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) { target_raw_bed = 0;
target_raw[TEMPSENSOR_HOTEND_0] = 0; bed_max_temp_error();
digitalWrite(HEATER_0_PIN, 0); kill();
SERIAL_ERROR_START; }
SERIAL_ERRORLNPGM("Temperature extruder 0 switched off. MINTEMP triggered !!"); #endif
kill();
}
#endif
#endif
#ifdef HEATER_1_MINTEMP
#if (HEATER_2_PIN > -1)
if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) {
target_raw[TEMPSENSOR_HOTEND_1] = 0;
digitalWrite(HEATER_2_PIN, 0);
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Temperature extruder 1 switched off. MINTEMP triggered !!");
kill();
}
#endif
#endif //MAXTEMP
#ifdef BED_MINTEMP
#if (HEATER_1_PIN > -1)
if(current_raw[1] <= bed_minttemp) {
target_raw[1] = 0;
digitalWrite(HEATER_1_PIN, 0);
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Temperatur heated bed switched off. MINTEMP triggered !!");
kill();
}
#endif
#endif
#ifdef BED_MAXTEMP
#if (HEATER_1_PIN > -1)
if(current_raw[1] >= bed_maxttemp) {
target_raw[1] = 0;
digitalWrite(HEATER_1_PIN, 0);
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !!");
kill();
}
#endif
#endif
} }
} }

View file

@ -32,95 +32,111 @@
void tp_init(); //initialise the heating void tp_init(); //initialise the heating
void manage_heater(); //it is critical that this is called periodically. void manage_heater(); //it is critical that this is called periodically.
enum TempSensor {TEMPSENSOR_HOTEND_0=0,TEMPSENSOR_BED=1, TEMPSENSOR_HOTEND_1=2};
//low leven conversion routines //low leven conversion routines
// do not use this routines and variables outsie of temperature.cpp // do not use this routines and variables outsie of temperature.cpp
int temp2analog(int celsius); int temp2analog(int celsius, uint8_t e);
int temp2analogBed(int celsius); int temp2analogBed(int celsius);
float analog2temp(int raw); float analog2temp(int raw, uint8_t e);
float analog2tempBed(int raw); float analog2tempBed(int raw);
extern int target_raw[3]; extern int target_raw[EXTRUDERS];
extern int heatingtarget_raw[3]; extern int heatingtarget_raw[EXTRUDERS];
extern int current_raw[3]; extern int current_raw[EXTRUDERS];
extern int target_raw_bed;
extern int current_raw_bed;
extern float Kp,Ki,Kd,Kc; extern float Kp,Ki,Kd,Kc;
#ifdef PIDTEMP #ifdef PIDTEMP
extern float pid_setpoint ; extern float pid_setpoint[EXTRUDERS];
#endif #endif
// #ifdef WATCHPERIOD // #ifdef WATCHPERIOD
// extern int watch_raw[3] ; extern int watch_raw[EXTRUDERS] ;
// extern unsigned long watchmillis; // extern unsigned long watchmillis;
// #endif // #endif
//high level conversion routines, for use outside of temperature.cpp //high level conversion routines, for use outside of temperature.cpp
//inline so that there is no performance decrease. //inline so that there is no performance decrease.
//deg=degreeCelsius //deg=degreeCelsius
FORCE_INLINE float degHotend0(){ return analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);}; FORCE_INLINE float degHotend(uint8_t extruder) {
FORCE_INLINE float degHotend1(){ return analog2temp(current_raw[TEMPSENSOR_HOTEND_1]);}; return analog2temp(current_raw[extruder], extruder);
FORCE_INLINE float degBed() { return analog2tempBed(current_raw[TEMPSENSOR_BED]);};
FORCE_INLINE float degHotend(uint8_t extruder){
if(extruder == 0) return analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);
if(extruder == 1) return analog2temp(current_raw[TEMPSENSOR_HOTEND_1]);
}; };
FORCE_INLINE float degTargetHotend0() { return analog2temp(target_raw[TEMPSENSOR_HOTEND_0]);}; FORCE_INLINE float degBed() {
FORCE_INLINE float degTargetHotend1() { return analog2temp(target_raw[TEMPSENSOR_HOTEND_1]);}; return analog2tempBed(current_raw_bed);
FORCE_INLINE float degTargetHotend(uint8_t extruder){
if(extruder == 0) return analog2temp(target_raw[TEMPSENSOR_HOTEND_0]);
if(extruder == 1) return analog2temp(target_raw[TEMPSENSOR_HOTEND_1]);
}; };
FORCE_INLINE float degTargetBed() { return analog2tempBed(target_raw[TEMPSENSOR_BED]);}; FORCE_INLINE float degTargetHotend(uint8_t extruder) {
return analog2temp(target_raw[extruder], extruder);
FORCE_INLINE void setTargetHotend0(const float &celsius) };
{
target_raw[TEMPSENSOR_HOTEND_0]=temp2analog(celsius); FORCE_INLINE float degTargetBed() {
heatingtarget_raw[TEMPSENSOR_HOTEND_0]=temp2analog(celsius-HEATING_EARLY_FINISH_DEG_OFFSET); return analog2tempBed(target_raw_bed);
#ifdef PIDTEMP };
pid_setpoint = celsius;
#endif //PIDTEMP FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) {
target_raw[extruder] = temp2analog(celsius, extruder);
#ifdef PIDTEMP
pid_setpoint[extruder] = celsius;
#endif //PIDTEMP
};
FORCE_INLINE void setTargetBed(const float &celsius) {
target_raw_bed = temp2analogBed(celsius);
}; };
FORCE_INLINE void setTargetHotend1(const float &celsius) { target_raw[TEMPSENSOR_HOTEND_1]=temp2analog(celsius);};
FORCE_INLINE void setTargetHotend(const float &celcius, uint8_t extruder){
if(extruder == 0) setTargetHotend0(celcius);
if(extruder == 1) setTargetHotend1(celcius);
};
FORCE_INLINE void setTargetBed(const float &celsius) { target_raw[TEMPSENSOR_BED ]=temp2analogBed(celsius);};
FORCE_INLINE bool isHeatingHotend0() {return heatingtarget_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0];};
FORCE_INLINE bool isHeatingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];};
FORCE_INLINE bool isHeatingHotend(uint8_t extruder){ FORCE_INLINE bool isHeatingHotend(uint8_t extruder){
if(extruder == 0) return heatingtarget_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0]; return target_raw[extruder] > current_raw[extruder];
if(extruder == 1) return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];
return false;
}; };
FORCE_INLINE bool isHeatingBed() {return target_raw[TEMPSENSOR_BED] > current_raw[TEMPSENSOR_BED];};
FORCE_INLINE bool isCoolingHotend0() {return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0];}; FORCE_INLINE bool isHeatingBed() {
FORCE_INLINE bool isCoolingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1];}; return target_raw_bed > current_raw_bed;
FORCE_INLINE bool isCoolingHotend(uint8_t extruder){
if(extruder == 0) return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0];
if(extruder == 1) return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1];
return false;
}; };
FORCE_INLINE bool isCoolingBed() {return target_raw[TEMPSENSOR_BED] < current_raw[TEMPSENSOR_BED];};
FORCE_INLINE bool isCoolingHotend(uint8_t extruder) {
return target_raw[extruder] < current_raw[extruder];
};
FORCE_INLINE bool isCoolingBed() {
return target_raw_bed < current_raw_bed;
};
#define degHotend0() degHotend(0)
#define degTargetHotend0() degTargetHotend(0)
#define setTargetHotend0(_celsius) setTargetHotend((_celsius), 0)
#define isHeatingHotend0() isHeatingHotend(0)
#define isCoolingHotend0() isCoolingHotend(0)
#if EXTRUDERS > 1
#define degHotend1() degHotend(1)
#define degTargetHotend1() degTargetHotend(1)
#define setTargetHotend1(_celsius) setTargetHotend((_celsius), 1)
#define isHeatingHotend1() isHeatingHotend(1)
#define isCoolingHotend1() isCoolingHotend(1)
#endif
#if EXTRUDERS > 2
#define degHotend2() degHotend(2)
#define degTargetHotend2() degTargetHotend(2)
#define setTargetHotend2(_celsius) setTargetHotend((_celsius), 2)
#define isHeatingHotend2() isHeatingHotend(2)
#define isCoolingHotend2() isCoolingHotend(2)
#endif
#if EXTRUDERS > 3
#error Invalid number of extruders
#endif
FORCE_INLINE void autotempShutdown(){ FORCE_INLINE void autotempShutdown(){
#ifdef AUTOTEMP #ifdef AUTOTEMP
if(autotemp_enabled) if(autotemp_enabled)
{ {
autotemp_enabled=false; autotemp_enabled=false;
if(degTargetHotend0()>autotemp_min) if(degTargetHotend(ACTIVE_EXTRUDER)>autotemp_min)
setTargetHotend0(0); setTargetHotend(0,ACTIVE_EXTRUDER);
} }
#endif #endif
} }
int getHeaterPower(int heater);
void disable_heater(); void disable_heater();
void setWatch(); void setWatch();
void updatePID(); void updatePID();

View file

@ -5,10 +5,9 @@
#define OVERSAMPLENR 16 #define OVERSAMPLENR 16
#if (THERMISTORHEATER_0 == 1) || (THERMISTORHEATER_1 == 1) || (THERMISTORBED == 1) //100k bed thermistor #if (THERMISTORHEATER_0 == 1) || (THERMISTORHEATER_1 == 1) || (THERMISTORHEATER_2 == 1) || (THERMISTORBED == 1) //100k bed thermistor
#define NUMTEMPS_1 61 const short temptable_1[][2] PROGMEM = {
const short temptable_1[NUMTEMPS_1][2] PROGMEM = {
{ 23*OVERSAMPLENR , 300 }, { 23*OVERSAMPLENR , 300 },
{ 25*OVERSAMPLENR , 295 }, { 25*OVERSAMPLENR , 295 },
{ 27*OVERSAMPLENR , 290 }, { 27*OVERSAMPLENR , 290 },
@ -72,9 +71,8 @@ const short temptable_1[NUMTEMPS_1][2] PROGMEM = {
{ 1008*OVERSAMPLENR , 0 } //safety { 1008*OVERSAMPLENR , 0 } //safety
}; };
#endif #endif
#if (THERMISTORHEATER_0 == 2) || (THERMISTORHEATER_1 == 2) || (THERMISTORBED == 2) //200k bed thermistor #if (THERMISTORHEATER_0 == 2) || (THERMISTORHEATER_1 == 2) || (THERMISTORHEATER_2 == 2) || (THERMISTORBED == 2) //200k bed thermistor
#define NUMTEMPS_2 21 const short temptable_2[][2] PROGMEM = {
const short temptable_2[NUMTEMPS_2][2] PROGMEM = {
{1*OVERSAMPLENR, 848}, {1*OVERSAMPLENR, 848},
{54*OVERSAMPLENR, 275}, {54*OVERSAMPLENR, 275},
{107*OVERSAMPLENR, 228}, {107*OVERSAMPLENR, 228},
@ -99,9 +97,8 @@ const short temptable_2[NUMTEMPS_2][2] PROGMEM = {
}; };
#endif #endif
#if (THERMISTORHEATER_0 == 3) || (THERMISTORHEATER_1 == 3) || (THERMISTORBED == 3) //mendel-parts #if (THERMISTORHEATER_0 == 3) || (THERMISTORHEATER_1 == 3) || (THERMISTORHEATER_2 == 3) || (THERMISTORBED == 3) //mendel-parts
#define NUMTEMPS_3 28 const short temptable_3[][2] PROGMEM = {
const short temptable_3[NUMTEMPS_3][2] PROGMEM = {
{1*OVERSAMPLENR,864}, {1*OVERSAMPLENR,864},
{21*OVERSAMPLENR,300}, {21*OVERSAMPLENR,300},
{25*OVERSAMPLENR,290}, {25*OVERSAMPLENR,290},
@ -133,10 +130,8 @@ const short temptable_3[NUMTEMPS_3][2] PROGMEM = {
}; };
#endif #endif
#if (THERMISTORHEATER_0 == 4) || (THERMISTORHEATER_1 == 4) || (THERMISTORBED == 4) //10k thermistor #if (THERMISTORHEATER_0 == 4) || (THERMISTORHEATER_1 == 4) || (THERMISTORHEATER_2 == 4) || (THERMISTORBED == 4) //10k thermistor
const short temptable_4[][2] PROGMEM = {
#define NUMTEMPS_4 20
const short temptable_4[NUMTEMPS_4][2] PROGMEM = {
{1*OVERSAMPLENR, 430}, {1*OVERSAMPLENR, 430},
{54*OVERSAMPLENR, 137}, {54*OVERSAMPLENR, 137},
{107*OVERSAMPLENR, 107}, {107*OVERSAMPLENR, 107},
@ -160,10 +155,8 @@ const short temptable_4[NUMTEMPS_4][2] PROGMEM = {
}; };
#endif #endif
#if (THERMISTORHEATER_0 == 5) || (THERMISTORHEATER_1 == 5) || (THERMISTORBED == 5) //100k ParCan thermistor (104GT-2) #if (THERMISTORHEATER_0 == 5) || (THERMISTORHEATER_1 == 5) || (THERMISTORHEATER_2 == 5) || (THERMISTORBED == 5) //100k ParCan thermistor (104GT-2)
const short temptable_5[][2] PROGMEM = {
#define NUMTEMPS_5 61
const short temptable_5[NUMTEMPS_5][2] PROGMEM = {
{1*OVERSAMPLENR, 713}, {1*OVERSAMPLENR, 713},
{18*OVERSAMPLENR, 316}, {18*OVERSAMPLENR, 316},
{35*OVERSAMPLENR, 266}, {35*OVERSAMPLENR, 266},
@ -228,9 +221,8 @@ const short temptable_5[NUMTEMPS_5][2] PROGMEM = {
}; };
#endif #endif
#if (THERMISTORHEATER_0 == 6) || (THERMISTORHEATER_1 == 6) || (THERMISTORBED == 6) // 100k Epcos thermistor #if (THERMISTORHEATER_0 == 6) || (THERMISTORHEATER_1 == 6) || (THERMISTORHEATER_2 == 6) || (THERMISTORBED == 6) // 100k Epcos thermistor
#define NUMTEMPS_6 36 const short temptable_6[][2] PROGMEM = {
const short temptable_6[NUMTEMPS_6][2] PROGMEM = {
{28*OVERSAMPLENR, 250}, {28*OVERSAMPLENR, 250},
{31*OVERSAMPLENR, 245}, {31*OVERSAMPLENR, 245},
{35*OVERSAMPLENR, 240}, {35*OVERSAMPLENR, 240},
@ -270,9 +262,8 @@ const short temptable_6[NUMTEMPS_6][2] PROGMEM = {
}; };
#endif #endif
#if (THERMISTORHEATER_0 == 7) || (THERMISTORHEATER_1 == 7) || (THERMISTORBED == 7) // 100k Honeywell 135-104LAG-J01 #if (THERMISTORHEATER_0 == 7) || (THERMISTORHEATER_1 == 7) || (THERMISTORHEATER_2 == 7) || (THERMISTORBED == 7) // 100k Honeywell 135-104LAG-J01
#define NUMTEMPS_7 54 const short temptable_7[][2] PROGMEM = {
const short temptable_7[NUMTEMPS_7][2] PROGMEM = {
{46*OVERSAMPLENR, 270}, {46*OVERSAMPLENR, 270},
{50*OVERSAMPLENR, 265}, {50*OVERSAMPLENR, 265},
{54*OVERSAMPLENR, 260}, {54*OVERSAMPLENR, 260},
@ -330,82 +321,52 @@ const short temptable_7[NUMTEMPS_7][2] PROGMEM = {
}; };
#endif #endif
#define _TT_NAME(_N) temptable_ ## _N
#define TT_NAME(_N) _TT_NAME(_N)
#ifdef THERMISTORHEATER_0
#if THERMISTORHEATER_0 == 1 #define heater_0_temptable TT_NAME(THERMISTORHEATER_0)
#define NUMTEMPS_HEATER_0 NUMTEMPS_1 #define heater_0_temptable_len (sizeof(heater_0_temptable)/sizeof(*heater_0_temptable))
#define heater_0_temptable temptable_1 #else
#elif THERMISTORHEATER_0 == 2 #ifdef HEATER_0_USES_THERMISTOR
#define NUMTEMPS_HEATER_0 NUMTEMPS_2 #error No heater 0 thermistor table specified
#define heater_0_temptable temptable_2 #else // HEATER_0_USES_THERMISTOR
#elif THERMISTORHEATER_0 == 3 #define heater_0_temptable 0
#define NUMTEMPS_HEATER_0 NUMTEMPS_3 #define heater_0_temptable_len 0
#define heater_0_temptable temptable_3 #endif // HEATER_0_USES_THERMISTOR
#elif THERMISTORHEATER_0 == 4
#define NUMTEMPS_HEATER_0 NUMTEMPS_4
#define heater_0_temptable temptable_4
#elif THERMISTORHEATER_0 == 5
#define NUMTEMPS_HEATER_0 NUMTEMPS_5
#define heater_0_temptable temptable_5
#elif THERMISTORHEATER_0 == 6
#define NUMTEMPS_HEATER_0 NUMTEMPS_6
#define heater_0_temptable temptable_6
#elif THERMISTORHEATER_0 == 7
#define NUMTEMPS_HEATER_0 NUMTEMPS_7
#define heater_0_temptable temptable_7
#elif defined HEATER_0_USES_THERMISTOR
#error No heater 0 thermistor table specified
#endif #endif
#if THERMISTORHEATER_1 == 1 #ifdef THERMISTORHEATER_1
#define NUMTEMPS_HEATER_1 NUMTEMPS_1 #define heater_1_temptable TT_NAME(THERMISTORHEATER_1)
#define heater_1_temptable temptable_1 #define heater_1_temptable_len (sizeof(heater_1_temptable)/sizeof(*heater_1_temptable))
#elif THERMISTORHEATER_1 == 2 #else
#define NUMTEMPS_HEATER_1 NUMTEMPS_2 #ifdef HEATER_1_USES_THERMISTOR
#define heater_1_temptable temptable_2 #error No heater 1 thermistor table specified
#elif THERMISTORHEATER_1 == 3 #else // HEATER_1_USES_THERMISTOR
#define NUMTEMPS_HEATER_1 NUMTEMPS_3 #define heater_1_temptable 0
#define heater_1_temptable temptable_3 #define heater_1_temptable_len 0
#elif THERMISTORHEATER_1 == 4 #endif // HEATER_1_USES_THERMISTOR
#define NUMTEMPS_HEATER_1 NUMTEMPS_4
#define heater_1_temptable temptable_4
#elif THERMISTORHEATER_1 == 5
#define NUMTEMPS_HEATER_1 NUMTEMPS_5
#define heater_1_temptable temptable_5
#elif THERMISTORHEATER_1 == 6
#define NUMTEMPS_HEATER_1 NUMTEMPS_6
#define heater_1_temptable temptable_6
#elif THERMISTORHEATER_1 == 7
#define NUMTEMPS_HEATER_1 NUMTEMPS_7
#define heater_1_temptable temptable_7
#elif defined HEATER_1_USES_THERMISTOR
#error No heater 1 thermistor table specified
#endif #endif
#ifdef THERMISTORHEATER_2
#define heater_2_temptable TT_NAME(THERMISTORHEATER_2)
#define heater_2_temptable_len (sizeof(heater_2_temptable)/sizeof(*heater_2_temptable))
#else
#ifdef HEATER_2_USES_THERMISTOR
#error No heater 2 thermistor table specified
#else // HEATER_2_USES_THERMISTOR
#define heater_2_temptable 0
#define heater_2_temptable_len 0
#endif // HEATER_2_USES_THERMISTOR
#endif
#if THERMISTORBED == 1 #ifdef THERMISTORBED
#define BNUMTEMPS NUMTEMPS_1 #define bedtemptable TT_NAME(THERMISTORBED)
#define bedtemptable temptable_1 #define bedtemptable_len (sizeof(bedtemptable)/sizeof(*bedtemptable))
#elif THERMISTORBED == 2 #else
#define BNUMTEMPS NUMTEMPS_2 #ifdef BED_USES_THERMISTOR
#define bedtemptable temptable_2 #error No bed thermistor table specified
#elif THERMISTORBED == 3 #endif // BED_USES_THERMISTOR
#define BNUMTEMPS NUMTEMPS_3
#define bedtemptable temptable_3
#elif THERMISTORBED == 4
#define BNUMTEMPS NUMTEMPS_4
#define bedtemptable temptable_4
#elif THERMISTORBED == 5
#define BNUMTEMPS NUMTEMPS_5
#define bedtemptable temptable_5
#elif THERMISTORBED == 6
#define BNUMTEMPS NUMTEMPS_6
#define bedtemptable temptable_6
#elif THERMISTORBED == 7
#define BNUMTEMPS NUMTEMPS_7
#define bedtemptable temptable_7
#elif defined BED_USES_THERMISTOR
#error No bed thermistor table specified
#endif #endif
#endif //THERMISTORTABLES_H_ #endif //THERMISTORTABLES_H_

View file

@ -1,1844 +1,1848 @@
#include "ultralcd.h" #include "ultralcd.h"
#ifdef ULTRA_LCD #ifdef ULTRA_LCD
//=========================================================================== //===========================================================================
//=============================imported variables============================ //=============================imported variables============================
//=========================================================================== //===========================================================================
extern volatile int feedmultiply; extern volatile int feedmultiply;
extern volatile bool feedmultiplychanged; extern volatile bool feedmultiplychanged;
extern long position[4]; extern long position[4];
extern CardReader card; extern CardReader card;
//=========================================================================== //===========================================================================
//=============================public variables============================ //=============================public variables============================
//=========================================================================== //===========================================================================
volatile char buttons=0; //the last checked buttons in a bit array. volatile char buttons=0; //the last checked buttons in a bit array.
int encoderpos=0; int encoderpos=0;
short lastenc=0; short lastenc=0;
//=========================================================================== //===========================================================================
//=============================private variables============================ //=============================private variables============================
//=========================================================================== //===========================================================================
static char messagetext[LCD_WIDTH]=""; static char messagetext[LCD_WIDTH]="";
//return for string conversion routines //return for string conversion routines
static char conv[8]; static char conv[8];
#include <LiquidCrystal.h> #include <LiquidCrystal.h>
LiquidCrystal lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7 LiquidCrystal lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
static unsigned long previous_millis_lcd=0; static unsigned long previous_millis_lcd=0;
static long previous_millis_buttons=0; static long previous_millis_buttons=0;
#ifdef NEWPANEL #ifdef NEWPANEL
static long blocking=0; static long blocking=0;
#else #else
static long blocking[8]={0,0,0,0,0,0,0,0}; static long blocking[8]={0,0,0,0,0,0,0,0};
#endif #endif
static MainMenu menu; static MainMenu menu;
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
void lcdProgMemprint(const char *str) void lcdProgMemprint(const char *str)
{ {
char ch=pgm_read_byte(str); char ch=pgm_read_byte(str);
while(ch) while(ch)
{ {
lcd.print(ch); lcd.print(ch);
ch=pgm_read_byte(++str); ch=pgm_read_byte(++str);
} }
} }
#define lcdprintPGM(x) lcdProgMemprint(MYPGM(x)) #define lcdprintPGM(x) lcdProgMemprint(MYPGM(x))
//=========================================================================== //===========================================================================
//=============================functions ============================ //=============================functions ============================
//=========================================================================== //===========================================================================
FORCE_INLINE int intround(const float &x){return int(0.5+x);} FORCE_INLINE int intround(const float &x){return int(0.5+x);}
void lcd_status(const char* message) void lcd_status(const char* message)
{ {
strncpy(messagetext,message,LCD_WIDTH); strncpy(messagetext,message,LCD_WIDTH);
messagetext[strlen(message)]=0; messagetext[strlen(message)]=0;
} }
void lcd_statuspgm(const char* message) void lcd_statuspgm(const char* message)
{ {
char ch=pgm_read_byte(message); char ch=pgm_read_byte(message);
char *target=messagetext; char *target=messagetext;
uint8_t cnt=0; uint8_t cnt=0;
while(ch &&cnt<LCD_WIDTH) while(ch &&cnt<LCD_WIDTH)
{ {
*target=ch; *target=ch;
target++; target++;
cnt++; cnt++;
ch=pgm_read_byte(++message); ch=pgm_read_byte(++message);
} }
*target=0; *target=0;
} }
FORCE_INLINE void clear() FORCE_INLINE void clear()
{ {
lcd.clear(); lcd.clear();
} }
void lcd_init() void lcd_init()
{ {
//beep(); //beep();
byte Degree[8] = byte Degree[8] =
{ {
B01100, B01100,
B10010, B10010,
B10010, B10010,
B01100, B01100,
B00000, B00000,
B00000, B00000,
B00000, B00000,
B00000 B00000
}; };
byte Thermometer[8] = byte Thermometer[8] =
{ {
B00100, B00100,
B01010, B01010,
B01010, B01010,
B01010, B01010,
B01010, B01010,
B10001, B10001,
B10001, B10001,
B01110 B01110
}; };
byte uplevel[8]={0x04, 0x0e, 0x1f, 0x04, 0x1c, 0x00, 0x00, 0x00};//thanks joris byte uplevel[8]={0x04, 0x0e, 0x1f, 0x04, 0x1c, 0x00, 0x00, 0x00};//thanks joris
byte refresh[8]={0x00, 0x06, 0x19, 0x18, 0x03, 0x13, 0x0c, 0x00}; //thanks joris byte refresh[8]={0x00, 0x06, 0x19, 0x18, 0x03, 0x13, 0x0c, 0x00}; //thanks joris
byte folder [8]={0x00, 0x1c, 0x1f, 0x11, 0x11, 0x1f, 0x00, 0x00}; //thanks joris byte folder [8]={0x00, 0x1c, 0x1f, 0x11, 0x11, 0x1f, 0x00, 0x00}; //thanks joris
lcd.begin(LCD_WIDTH, LCD_HEIGHT); lcd.begin(LCD_WIDTH, LCD_HEIGHT);
lcd.createChar(1,Degree); lcd.createChar(1,Degree);
lcd.createChar(2,Thermometer); lcd.createChar(2,Thermometer);
lcd.createChar(3,uplevel); lcd.createChar(3,uplevel);
lcd.createChar(4,refresh); lcd.createChar(4,refresh);
lcd.createChar(5,folder); lcd.createChar(5,folder);
LCD_MESSAGEPGM("UltiMarlin ready."); LCD_MESSAGEPGM("UltiMarlin ready.");
} }
void beep() void beep()
{ {
//return; //return;
#ifdef ULTIPANEL #ifdef ULTIPANEL
pinMode(BEEPER,OUTPUT); pinMode(BEEPER,OUTPUT);
for(int8_t i=0;i<20;i++){ for(int8_t i=0;i<20;i++){
WRITE(BEEPER,HIGH); WRITE(BEEPER,HIGH);
delay(5); delay(5);
WRITE(BEEPER,LOW); WRITE(BEEPER,LOW);
delay(5); delay(5);
} }
#endif #endif
} }
void beepshort() void beepshort()
{ {
//return; //return;
#ifdef ULTIPANEL #ifdef ULTIPANEL
pinMode(BEEPER,OUTPUT); pinMode(BEEPER,OUTPUT);
for(int8_t i=0;i<10;i++){ for(int8_t i=0;i<10;i++){
WRITE(BEEPER,HIGH); WRITE(BEEPER,HIGH);
delay(3); delay(3);
WRITE(BEEPER,LOW); WRITE(BEEPER,LOW);
delay(3); delay(3);
} }
#endif #endif
} }
void lcd_status() void lcd_status()
{ {
#ifdef ULTIPANEL #ifdef ULTIPANEL
static uint8_t oldbuttons=0; static uint8_t oldbuttons=0;
//static long previous_millis_buttons=0; //static long previous_millis_buttons=0;
//static long previous_lcdinit=0; //static long previous_lcdinit=0;
// buttons_check(); // Done in temperature interrupt // buttons_check(); // Done in temperature interrupt
//previous_millis_buttons=millis(); //previous_millis_buttons=millis();
long ms=millis();
if((buttons==oldbuttons) && ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) ) for(int8_t i=0; i<8; i++) {
return; if((blocking[i]>ms))
oldbuttons=buttons; buttons &= ~(1<<i);
#else }
if((buttons==oldbuttons) && ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) ) return;
return; oldbuttons=buttons;
#endif #else
previous_millis_lcd=millis(); if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL) )
menu.update(); return;
} #endif
#ifdef ULTIPANEL
previous_millis_lcd=millis();
menu.update();
void buttons_init() }
{ #ifdef ULTIPANEL
#ifdef NEWPANEL
pinMode(BTN_EN1,INPUT);
pinMode(BTN_EN2,INPUT); void buttons_init()
pinMode(BTN_ENC,INPUT); {
pinMode(SDCARDDETECT,INPUT); #ifdef NEWPANEL
WRITE(BTN_EN1,HIGH); pinMode(BTN_EN1,INPUT);
WRITE(BTN_EN2,HIGH); pinMode(BTN_EN2,INPUT);
WRITE(BTN_ENC,HIGH); pinMode(BTN_ENC,INPUT);
WRITE(SDCARDDETECT,HIGH); pinMode(SDCARDDETECT,INPUT);
#else WRITE(BTN_EN1,HIGH);
pinMode(SHIFT_CLK,OUTPUT); WRITE(BTN_EN2,HIGH);
pinMode(SHIFT_LD,OUTPUT); WRITE(BTN_ENC,HIGH);
pinMode(SHIFT_EN,OUTPUT); WRITE(SDCARDDETECT,HIGH);
pinMode(SHIFT_OUT,INPUT); #else
WRITE(SHIFT_OUT,HIGH); pinMode(SHIFT_CLK,OUTPUT);
WRITE(SHIFT_LD,HIGH); pinMode(SHIFT_LD,OUTPUT);
WRITE(SHIFT_EN,LOW); pinMode(SHIFT_EN,OUTPUT);
#endif pinMode(SHIFT_OUT,INPUT);
} WRITE(SHIFT_OUT,HIGH);
WRITE(SHIFT_LD,HIGH);
WRITE(SHIFT_EN,LOW);
void buttons_check() #endif
{ }
#ifdef NEWPANEL
uint8_t newbutton=0; void buttons_check()
if(READ(BTN_EN1)==0) newbutton|=EN_A; {
if(READ(BTN_EN2)==0) newbutton|=EN_B;
if((blocking<millis()) &&(READ(BTN_ENC)==0)) #ifdef NEWPANEL
newbutton|=EN_C; uint8_t newbutton=0;
buttons=newbutton; if(READ(BTN_EN1)==0) newbutton|=EN_A;
#else //read it from the shift register if(READ(BTN_EN2)==0) newbutton|=EN_B;
uint8_t newbutton=0; if((blocking<millis()) &&(READ(BTN_ENC)==0))
WRITE(SHIFT_LD,LOW); newbutton|=EN_C;
WRITE(SHIFT_LD,HIGH); buttons=newbutton;
unsigned char tmp_buttons=0; #else //read it from the shift register
for(int8_t i=0;i<8;i++) uint8_t newbutton=0;
{ WRITE(SHIFT_LD,LOW);
newbutton = newbutton>>1; WRITE(SHIFT_LD,HIGH);
if(READ(SHIFT_OUT)) unsigned char tmp_buttons=0;
newbutton|=(1<<7); for(int8_t i=0;i<8;i++)
WRITE(SHIFT_CLK,HIGH); {
WRITE(SHIFT_CLK,LOW); newbutton = newbutton>>1;
} if(READ(SHIFT_OUT))
buttons=~newbutton; //invert it, because a pressed switch produces a logical 0 newbutton|=(1<<7);
#endif WRITE(SHIFT_CLK,HIGH);
WRITE(SHIFT_CLK,LOW);
//manage encoder rotation }
char enc=0; buttons=~newbutton; //invert it, because a pressed switch produces a logical 0
if(buttons&EN_A) #endif
enc|=(1<<0);
if(buttons&EN_B) //manage encoder rotation
enc|=(1<<1); char enc=0;
if(enc!=lastenc) if(buttons&EN_A)
{ enc|=(1<<0);
switch(enc) if(buttons&EN_B)
{ enc|=(1<<1);
case encrot0: if(enc!=lastenc)
if(lastenc==encrot3) {
encoderpos++; switch(enc)
else if(lastenc==encrot1) {
encoderpos--; case encrot0:
break; if(lastenc==encrot3)
case encrot1: encoderpos++;
if(lastenc==encrot0) else if(lastenc==encrot1)
encoderpos++; encoderpos--;
else if(lastenc==encrot2) break;
encoderpos--; case encrot1:
break; if(lastenc==encrot0)
case encrot2: encoderpos++;
if(lastenc==encrot1) else if(lastenc==encrot2)
encoderpos++; encoderpos--;
else if(lastenc==encrot3) break;
encoderpos--; case encrot2:
break; if(lastenc==encrot1)
case encrot3: encoderpos++;
if(lastenc==encrot2) else if(lastenc==encrot3)
encoderpos++; encoderpos--;
else if(lastenc==encrot0) break;
encoderpos--; case encrot3:
break; if(lastenc==encrot2)
default: encoderpos++;
; else if(lastenc==encrot0)
} encoderpos--;
} break;
lastenc=enc; default:
} ;
}
#endif }
lastenc=enc;
MainMenu::MainMenu() }
{
status=Main_Status; #endif
displayStartingRow=0;
activeline=0; MainMenu::MainMenu()
force_lcd_update=true; {
#ifdef ULTIPANEL status=Main_Status;
buttons_init(); displayStartingRow=0;
#endif activeline=0;
lcd_init(); force_lcd_update=true;
linechanging=false; #ifdef ULTIPANEL
tune=false; buttons_init();
} #endif
lcd_init();
void MainMenu::showStatus() linechanging=false;
{ tune=false;
#if LCD_HEIGHT==4 }
static int olddegHotEnd0=-1;
static int oldtargetHotEnd0=-1; void MainMenu::showStatus()
//force_lcd_update=true; {
if(force_lcd_update||feedmultiplychanged) //initial display of content #if LCD_HEIGHT==4
{ static int olddegHotEnd0=-1;
feedmultiplychanged=false; static int oldtargetHotEnd0=-1;
encoderpos=feedmultiply; //force_lcd_update=true;
clear(); if(force_lcd_update||feedmultiplychanged) //initial display of content
lcd.setCursor(0,0);lcdprintPGM("\002123/567\001 "); {
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595 feedmultiplychanged=false;
lcd.setCursor(10,0);lcdprintPGM("B123/567\001 "); encoderpos=feedmultiply;
#endif clear();
} lcd.setCursor(0,0);lcdprintPGM("\002123/567\001 ");
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
int tHotEnd0=intround(degHotend0()); lcd.setCursor(10,0);lcdprintPGM("B123/567\001 ");
if((abs(tHotEnd0-olddegHotEnd0)>1)||force_lcd_update) //>1 because otherwise the lcd is refreshed to often. #endif
{ }
lcd.setCursor(1,0);
lcd.print(ftostr3(tHotEnd0)); int tHotEnd0=intround(degHotend0());
olddegHotEnd0=tHotEnd0; if((abs(tHotEnd0-olddegHotEnd0)>1)||force_lcd_update) //>1 because otherwise the lcd is refreshed to often.
} {
int ttHotEnd0=intround(degTargetHotend0()); lcd.setCursor(1,0);
if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update) lcd.print(ftostr3(tHotEnd0));
{ olddegHotEnd0=tHotEnd0;
lcd.setCursor(5,0); }
lcd.print(ftostr3(ttHotEnd0)); int ttHotEnd0=intround(degTargetHotend0());
oldtargetHotEnd0=ttHotEnd0; if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update)
} {
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595 lcd.setCursor(5,0);
static int oldtBed=-1; lcd.print(ftostr3(ttHotEnd0));
static int oldtargetBed=-1; oldtargetHotEnd0=ttHotEnd0;
int tBed=intround(degBed()); }
if((tBed!=oldtBed)||force_lcd_update) #if defined BED_USES_THERMISTOR || defined BED_USES_AD595
{ static int oldtBed=-1;
lcd.setCursor(1,0); static int oldtargetBed=-1;
lcd.print(ftostr3(tBed)); int tBed=intround(degBed());
oldtBed=tBed; if((tBed!=oldtBed)||force_lcd_update)
} {
int targetBed=intround(degTargetBed()); lcd.setCursor(1,0);
if((targetBed!=oldtargetBed)||force_lcd_update) lcd.print(ftostr3(tBed));
{ oldtBed=tBed;
lcd.setCursor(5,0); }
lcd.print(ftostr3(targetBed)); int targetBed=intround(degTargetBed());
oldtargetBed=targetBed; if((targetBed!=oldtargetBed)||force_lcd_update)
} {
#endif lcd.setCursor(5,0);
//starttime=2; lcd.print(ftostr3(targetBed));
static uint16_t oldtime=0; oldtargetBed=targetBed;
if(starttime!=0) }
{ #endif
lcd.setCursor(0,1); //starttime=2;
uint16_t time=millis()/60000-starttime/60000; static uint16_t oldtime=0;
if(starttime!=0)
if(starttime!=oldtime) {
{ lcd.setCursor(0,1);
lcd.print(itostr2(time/60));lcdprintPGM("h ");lcd.print(itostr2(time%60));lcdprintPGM("m"); uint16_t time=millis()/60000-starttime/60000;
oldtime=time;
} if(starttime!=oldtime)
} {
static int oldzpos=0; lcd.print(itostr2(time/60));lcdprintPGM("h ");lcd.print(itostr2(time%60));lcdprintPGM("m");
int currentz=current_position[2]*10; oldtime=time;
if((currentz!=oldzpos)||force_lcd_update) }
{ }
lcd.setCursor(10,1); static int oldzpos=0;
lcdprintPGM("Z:");lcd.print(itostr31(currentz)); int currentz=current_position[2]*10;
oldzpos=currentz; if((currentz!=oldzpos)||force_lcd_update)
} {
static int oldfeedmultiply=0; lcd.setCursor(10,1);
int curfeedmultiply=feedmultiply; lcdprintPGM("Z:");lcd.print(itostr31(currentz));
if(encoderpos!=curfeedmultiply||force_lcd_update) oldzpos=currentz;
{ }
curfeedmultiply=encoderpos; static int oldfeedmultiply=0;
if(curfeedmultiply<10) int curfeedmultiply=feedmultiply;
curfeedmultiply=10; if(encoderpos!=curfeedmultiply||force_lcd_update)
if(curfeedmultiply>999) {
curfeedmultiply=999; curfeedmultiply=encoderpos;
feedmultiply=curfeedmultiply; if(curfeedmultiply<10)
encoderpos=curfeedmultiply; curfeedmultiply=10;
} if(curfeedmultiply>999)
if((curfeedmultiply!=oldfeedmultiply)||force_lcd_update) curfeedmultiply=999;
{ feedmultiply=curfeedmultiply;
oldfeedmultiply=curfeedmultiply; encoderpos=curfeedmultiply;
lcd.setCursor(0,2); }
lcd.print(itostr3(curfeedmultiply));lcdprintPGM("% "); if((curfeedmultiply!=oldfeedmultiply)||force_lcd_update)
} {
if(messagetext[0]!='\0') oldfeedmultiply=curfeedmultiply;
{ lcd.setCursor(0,2);
lcd.setCursor(0,LCD_HEIGHT-1); lcd.print(itostr3(curfeedmultiply));lcdprintPGM("% ");
lcd.print(messagetext); }
uint8_t n=strlen(messagetext); if(messagetext[0]!='\0')
for(int8_t i=0;i<LCD_WIDTH-n;i++) {
lcd.print(" "); lcd.setCursor(0,LCD_HEIGHT-1);
lcd.print(messagetext);
messagetext[0]='\0'; uint8_t n=strlen(messagetext);
} for(int8_t i=0;i<LCD_WIDTH-n;i++)
lcd.print(" ");
static uint8_t oldpercent=101;
uint8_t percent=card.percentDone(); messagetext[0]='\0';
if(oldpercent!=percent ||force_lcd_update) }
{
lcd.setCursor(7,2); static uint8_t oldpercent=101;
lcd.print(itostr3((int)percent)); uint8_t percent=card.percentDone();
lcdprintPGM("%SD"); if(oldpercent!=percent ||force_lcd_update)
{
} lcd.setCursor(7,2);
lcd.print(itostr3((int)percent));
#else //smaller LCDS---------------------------------- lcdprintPGM("%SD");
static int olddegHotEnd0=-1;
static int oldtargetHotEnd0=-1; }
if(force_lcd_update) //initial display of content
{ #else //smaller LCDS----------------------------------
encoderpos=feedmultiply; static int olddegHotEnd0=-1;
lcd.setCursor(0,0);lcdprintPGM("\002123/567\001 "); static int oldtargetHotEnd0=-1;
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595 if(force_lcd_update) //initial display of content
lcd.setCursor(10,0);lcdprintPGM("B123/567\001 "); {
#endif encoderpos=feedmultiply;
} lcd.setCursor(0,0);lcdprintPGM("\002123/567\001 ");
#if defined BED_USES_THERMISTOR || defined BED_USES_AD595
int tHotEnd0=intround(degHotend0()); lcd.setCursor(10,0);lcdprintPGM("B123/567\001 ");
int ttHotEnd0=intround(degTargetHotend0()); #endif
}
if((abs(tHotEnd0-olddegHotEnd0)>1)||force_lcd_update) int tHotEnd0=intround(degHotend0());
{ int ttHotEnd0=intround(degTargetHotend0());
lcd.setCursor(1,0);
lcd.print(ftostr3(tHotEnd0));
olddegHotEnd0=tHotEnd0; if((abs(tHotEnd0-olddegHotEnd0)>1)||force_lcd_update)
} {
if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update) lcd.setCursor(1,0);
{ lcd.print(ftostr3(tHotEnd0));
lcd.setCursor(5,0); olddegHotEnd0=tHotEnd0;
lcd.print(ftostr3(ttHotEnd0)); }
oldtargetHotEnd0=ttHotEnd0; if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update)
} {
lcd.setCursor(5,0);
if(messagetext[0]!='\0') lcd.print(ftostr3(ttHotEnd0));
{ oldtargetHotEnd0=ttHotEnd0;
lcd.setCursor(0,LCD_HEIGHT-1); }
lcd.print(messagetext);
uint8_t n=strlen(messagetext); if(messagetext[0]!='\0')
for(int8_t i=0;i<LCD_WIDTH-n;i++) {
lcd.print(" "); lcd.setCursor(0,LCD_HEIGHT-1);
messagetext[0]='\0'; lcd.print(messagetext);
} uint8_t n=strlen(messagetext);
for(int8_t i=0;i<LCD_WIDTH-n;i++)
#endif lcd.print(" ");
force_lcd_update=false; messagetext[0]='\0';
} }
enum {ItemP_exit, ItemP_autostart,ItemP_disstep,ItemP_home, ItemP_origin, ItemP_preheat, ItemP_extrude}; #endif
force_lcd_update=false;
//any action must not contain a ',' character anywhere, or this breaks: }
#define MENUITEM(repaint_action, click_action) \
{\ enum {ItemP_exit, ItemP_autostart,ItemP_disstep,ItemP_home, ItemP_origin, ItemP_preheat, ItemP_extrude};
if(force_lcd_update) { lcd.setCursor(0,line); repaint_action; } \
if((activeline==line) && CLICKED) {click_action} \ //any action must not contain a ',' character anywhere, or this breaks:
} #define MENUITEM(repaint_action, click_action) \
{\
void MainMenu::showPrepare() if(force_lcd_update) { lcd.setCursor(0,line); repaint_action; } \
{ if((activeline==line) && CLICKED) {click_action} \
uint8_t line=0; }
clearIfNecessary();
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++) void MainMenu::showPrepare()
{ {
//Serial.println((int)(line-lineoffset)); uint8_t line=0;
switch(i) clearIfNecessary();
{ for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
case ItemP_exit: {
MENUITEM( lcdprintPGM(" Main \003") , BLOCK;status=Main_Menu;beepshort(); ) ; //Serial.println((int)(line-lineoffset));
break; switch(i)
case ItemP_autostart: {
MENUITEM( lcdprintPGM(" Autostart") , BLOCK;card.lastnr=0;card.checkautostart(true);beepshort(); ) ; case ItemP_exit:
break; MENUITEM( lcdprintPGM(" Main \003") , BLOCK;status=Main_Menu;beepshort(); ) ;
case ItemP_disstep: break;
MENUITEM( lcdprintPGM(" Disable Steppers") , BLOCK;enquecommand("M84");beepshort(); ) ; case ItemP_autostart:
break; MENUITEM( lcdprintPGM(" Autostart") , BLOCK;card.lastnr=0;card.checkautostart(true);beepshort(); ) ;
case ItemP_home: break;
MENUITEM( lcdprintPGM(" Auto Home") , BLOCK;enquecommand("G28 X-105 Y-105 Z0");beepshort(); ) ; case ItemP_disstep:
break; MENUITEM( lcdprintPGM(" Disable Steppers") , BLOCK;enquecommand("M84");beepshort(); ) ;
case ItemP_origin: break;
MENUITEM( lcdprintPGM(" Set Origin") , BLOCK;enquecommand("G92 X0 Y0 Z0");beepshort(); ) ; case ItemP_home:
break; MENUITEM( lcdprintPGM(" Auto Home") , BLOCK;enquecommand("G28 X-105 Y-105 Z0");beepshort(); ) ;
case ItemP_preheat: break;
MENUITEM( lcdprintPGM(" Preheat") , BLOCK;setTargetHotend0(170);beepshort(); ) ; case ItemP_origin:
break; MENUITEM( lcdprintPGM(" Set Origin") , BLOCK;enquecommand("G92 X0 Y0 Z0");beepshort(); ) ;
case ItemP_extrude: break;
MENUITEM( lcdprintPGM(" Extrude") , BLOCK;enquecommand("G92 E0");enquecommand("G1 F700 E50");beepshort(); ) ; case ItemP_preheat:
break; MENUITEM( lcdprintPGM(" Preheat") , BLOCK;setTargetHotend0(170);beepshort(); ) ;
break;
case ItemP_extrude:
default: MENUITEM( lcdprintPGM(" Extrude") , BLOCK;enquecommand("G92 E0");enquecommand("G1 F700 E50");beepshort(); ) ;
break; break;
}
line++;
} default:
updateActiveLines(ItemP_extrude,encoderpos); break;
} }
line++;
enum {ItemT_exit,ItemT_speed,ItemT_flow,ItemT_nozzle,ItemT_fan}; }
updateActiveLines(ItemP_extrude,encoderpos);
void MainMenu::showTune() }
{
uint8_t line=0; enum {ItemT_exit,ItemT_speed,ItemT_flow,ItemT_nozzle,ItemT_fan};
clearIfNecessary();
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++) void MainMenu::showTune()
{ {
//Serial.println((int)(line-lineoffset)); uint8_t line=0;
switch(i) clearIfNecessary();
{ for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
case ItemT_exit: {
MENUITEM( lcdprintPGM(" Main \003") , BLOCK;status=Main_Menu;beepshort(); ) ; //Serial.println((int)(line-lineoffset));
break; switch(i)
case ItemT_speed: {
{ case ItemT_exit:
if(force_lcd_update) MENUITEM( lcdprintPGM(" Main \003") , BLOCK;status=Main_Menu;beepshort(); ) ;
{ break;
lcd.setCursor(0,line);lcdprintPGM(" Speed:"); case ItemT_speed:
lcd.setCursor(13,line);lcd.print(ftostr3(feedmultiply)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" Speed:");
break; lcd.setCursor(13,line);lcd.print(ftostr3(feedmultiply));
}
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
encoderpos=feedmultiply; {
} linechanging=!linechanging;
else if(linechanging)
{ {
encoderpos=activeline*lcdslow; encoderpos=feedmultiply;
beepshort(); }
} else
BLOCK; {
} encoderpos=activeline*lcdslow;
if(linechanging) beepshort();
{ }
if(encoderpos<1) encoderpos=1; BLOCK;
if(encoderpos>400) encoderpos=400; }
feedmultiply = encoderpos; if(linechanging)
feedmultiplychanged=true; {
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(encoderpos<1) encoderpos=1;
} if(encoderpos>400) encoderpos=400;
feedmultiply = encoderpos;
}break; feedmultiplychanged=true;
case ItemT_nozzle: lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" \002Nozzle:"); case ItemT_nozzle:
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0()))); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" \002Nozzle:");
break; lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=intround(degTargetHotend0()); {
} linechanging=!linechanging;
else if(linechanging)
{ {
setTargetHotend0(encoderpos); encoderpos=intround(degTargetHotend0());
encoderpos=activeline*lcdslow; }
beepshort(); else
} {
BLOCK; setTargetHotend0(encoderpos);
} encoderpos=activeline*lcdslow;
if(linechanging) beepshort();
{ }
if(encoderpos<0) encoderpos=0; BLOCK;
if(encoderpos>260) encoderpos=260; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(linechanging)
} {
}break; if(encoderpos<0) encoderpos=0;
if(encoderpos>260) encoderpos=260;
case ItemT_fan: lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
{ }
if(force_lcd_update) }break;
{
lcd.setCursor(0,line);lcdprintPGM(" Fan speed:"); case ItemT_fan:
lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" Fan speed:");
break; lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
}
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
encoderpos=fanpwm; {
} linechanging=!linechanging;
else if(linechanging)
{ {
encoderpos=activeline*lcdslow; encoderpos=fanpwm;
beepshort(); }
} else
BLOCK; {
} encoderpos=activeline*lcdslow;
if(linechanging) beepshort();
{ }
if(encoderpos<0) encoderpos=0; BLOCK;
if(encoderpos>255) encoderpos=255; }
fanpwm=encoderpos; if(linechanging)
analogWrite(FAN_PIN, fanpwm); {
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(encoderpos<0) encoderpos=0;
} if(encoderpos>255) encoderpos=255;
fanpwm=encoderpos;
}break; analogWrite(FAN_PIN, fanpwm);
case ItemT_flow://axis_steps_per_unit[i] = code_value(); lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" Flow:"); case ItemT_flow://axis_steps_per_unit[i] = code_value();
lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3])); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" Flow:");
break; lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)axis_steps_per_unit[3]; {
} linechanging=!linechanging;
else if(linechanging)
{ {
float factor=float(encoderpos)/float(axis_steps_per_unit[3]); encoderpos=(int)axis_steps_per_unit[3];
position[E_AXIS]=lround(position[E_AXIS]*factor); }
//current_position[3]*=factor; else
axis_steps_per_unit[E_AXIS]= encoderpos; {
encoderpos=activeline*lcdslow; float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
position[E_AXIS]=lround(position[E_AXIS]*factor);
} //current_position[3]*=factor;
BLOCK; axis_steps_per_unit[E_AXIS]= encoderpos;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<5) encoderpos=5; beepshort();
if(encoderpos>9999) encoderpos=9999; }
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos)); if(linechanging)
} {
if(encoderpos<5) encoderpos=5;
}break; if(encoderpos>9999) encoderpos=9999;
default: lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
break; }
}
line++; }break;
} default:
updateActiveLines(ItemT_fan,encoderpos); break;
} }
line++;
//does not work }
// #define MENUCHANGEITEM(repaint_action, enter_action, accept_action, change_action) \ updateActiveLines(ItemT_fan,encoderpos);
// {\ }
// if(force_lcd_update) { lcd.setCursor(0,line); repaint_action; } \
// if(activeline==line) \ //does not work
// { \ // #define MENUCHANGEITEM(repaint_action, enter_action, accept_action, change_action) \
// if(CLICKED) \ // {\
// { \ // if(force_lcd_update) { lcd.setCursor(0,line); repaint_action; } \
// linechanging=!linechanging; \ // if(activeline==line) \
// if(linechanging) {enter_action;} \ // { \
// else {accept_action;} \ // if(CLICKED) \
// } \ // { \
// else \ // linechanging=!linechanging; \
// if(linechanging) {change_action};}\ // if(linechanging) {enter_action;} \
// } // else {accept_action;} \
// // } \
// else \
enum { // if(linechanging) {change_action};}\
ItemCT_exit,ItemCT_nozzle, // }
#ifdef AUTOTEMP //
ItemCT_autotempactive,
ItemCT_autotempmin,ItemCT_autotempmax,ItemCT_autotempfact, enum {
#endif ItemCT_exit,ItemCT_nozzle,
ItemCT_fan, #ifdef AUTOTEMP
ItemCT_PID_P,ItemCT_PID_I,ItemCT_PID_D,ItemCT_PID_C ItemCT_autotempactive,
}; ItemCT_autotempmin,ItemCT_autotempmax,ItemCT_autotempfact,
#endif
void MainMenu::showControlTemp() ItemCT_fan,
{ ItemCT_PID_P,ItemCT_PID_I,ItemCT_PID_D,ItemCT_PID_C
uint8_t line=0; };
clearIfNecessary();
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++) void MainMenu::showControlTemp()
{ {
switch(i) uint8_t line=0;
{ clearIfNecessary();
case ItemCT_exit: for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
MENUITEM( lcdprintPGM(" Control \003") , BLOCK;status=Main_Control;beepshort(); ) ; {
break; switch(i)
case ItemCT_nozzle: {
{ case ItemCT_exit:
if(force_lcd_update) MENUITEM( lcdprintPGM(" Control \003") , BLOCK;status=Main_Control;beepshort(); ) ;
{ break;
lcd.setCursor(0,line);lcdprintPGM(" \002Nozzle:"); case ItemCT_nozzle:
lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0()))); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" \002Nozzle:");
break; lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=intround(degTargetHotend0()); {
} linechanging=!linechanging;
else if(linechanging)
{ {
setTargetHotend0(encoderpos); encoderpos=intround(degTargetHotend0());
encoderpos=activeline*lcdslow; }
beepshort(); else
} {
BLOCK; setTargetHotend0(encoderpos);
} encoderpos=activeline*lcdslow;
if(linechanging) beepshort();
{ }
if(encoderpos<0) encoderpos=0; BLOCK;
if(encoderpos>260) encoderpos=260; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(linechanging)
} {
if(encoderpos<0) encoderpos=0;
}break; if(encoderpos>260) encoderpos=260;
#ifdef AUTOTEMP lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
case ItemCT_autotempmin: }
{
if(force_lcd_update) }break;
{ #ifdef AUTOTEMP
lcd.setCursor(0,line);lcdprintPGM(" \002 Min:"); case ItemCT_autotempmin:
lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_min)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" \002 Min:");
break; lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_min));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=intround(autotemp_min); {
} linechanging=!linechanging;
else if(linechanging)
{ {
autotemp_min=encoderpos; encoderpos=intround(autotemp_min);
encoderpos=activeline*lcdslow; }
beepshort(); else
} {
BLOCK; autotemp_min=encoderpos;
} encoderpos=activeline*lcdslow;
if(linechanging) beepshort();
{ }
if(encoderpos<0) encoderpos=0; BLOCK;
if(encoderpos>260) encoderpos=260; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(linechanging)
} {
if(encoderpos<0) encoderpos=0;
}break; if(encoderpos>260) encoderpos=260;
case ItemCT_autotempmax: lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" \002 Max:"); case ItemCT_autotempmax:
lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_max)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" \002 Max:");
break; lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_max));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=intround(autotemp_max); {
} linechanging=!linechanging;
else if(linechanging)
{ {
autotemp_max=encoderpos; encoderpos=intround(autotemp_max);
encoderpos=activeline*lcdslow; }
beepshort(); else
} {
BLOCK; autotemp_max=encoderpos;
} encoderpos=activeline*lcdslow;
if(linechanging) beepshort();
{ }
if(encoderpos<0) encoderpos=0; BLOCK;
if(encoderpos>260) encoderpos=260; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(linechanging)
} {
if(encoderpos<0) encoderpos=0;
}break; if(encoderpos>260) encoderpos=260;
case ItemCT_autotempfact: lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" \002 Fact:"); case ItemCT_autotempfact:
lcd.setCursor(13,line);lcd.print(ftostr32(autotemp_factor)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" \002 Fact:");
break; lcd.setCursor(13,line);lcd.print(ftostr32(autotemp_factor));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=intround(autotemp_factor*100); {
} linechanging=!linechanging;
else if(linechanging)
{ {
autotemp_max=encoderpos; encoderpos=intround(autotemp_factor*100);
encoderpos=activeline*lcdslow; }
beepshort(); else
} {
BLOCK; autotemp_max=encoderpos;
} encoderpos=activeline*lcdslow;
if(linechanging) beepshort();
{ }
if(encoderpos<0) encoderpos=0; BLOCK;
if(encoderpos>99) encoderpos=99; }
lcd.setCursor(13,line);lcd.print(ftostr32(encoderpos/100.)); if(linechanging)
} {
if(encoderpos<0) encoderpos=0;
}break; if(encoderpos>99) encoderpos=99;
case ItemCT_autotempactive: lcd.setCursor(13,line);lcd.print(ftostr32(encoderpos/100.));
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" Autotemp:"); case ItemCT_autotempactive:
lcd.setCursor(13,line); {
if(autotemp_enabled) if(force_lcd_update)
lcdprintPGM("On"); {
else lcd.setCursor(0,line);lcdprintPGM(" Autotemp:");
lcdprintPGM("Off"); lcd.setCursor(13,line);
} if(autotemp_enabled)
lcdprintPGM("On");
if((activeline!=line) ) else
break; lcdprintPGM("Off");
}
if(CLICKED)
{ if((activeline!=line) )
autotemp_enabled=!autotemp_enabled; break;
lcd.setCursor(13,line);
if(autotemp_enabled) if(CLICKED)
lcdprintPGM("On "); {
else autotemp_enabled=!autotemp_enabled;
lcdprintPGM("Off"); lcd.setCursor(13,line);
BLOCK; if(autotemp_enabled)
} lcdprintPGM("On ");
else
}break; lcdprintPGM("Off");
#endif //autotemp BLOCK;
case ItemCT_fan: }
{
if(force_lcd_update) }break;
{ #endif //autotemp
lcd.setCursor(0,line);lcdprintPGM(" Fan speed:"); case ItemCT_fan:
lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" Fan speed:");
break; lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
}
if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED) //nalogWrite(FAN_PIN, fanpwm);
encoderpos=fanpwm; {
} linechanging=!linechanging;
else if(linechanging)
{ {
encoderpos=activeline*lcdslow; encoderpos=fanpwm;
beepshort(); }
} else
BLOCK; {
} encoderpos=activeline*lcdslow;
if(linechanging) beepshort();
{ }
if(encoderpos<0) encoderpos=0; BLOCK;
if(encoderpos>255) encoderpos=255; }
fanpwm=encoderpos; if(linechanging)
analogWrite(FAN_PIN, fanpwm); {
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(encoderpos<0) encoderpos=0;
} if(encoderpos>255) encoderpos=255;
fanpwm=encoderpos;
}break; analogWrite(FAN_PIN, fanpwm);
case ItemCT_PID_P: lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" PID-P: "); case ItemCT_PID_P:
lcd.setCursor(13,line);lcd.print(itostr4(Kp)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" PID-P: ");
break; lcd.setCursor(13,line);lcd.print(itostr4(Kp));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)Kp; {
} linechanging=!linechanging;
else if(linechanging)
{ {
Kp= encoderpos; encoderpos=(int)Kp;
encoderpos=activeline*lcdslow; }
else
} {
BLOCK; Kp= encoderpos;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<1) encoderpos=1; beepshort();
if(encoderpos>9990) encoderpos=9990; }
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos)); if(linechanging)
} {
if(encoderpos<1) encoderpos=1;
}break; if(encoderpos>9990) encoderpos=9990;
case ItemCT_PID_I: lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" PID-I: "); case ItemCT_PID_I:
lcd.setCursor(13,line);lcd.print(ftostr51(Ki/PID_dT)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" PID-I: ");
break; lcd.setCursor(13,line);lcd.print(ftostr51(Ki/PID_dT));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)(Ki*10/PID_dT); {
} linechanging=!linechanging;
else if(linechanging)
{ {
Ki= encoderpos/10.*PID_dT; encoderpos=(int)(Ki*10/PID_dT);
encoderpos=activeline*lcdslow; }
else
} {
BLOCK; Ki= encoderpos/10.*PID_dT;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<0) encoderpos=0; beepshort();
if(encoderpos>9990) encoderpos=9990; }
lcd.setCursor(13,line);lcd.print(ftostr51(encoderpos/10.)); if(linechanging)
} {
if(encoderpos<0) encoderpos=0;
}break; if(encoderpos>9990) encoderpos=9990;
case ItemCT_PID_D: lcd.setCursor(13,line);lcd.print(ftostr51(encoderpos/10.));
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" PID-D: "); case ItemCT_PID_D:
lcd.setCursor(13,line);lcd.print(itostr4(Kd*PID_dT)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" PID-D: ");
break; lcd.setCursor(13,line);lcd.print(itostr4(Kd*PID_dT));
}
if(CLICKED) if((activeline!=line) )
{ break;
linechanging=!linechanging;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)(Kd/5./PID_dT); {
} linechanging=!linechanging;
else if(linechanging)
{ {
Kd= encoderpos; encoderpos=(int)(Kd/5./PID_dT);
encoderpos=activeline*lcdslow; }
else
} {
BLOCK; Kd= encoderpos;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<0) encoderpos=0; beepshort();
if(encoderpos>9990) encoderpos=9990; }
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos)); if(linechanging)
} {
if(encoderpos<0) encoderpos=0;
}break; if(encoderpos>9990) encoderpos=9990;
case ItemCT_PID_C: lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
#ifdef PID_ADD_EXTRUSION_RATE }
{
if(force_lcd_update) }break;
{ case ItemCT_PID_C:
lcd.setCursor(0,line);lcdprintPGM(" PID-C: "); #ifdef PID_ADD_EXTRUSION_RATE
lcd.setCursor(13,line);lcd.print(itostr3(Kc)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" PID-C: ");
break; lcd.setCursor(13,line);lcd.print(itostr3(Kc));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)Kc; {
} linechanging=!linechanging;
else if(linechanging)
{ {
Kc= encoderpos; encoderpos=(int)Kc;
encoderpos=activeline*lcdslow; }
else
} {
BLOCK; Kc= encoderpos;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<0) encoderpos=0; beepshort();
if(encoderpos>990) encoderpos=990; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(linechanging)
} {
if(encoderpos<0) encoderpos=0;
} if(encoderpos>990) encoderpos=990;
#endif lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
break; }
default:
break; }
} #endif
line++; break;
} default:
#ifdef PID_ADD_EXTRUSION_RATE break;
updateActiveLines(ItemCT_PID_C,encoderpos); }
#else line++;
updateActiveLines(ItemCT_PID_D,encoderpos); }
#endif #ifdef PID_ADD_EXTRUSION_RATE
} updateActiveLines(ItemCT_PID_C,encoderpos);
#else
updateActiveLines(ItemCT_PID_D,encoderpos);
enum { #endif
ItemCM_exit, }
ItemCM_acc, ItemCM_xyjerk,
ItemCM_vmaxx, ItemCM_vmaxy, ItemCM_vmaxz, ItemCM_vmaxe,
ItemCM_vtravmin,ItemCM_vmin, enum {
ItemCM_amaxx, ItemCM_amaxy, ItemCM_amaxz, ItemCM_amaxe, ItemCM_exit,
ItemCM_aret,ItemCM_esteps ItemCM_acc, ItemCM_xyjerk,
}; ItemCM_vmaxx, ItemCM_vmaxy, ItemCM_vmaxz, ItemCM_vmaxe,
ItemCM_vtravmin,ItemCM_vmin,
ItemCM_amaxx, ItemCM_amaxy, ItemCM_amaxz, ItemCM_amaxe,
ItemCM_aret,ItemCM_esteps
void MainMenu::showControlMotion() };
{
uint8_t line=0;
clearIfNecessary();
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++) void MainMenu::showControlMotion()
{ {
switch(i) uint8_t line=0;
{ clearIfNecessary();
case ItemCM_exit: for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
MENUITEM( lcdprintPGM(" Control \003") , BLOCK;status=Main_Control;beepshort(); ) ; {
break; switch(i)
case ItemCM_acc: {
{ case ItemCM_exit:
if(force_lcd_update) MENUITEM( lcdprintPGM(" Control \003") , BLOCK;status=Main_Control;beepshort(); ) ;
{ break;
lcd.setCursor(0,line);lcdprintPGM(" Acc:"); case ItemCM_acc:
lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcdprintPGM("00"); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" Acc:");
break; lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcdprintPGM("00");
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)acceleration/100; {
} linechanging=!linechanging;
else if(linechanging)
{ {
acceleration= encoderpos*100; encoderpos=(int)acceleration/100;
encoderpos=activeline*lcdslow; }
} else
BLOCK; {
beepshort(); acceleration= encoderpos*100;
} encoderpos=activeline*lcdslow;
if(linechanging) }
{ BLOCK;
if(encoderpos<5) encoderpos=5; beepshort();
if(encoderpos>990) encoderpos=990; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00"); if(linechanging)
} {
if(encoderpos<5) encoderpos=5;
}break; if(encoderpos>990) encoderpos=990;
case ItemCM_xyjerk: //max_xy_jerk lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" Vxy-jerk: "); case ItemCM_xyjerk: //max_xy_jerk
lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" Vxy-jerk: ");
break; lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)max_xy_jerk; {
} linechanging=!linechanging;
else if(linechanging)
{ {
max_xy_jerk= encoderpos; encoderpos=(int)max_xy_jerk;
encoderpos=activeline*lcdslow; }
else
} {
BLOCK; max_xy_jerk= encoderpos;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<1) encoderpos=1; beepshort();
if(encoderpos>990) encoderpos=990; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(linechanging)
} {
if(encoderpos<1) encoderpos=1;
}break; if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
case ItemCM_vmaxx: }
case ItemCM_vmaxy:
case ItemCM_vmaxz: }break;
case ItemCM_vmaxe:
{ case ItemCM_vmaxx:
if(force_lcd_update) case ItemCM_vmaxy:
{ case ItemCM_vmaxz:
lcd.setCursor(0,line);lcdprintPGM(" Vmax "); case ItemCM_vmaxe:
if(i==ItemCM_vmaxx)lcdprintPGM("x:"); {
if(i==ItemCM_vmaxy)lcdprintPGM("y:"); if(force_lcd_update)
if(i==ItemCM_vmaxz)lcdprintPGM("z:"); {
if(i==ItemCM_vmaxe)lcdprintPGM("e:"); lcd.setCursor(0,line);lcdprintPGM(" Vmax ");
lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemCM_vmaxx])); if(i==ItemCM_vmaxx)lcdprintPGM("x:");
} if(i==ItemCM_vmaxy)lcdprintPGM("y:");
if(i==ItemCM_vmaxz)lcdprintPGM("z:");
if((activeline!=line) ) if(i==ItemCM_vmaxe)lcdprintPGM("e:");
break; lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemCM_vmaxx]));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)max_feedrate[i-ItemCM_vmaxx]; {
} linechanging=!linechanging;
else if(linechanging)
{ {
max_feedrate[i-ItemCM_vmaxx]= encoderpos; encoderpos=(int)max_feedrate[i-ItemCM_vmaxx];
encoderpos=activeline*lcdslow; }
else
} {
BLOCK; max_feedrate[i-ItemCM_vmaxx]= encoderpos;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<1) encoderpos=1; beepshort();
if(encoderpos>990) encoderpos=990; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(linechanging)
} {
if(encoderpos<1) encoderpos=1;
}break; if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
case ItemCM_vmin: }
{
if(force_lcd_update) }break;
{
lcd.setCursor(0,line);lcdprintPGM(" Vmin:"); case ItemCM_vmin:
lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" Vmin:");
break; lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)(minimumfeedrate); {
} linechanging=!linechanging;
else if(linechanging)
{ {
minimumfeedrate= encoderpos; encoderpos=(int)(minimumfeedrate);
encoderpos=activeline*lcdslow; }
else
} {
BLOCK; minimumfeedrate= encoderpos;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<0) encoderpos=0; beepshort();
if(encoderpos>990) encoderpos=990; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(linechanging)
} {
if(encoderpos<0) encoderpos=0;
}break; if(encoderpos>990) encoderpos=990;
case ItemCM_vtravmin: lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" VTrav min:"); case ItemCM_vtravmin:
lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate)); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" VTrav min:");
break; lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)mintravelfeedrate; {
} linechanging=!linechanging;
else if(linechanging)
{ {
mintravelfeedrate= encoderpos; encoderpos=(int)mintravelfeedrate;
encoderpos=activeline*lcdslow; }
else
} {
BLOCK; mintravelfeedrate= encoderpos;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<0) encoderpos=0; beepshort();
if(encoderpos>990) encoderpos=990; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos)); if(linechanging)
} {
if(encoderpos<0) encoderpos=0;
}break; if(encoderpos>990) encoderpos=990;
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));
case ItemCM_amaxx: }
case ItemCM_amaxy:
case ItemCM_amaxz: }break;
case ItemCM_amaxe:
{ case ItemCM_amaxx:
if(force_lcd_update) case ItemCM_amaxy:
{ case ItemCM_amaxz:
lcd.setCursor(0,line);lcdprintPGM(" Amax "); case ItemCM_amaxe:
if(i==ItemCM_amaxx)lcdprintPGM("x:"); {
if(i==ItemCM_amaxy)lcdprintPGM("y:"); if(force_lcd_update)
if(i==ItemCM_amaxz)lcdprintPGM("z:"); {
if(i==ItemCM_amaxe)lcdprintPGM("e:"); lcd.setCursor(0,line);lcdprintPGM(" Amax ");
lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100));lcdprintPGM("00"); if(i==ItemCM_amaxx)lcdprintPGM("x:");
} if(i==ItemCM_amaxy)lcdprintPGM("y:");
if(i==ItemCM_amaxz)lcdprintPGM("z:");
if((activeline!=line) ) if(i==ItemCM_amaxe)lcdprintPGM("e:");
break; lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100));lcdprintPGM("00");
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100; {
} linechanging=!linechanging;
else if(linechanging)
{ {
max_acceleration_units_per_sq_second[i-ItemCM_amaxx]= encoderpos*100; encoderpos=(int)max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100;
encoderpos=activeline*lcdslow; }
} else
BLOCK; {
beepshort(); max_acceleration_units_per_sq_second[i-ItemCM_amaxx]= encoderpos*100;
} encoderpos=activeline*lcdslow;
if(linechanging) }
{ BLOCK;
if(encoderpos<1) encoderpos=1; beepshort();
if(encoderpos>990) encoderpos=990; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00"); if(linechanging)
} {
if(encoderpos<1) encoderpos=1;
}break; if(encoderpos>990) encoderpos=990;
case ItemCM_aret://float retract_acceleration = 7000; lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" A-retract:"); case ItemCM_aret://float retract_acceleration = 7000;
lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcdprintPGM("00"); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" A-retract:");
break; lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcdprintPGM("00");
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)retract_acceleration/100; {
} linechanging=!linechanging;
else if(linechanging)
{ {
retract_acceleration= encoderpos*100; encoderpos=(int)retract_acceleration/100;
encoderpos=activeline*lcdslow; }
else
} {
BLOCK; retract_acceleration= encoderpos*100;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<10) encoderpos=10; beepshort();
if(encoderpos>990) encoderpos=990; }
lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00"); if(linechanging)
} {
if(encoderpos<10) encoderpos=10;
}break; if(encoderpos>990) encoderpos=990;
case ItemCM_esteps://axis_steps_per_unit[i] = code_value(); lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
{ }
if(force_lcd_update)
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" Esteps/mm:"); case ItemCM_esteps://axis_steps_per_unit[i] = code_value();
lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3])); {
} if(force_lcd_update)
{
if((activeline!=line) ) lcd.setCursor(0,line);lcdprintPGM(" Esteps/mm:");
break; lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
}
if(CLICKED)
{ if((activeline!=line) )
linechanging=!linechanging; break;
if(linechanging)
{ if(CLICKED)
encoderpos=(int)axis_steps_per_unit[3]; {
} linechanging=!linechanging;
else if(linechanging)
{ {
float factor=float(encoderpos)/float(axis_steps_per_unit[3]); encoderpos=(int)axis_steps_per_unit[3];
position[E_AXIS]=lround(position[E_AXIS]*factor); }
//current_position[3]*=factor; else
axis_steps_per_unit[E_AXIS]= encoderpos; {
encoderpos=activeline*lcdslow; float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
position[E_AXIS]=lround(position[E_AXIS]*factor);
} //current_position[3]*=factor;
BLOCK; axis_steps_per_unit[E_AXIS]= encoderpos;
beepshort(); encoderpos=activeline*lcdslow;
}
if(linechanging) }
{ BLOCK;
if(encoderpos<5) encoderpos=5; beepshort();
if(encoderpos>9999) encoderpos=9999; }
lcd.setCursor(13,line);lcd.print(itostr4(encoderpos)); if(linechanging)
} {
if(encoderpos<5) encoderpos=5;
}break; if(encoderpos>9999) encoderpos=9999;
default: lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
break; }
}
line++; }break;
} default:
updateActiveLines(ItemCM_esteps,encoderpos); break;
} }
line++;
}
enum { updateActiveLines(ItemCM_esteps,encoderpos);
ItemC_exit,ItemC_temp,ItemC_move, }
ItemC_store, ItemC_load,ItemC_failsafe
};
enum {
void MainMenu::showControl() ItemC_exit,ItemC_temp,ItemC_move,
{ ItemC_store, ItemC_load,ItemC_failsafe
uint8_t line=0; };
clearIfNecessary();
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++) void MainMenu::showControl()
{ {
switch(i) uint8_t line=0;
{ clearIfNecessary();
case ItemC_exit: for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
MENUITEM( lcdprintPGM(" Main \003") , BLOCK;status=Main_Menu;beepshort(); ) ; {
break; switch(i)
case ItemC_temp: {
MENUITEM( lcdprintPGM(" Temperature \x7E") , BLOCK;status=Sub_TempControl;beepshort(); ) ; case ItemC_exit:
break; MENUITEM( lcdprintPGM(" Main \003") , BLOCK;status=Main_Menu;beepshort(); ) ;
case ItemC_move: break;
MENUITEM( lcdprintPGM(" Motion \x7E") , BLOCK;status=Sub_MotionControl;beepshort(); ) ; case ItemC_temp:
break; MENUITEM( lcdprintPGM(" Temperature \x7E") , BLOCK;status=Sub_TempControl;beepshort(); ) ;
case ItemC_store: break;
{ case ItemC_move:
if(force_lcd_update) MENUITEM( lcdprintPGM(" Motion \x7E") , BLOCK;status=Sub_MotionControl;beepshort(); ) ;
{ break;
lcd.setCursor(0,line);lcdprintPGM(" Store EPROM"); case ItemC_store:
} {
if((activeline==line) && CLICKED) if(force_lcd_update)
{ {
//enquecommand("M84"); lcd.setCursor(0,line);lcdprintPGM(" Store EPROM");
beepshort(); }
BLOCK; if((activeline==line) && CLICKED)
EEPROM_StoreSettings(); {
} //enquecommand("M84");
}break; beepshort();
case ItemC_load: BLOCK;
{ EEPROM_StoreSettings();
if(force_lcd_update) }
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" Load EPROM"); case ItemC_load:
} {
if((activeline==line) && CLICKED) if(force_lcd_update)
{ {
//enquecommand("M84"); lcd.setCursor(0,line);lcdprintPGM(" Load EPROM");
beepshort(); }
BLOCK; if((activeline==line) && CLICKED)
EEPROM_RetrieveSettings(); {
} //enquecommand("M84");
}break; beepshort();
case ItemC_failsafe: BLOCK;
{ EEPROM_RetrieveSettings();
if(force_lcd_update) }
{ }break;
lcd.setCursor(0,line);lcdprintPGM(" Restore Failsafe"); case ItemC_failsafe:
} {
if((activeline==line) && CLICKED) if(force_lcd_update)
{ {
//enquecommand("M84"); lcd.setCursor(0,line);lcdprintPGM(" Restore Failsafe");
beepshort(); }
BLOCK; if((activeline==line) && CLICKED)
EEPROM_RetrieveSettings(true); {
} //enquecommand("M84");
}break; beepshort();
default: BLOCK;
break; EEPROM_RetrieveSettings(true);
} }
line++; }break;
} default:
updateActiveLines(ItemC_failsafe,encoderpos); break;
} }
line++;
}
updateActiveLines(ItemC_failsafe,encoderpos);
}
void MainMenu::showSD()
{
#ifdef SDSUPPORT
uint8_t line=0;
void MainMenu::showSD()
clearIfNecessary(); {
static uint8_t nrfiles=0; #ifdef SDSUPPORT
if(force_lcd_update) uint8_t line=0;
{
if(card.cardOK) clearIfNecessary();
{ static uint8_t nrfiles=0;
nrfiles=card.getnrfilenames(); if(force_lcd_update)
} {
else if(card.cardOK)
{ {
nrfiles=0; nrfiles=card.getnrfilenames();
lineoffset=0; }
} else
} {
bool enforceupdate=false; nrfiles=0;
for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++) lineoffset=0;
{ }
switch(i) }
{ bool enforceupdate=false;
case 0: for(int8_t i=lineoffset;i<lineoffset+LCD_HEIGHT;i++)
MENUITEM( lcdprintPGM(" Main \003") , BLOCK;status=Main_Menu;beepshort(); ) ; {
break; switch(i)
// case 1: {
// { case 0:
// if(force_lcd_update) MENUITEM( lcdprintPGM(" Main \003") , BLOCK;status=Main_Menu;beepshort(); ) ;
// { break;
// lcd.setCursor(0,line); // case 1:
// #ifdef CARDINSERTED // {
// if(CARDINSERTED) // if(force_lcd_update)
// #else // {
// if(true) // lcd.setCursor(0,line);
// #endif // #ifdef CARDINSERTED
// { // if(CARDINSERTED)
// lcdprintPGM(" \004Refresh"); // #else
// } // if(true)
// else // #endif
// { // {
// lcdprintPGM(" \004Insert Card"); // lcdprintPGM(" \004Refresh");
// } // }
// // else
// } // {
// if((activeline==line) && CLICKED) // lcdprintPGM(" \004Insert Card");
// { // }
// BLOCK; //
// beepshort(); // }
// card.initsd(); // if((activeline==line) && CLICKED)
// force_lcd_update=true; // {
// nrfiles=card.getnrfilenames(); // BLOCK;
// } // beepshort();
// }break; // card.initsd();
case 1: // force_lcd_update=true;
MENUITEM( lcd.print(" ");card.getWorkDirName();if(card.filename[0]=='/') lcdprintPGM("\004Refresh");else {lcd.print("\005");lcd.print(card.filename);lcd.print("/..");} , BLOCK;card.updir();enforceupdate=true;lineoffset=0;beepshort(); ) ; // nrfiles=card.getnrfilenames();
// }
break; // }break;
default: case 1:
{ MENUITEM( lcd.print(" ");card.getWorkDirName();if(card.filename[0]=='/') lcdprintPGM("\004Refresh");else {lcd.print("\005");lcd.print(card.filename);lcd.print("/..");} , BLOCK;card.updir();enforceupdate=true;lineoffset=0;beepshort(); ) ;
#define FIRSTITEM 2
if(i-FIRSTITEM<nrfiles) break;
{ default:
if(force_lcd_update) {
{ #define FIRSTITEM 2
card.getfilename(i-FIRSTITEM); if(i-FIRSTITEM<nrfiles)
//Serial.print("Filenr:");Serial.println(i-2); {
lcd.setCursor(0,line);lcdprintPGM(" "); if(force_lcd_update)
if(card.filenameIsDir) lcd.print("\005"); {
lcd.print(card.filename); card.getfilename(i-FIRSTITEM);
} //Serial.print("Filenr:");Serial.println(i-2);
if((activeline==line) && CLICKED) lcd.setCursor(0,line);lcdprintPGM(" ");
{ if(card.filenameIsDir) lcd.print("\005");
BLOCK lcd.print(card.filename);
card.getfilename(i-FIRSTITEM); }
if(card.filenameIsDir) if((activeline==line) && CLICKED)
{ {
for(int8_t i=0;i<strlen(card.filename);i++) BLOCK
card.filename[i]=tolower(card.filename[i]); card.getfilename(i-FIRSTITEM);
card.chdir(card.filename); if(card.filenameIsDir)
lineoffset=0; {
enforceupdate=true; for(int8_t i=0;i<strlen(card.filename);i++)
} card.filename[i]=tolower(card.filename[i]);
else card.chdir(card.filename);
{ lineoffset=0;
char cmd[30]; enforceupdate=true;
for(int8_t i=0;i<strlen(card.filename);i++) }
card.filename[i]=tolower(card.filename[i]); else
sprintf(cmd,"M23 %s",card.filename); {
//sprintf(cmd,"M115"); char cmd[30];
enquecommand(cmd); for(int8_t i=0;i<strlen(card.filename);i++)
enquecommand("M24"); card.filename[i]=tolower(card.filename[i]);
beep(); sprintf(cmd,"M23 %s",card.filename);
status=Main_Status; //sprintf(cmd,"M115");
lcd_status(card.filename); enquecommand(cmd);
} enquecommand("M24");
} beep();
} status=Main_Status;
lcd_status(card.filename);
} }
break; }
} }
line++;
} }
updateActiveLines(FIRSTITEM+nrfiles-1,encoderpos); break;
if(enforceupdate) }
{ line++;
force_lcd_update=true; }
enforceupdate=false; updateActiveLines(FIRSTITEM+nrfiles-1,encoderpos);
} if(enforceupdate)
#endif {
} force_lcd_update=true;
enforceupdate=false;
enum {ItemM_watch, ItemM_prepare, ItemM_control, ItemM_file }; }
void MainMenu::showMainMenu() #endif
{ }
#ifndef ULTIPANEL enum {ItemM_watch, ItemM_prepare, ItemM_control, ItemM_file };
force_lcd_update=false; void MainMenu::showMainMenu()
#endif {
if(tune)
{ #ifndef ULTIPANEL
if(!(movesplanned() ||card.sdprinting)) force_lcd_update=false;
{ #endif
force_lcd_update=true; if(tune)
tune=false; {
} if(!(movesplanned() ||card.sdprinting))
} {
else force_lcd_update=true;
{ tune=false;
if(movesplanned() ||card.sdprinting) }
{ }
force_lcd_update=true; else
tune=true; {
} if(movesplanned() ||card.sdprinting)
} {
clearIfNecessary(); force_lcd_update=true;
for(int8_t line=0;line<LCD_HEIGHT;line++) tune=true;
{ }
switch(line) }
{ clearIfNecessary();
case ItemM_watch: for(int8_t line=0;line<LCD_HEIGHT;line++)
MENUITEM( lcdprintPGM(" Watch \003") , BLOCK;status=Main_Status;beepshort(); ) ; {
break; switch(line)
case ItemM_prepare: {
MENUITEM( if(!tune) lcdprintPGM(" Prepare \x7E");else lcdprintPGM(" Tune \x7E"); , BLOCK;status=Main_Prepare;beepshort(); ) ; case ItemM_watch:
break; MENUITEM( lcdprintPGM(" Watch \003") , BLOCK;status=Main_Status;beepshort(); ) ;
break;
case ItemM_control: case ItemM_prepare:
MENUITEM( lcdprintPGM(" Control \x7E") , BLOCK;status=Main_Control;beepshort(); ) ; MENUITEM( if(!tune) lcdprintPGM(" Prepare \x7E");else lcdprintPGM(" Tune \x7E"); , BLOCK;status=Main_Prepare;beepshort(); ) ;
break; break;
#ifdef SDSUPPORT
case ItemM_file: case ItemM_control:
{ MENUITEM( lcdprintPGM(" Control \x7E") , BLOCK;status=Main_Control;beepshort(); ) ;
if(force_lcd_update) break;
{ #ifdef SDSUPPORT
lcd.setCursor(0,line); case ItemM_file:
#ifdef CARDINSERTED {
if(CARDINSERTED) if(force_lcd_update)
#else {
if(true) lcd.setCursor(0,line);
#endif #ifdef CARDINSERTED
{ if(CARDINSERTED)
if(card.sdprinting) #else
lcdprintPGM(" Stop Print \x7E"); if(true)
else #endif
lcdprintPGM(" Card Menu \x7E"); {
} if(card.sdprinting)
else lcdprintPGM(" Stop Print \x7E");
{ else
lcdprintPGM(" No Card"); lcdprintPGM(" Card Menu \x7E");
} }
} else
#ifdef CARDINSERTED {
if(CARDINSERTED) lcdprintPGM(" No Card");
#endif }
if((activeline==line)&&CLICKED) }
{ #ifdef CARDINSERTED
card.printingHasFinished(); if(CARDINSERTED)
BLOCK; #endif
status=Main_SD; if((activeline==line)&&CLICKED)
beepshort(); {
} card.printingHasFinished();
}break; BLOCK;
#else status=Main_SD;
case ItemM_file: beepshort();
break; }
#endif }break;
default: #else
SERIAL_ERROR_START; case ItemM_file:
SERIAL_ERRORLNPGM("Something is wrong in the MenuStructure."); break;
break; #endif
} default:
} SERIAL_ERROR_START;
updateActiveLines(3,encoderpos); SERIAL_ERRORLNPGM("Something is wrong in the MenuStructure.");
} break;
}
void MainMenu::update() }
{ updateActiveLines(3,encoderpos);
static MainStatus oldstatus=Main_Menu; //init automatically causes foce_lcd_update=true }
static long timeoutToStatus=0;
static bool oldcardstatus=false; void MainMenu::update()
#ifdef CARDINSERTED {
if((CARDINSERTED != oldcardstatus)) static MainStatus oldstatus=Main_Menu; //init automatically causes foce_lcd_update=true
{ static long timeoutToStatus=0;
force_lcd_update=true; static bool oldcardstatus=false;
oldcardstatus=CARDINSERTED; #ifdef CARDINSERTED
//Serial.println("echo: SD CHANGE"); if((CARDINSERTED != oldcardstatus))
if(CARDINSERTED) {
{ force_lcd_update=true;
card.initsd(); oldcardstatus=CARDINSERTED;
LCD_MESSAGEPGM("Card inserted"); //Serial.println("echo: SD CHANGE");
} if(CARDINSERTED)
else {
{ card.initsd();
card.release(); LCD_MESSAGEPGM("Card inserted");
LCD_MESSAGEPGM("Card removed"); }
} else
} {
#endif card.release();
LCD_MESSAGEPGM("Card removed");
if(status!=oldstatus) }
{ }
force_lcd_update=true; #endif
encoderpos=0;
lineoffset=0; if(status!=oldstatus)
{
oldstatus=status; force_lcd_update=true;
} encoderpos=0;
if( (encoderpos!=lastencoderpos) || CLICKED) lineoffset=0;
timeoutToStatus=millis()+STATUSTIMEOUT;
oldstatus=status;
switch(status) }
{ if( (encoderpos!=lastencoderpos) || CLICKED)
case Main_Status: timeoutToStatus=millis()+STATUSTIMEOUT;
{
showStatus(); switch(status)
if(CLICKED) {
{ case Main_Status:
linechanging=false; {
BLOCK showStatus();
status=Main_Menu; if(CLICKED)
timeoutToStatus=millis()+STATUSTIMEOUT; {
} linechanging=false;
}break; BLOCK
case Main_Menu: status=Main_Menu;
{ timeoutToStatus=millis()+STATUSTIMEOUT;
showMainMenu(); }
linechanging=false; }break;
}break; case Main_Menu:
case Main_Prepare: {
{ showMainMenu();
if(tune) linechanging=false;
{ }break;
showTune(); case Main_Prepare:
} {
else if(tune)
{ {
showPrepare(); showTune();
} }
}break; else
case Main_Control: {
{ showPrepare();
showControl(); }
}break; }break;
case Sub_MotionControl: case Main_Control:
{ {
showControlMotion(); showControl();
}break; }break;
case Sub_TempControl: case Sub_MotionControl:
{ {
showControlTemp(); showControlMotion();
}break; }break;
case Main_SD: case Sub_TempControl:
{ {
showSD(); showControlTemp();
}break; }break;
} case Main_SD:
{
if(timeoutToStatus<millis()) showSD();
status=Main_Status; }break;
//force_lcd_update=false; }
lastencoderpos=encoderpos;
} if(timeoutToStatus<millis())
status=Main_Status;
//force_lcd_update=false;
lastencoderpos=encoderpos;
}
// convert float to string with +123.4 format
char *ftostr3(const float &x)
{
//sprintf(conv,"%5.1f",x);
int xx=x; // convert float to string with +123.4 format
conv[0]=(xx/100)%10+'0'; char *ftostr3(const float &x)
conv[1]=(xx/10)%10+'0'; {
conv[2]=(xx)%10+'0'; //sprintf(conv,"%5.1f",x);
conv[3]=0; int xx=x;
return conv; conv[0]=(xx/100)%10+'0';
} conv[1]=(xx/10)%10+'0';
conv[2]=(xx)%10+'0';
char *itostr2(const uint8_t &x) conv[3]=0;
{ return conv;
//sprintf(conv,"%5.1f",x); }
int xx=x;
conv[0]=(xx/10)%10+'0'; char *itostr2(const uint8_t &x)
conv[1]=(xx)%10+'0'; {
conv[2]=0; //sprintf(conv,"%5.1f",x);
return conv; int xx=x;
} conv[0]=(xx/10)%10+'0';
conv[1]=(xx)%10+'0';
// convert float to string with +123.4 format conv[2]=0;
char *ftostr31(const float &x) return conv;
{ }
int xx=x*10;
conv[0]=(xx>=0)?'+':'-'; // convert float to string with +123.4 format
xx=abs(xx); char *ftostr31(const float &x)
conv[1]=(xx/1000)%10+'0'; {
conv[2]=(xx/100)%10+'0'; int xx=x*10;
conv[3]=(xx/10)%10+'0'; conv[0]=(xx>=0)?'+':'-';
conv[4]='.'; xx=abs(xx);
conv[5]=(xx)%10+'0'; conv[1]=(xx/1000)%10+'0';
conv[6]=0; conv[2]=(xx/100)%10+'0';
return conv; conv[3]=(xx/10)%10+'0';
} conv[4]='.';
conv[5]=(xx)%10+'0';
char *ftostr32(const float &x) conv[6]=0;
{ return conv;
int xx=x*100; }
conv[0]=(xx>=0)?'+':'-';
xx=abs(xx); char *ftostr32(const float &x)
conv[1]=(xx/100)%10+'0'; {
conv[2]='.'; int xx=x*100;
conv[3]=(xx/10)%10+'0'; conv[0]=(xx>=0)?'+':'-';
conv[4]=(xx)%10+'0'; xx=abs(xx);
conv[6]=0; conv[1]=(xx/100)%10+'0';
return conv; conv[2]='.';
} conv[3]=(xx/10)%10+'0';
conv[4]=(xx)%10+'0';
char *itostr31(const int &xx) conv[6]=0;
{ return conv;
conv[0]=(xx>=0)?'+':'-'; }
conv[1]=(xx/1000)%10+'0';
conv[2]=(xx/100)%10+'0'; char *itostr31(const int &xx)
conv[3]=(xx/10)%10+'0'; {
conv[4]='.'; conv[0]=(xx>=0)?'+':'-';
conv[5]=(xx)%10+'0'; conv[1]=(xx/1000)%10+'0';
conv[6]=0; conv[2]=(xx/100)%10+'0';
return conv; conv[3]=(xx/10)%10+'0';
} conv[4]='.';
conv[5]=(xx)%10+'0';
char *itostr3(const int &xx) conv[6]=0;
{ return conv;
conv[0]=(xx/100)%10+'0'; }
conv[1]=(xx/10)%10+'0';
conv[2]=(xx)%10+'0'; char *itostr3(const int &xx)
conv[3]=0; {
return conv; conv[0]=(xx/100)%10+'0';
} conv[1]=(xx/10)%10+'0';
conv[2]=(xx)%10+'0';
char *itostr4(const int &xx) conv[3]=0;
{ return conv;
conv[0]=(xx/1000)%10+'0'; }
conv[1]=(xx/100)%10+'0';
conv[2]=(xx/10)%10+'0'; char *itostr4(const int &xx)
conv[3]=(xx)%10+'0'; {
conv[4]=0; conv[0]=(xx/1000)%10+'0';
return conv; conv[1]=(xx/100)%10+'0';
} conv[2]=(xx/10)%10+'0';
conv[3]=(xx)%10+'0';
// convert float to string with +1234.5 format conv[4]=0;
char *ftostr51(const float &x) return conv;
{ }
int xx=x*10;
conv[0]=(xx>=0)?'+':'-'; // convert float to string with +1234.5 format
xx=abs(xx); char *ftostr51(const float &x)
conv[1]=(xx/10000)%10+'0'; {
conv[2]=(xx/1000)%10+'0'; int xx=x*10;
conv[3]=(xx/100)%10+'0'; conv[0]=(xx>=0)?'+':'-';
conv[4]=(xx/10)%10+'0'; xx=abs(xx);
conv[5]='.'; conv[1]=(xx/10000)%10+'0';
conv[6]=(xx)%10+'0'; conv[2]=(xx/1000)%10+'0';
conv[7]=0; conv[3]=(xx/100)%10+'0';
return conv; conv[4]=(xx/10)%10+'0';
} conv[5]='.';
conv[6]=(xx)%10+'0';
conv[7]=0;
#endif //ULTRA_LCD return conv;
}
#endif //ULTRA_LCD