Merged multiple extruder support.

Soft PWM. (Sanguinololu can also have PID temperature control)
Interrupt save WRITE for addresses > 0x0FF
This commit is contained in:
Erik van der Zalm 2011-12-12 19:34:37 +01:00
parent 3664ed6aad
commit e017228569
11 changed files with 5525 additions and 5413 deletions

View file

@ -4,11 +4,11 @@
// This determines the communication speed of the printer // This determines the communication speed of the printer
//#define BAUDRATE 250000 #define BAUDRATE 250000
#define BAUDRATE 115200 //#define BAUDRATE 115200
//#define BAUDRATE 230400 //#define BAUDRATE 230400
#define EXTRUDERS 2 #define EXTRUDERS 1
// Frequency limit // Frequency limit
// See nophead's blog for more info // See nophead's blog for more info
@ -32,7 +32,7 @@
// Sanguinololu 1.2 and above = 62 // Sanguinololu 1.2 and above = 62
// Ultimaker = 7, // Ultimaker = 7,
// Teensylu = 8 // Teensylu = 8
#define MOTHERBOARD 33 #define MOTHERBOARD 7
//=========================================================================== //===========================================================================
//=============================Thermal Settings ============================ //=============================Thermal Settings ============================
@ -46,16 +46,21 @@
// 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 1
#define THERMISTORHEATER_1 1 //#define THERMISTORHEATER_0 3
#define HEATER_0_USES_THERMISTOR //#define THERMISTORHEATER_1 1
#define HEATER_1_USES_THERMISTOR //#define THERMISTORHEATER_2 1
//#define HEATER_0_USES_AD595
//#define HEATER_0_USES_THERMISTOR
//#define HEATER_1_USES_THERMISTOR
//#define HEATER_2_USES_THERMISTOR
#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 THERMISTORBED 1
#define BED_USES_THERMISTOR //#define BED_USES_THERMISTOR
//#define BED_USES_AD595 //#define BED_USES_AD595
#define BED_CHECK_INTERVAL 5000 //ms #define BED_CHECK_INTERVAL 5000 //ms
@ -73,7 +78,8 @@
//// 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 BED_MINTEMP 5 //#define HEATER_2_MINTEMP 5
//#define BED_MINTEMP 5
// When temperature exceeds max temp, your heater will be switched off. // When temperature exceeds max temp, your heater will be switched off.
@ -81,7 +87,8 @@
// 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 BED_MAXTEMP 150 //#define HEATER_2_MAXTEMP 275
//#define BED_MAXTEMP 150
// Wait for Cooldown // Wait for Cooldown
@ -92,21 +99,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.
@ -130,14 +133,14 @@
// #define DEFAULT_Kd (PID_SWING_AT_CRITIAL/8./PID_dT) // #define DEFAULT_Kd (PID_SWING_AT_CRITIAL/8./PID_dT)
// Ultitmaker // Ultitmaker
// #define DEFAULT_Kp 22.2 #define DEFAULT_Kp 22.2
// #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 // Makergear
#define DEFAULT_Kp 7.0 // #define DEFAULT_Kp 7.0
#define DEFAULT_Ki 0.1 // #define DEFAULT_Ki 0.1
#define DEFAULT_Kd 12 // #define DEFAULT_Kd 12
// Mendel Parts V9 on 12V // Mendel Parts V9 on 12V
// #define DEFAULT_Kp 63.0 // #define DEFAULT_Kp 63.0
@ -170,12 +173,12 @@
#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 = false; // 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 = false; // 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 = false; // 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
@ -186,7 +189,7 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
// 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 true #define DISABLE_Z false
#define DISABLE_E false // For all extruders #define DISABLE_E false // For all extruders
// Inverting axis direction // Inverting axis direction
@ -195,11 +198,11 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
//#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, used for all extruders //#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 false // 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_E0_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 true // 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 #define INVERT_E2_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
//// ENDSTOP SETTINGS: //// ENDSTOP SETTINGS:
@ -208,15 +211,15 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
#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
#define HOMING_FEEDRATE {30*60, 30*60, 2*60, 0} // set the homing speeds (mm/min) #define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0} // set the homing speeds (mm/min)
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
#define X_HOME_RETRACT_MM 5 #define X_HOME_RETRACT_MM 5
@ -230,9 +233,9 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
// 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_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.
@ -283,10 +286,10 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
// 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
@ -298,10 +301,10 @@ const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of t
//LCD and SD support //LCD and SD support
//#define ULTRA_LCD //general lcd support, also 16x2 //#define ULTRA_LCD //general lcd support, also 16x2
#define SDSUPPORT // Enable SD Card Support in Hardware Console //#define SDSUPPORT // Enable SD Card Support in Hardware Console
#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 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

@ -57,8 +57,6 @@ const prog_char echomagic[] PROGMEM ="echo:";
#define SERIAL_ECHOPAIR(name,value) {SERIAL_ECHOPGM(name);SERIAL_ECHO(value);} #define SERIAL_ECHOPAIR(name,value) {SERIAL_ECHOPGM(name);SERIAL_ECHO(value);}
// Macro for getting current active extruder
#define ACTIVE_EXTRUDER (active_extruder)
//things to write to serial from Programmemory. saves 400 to 2k of RAM. //things to write to serial from Programmemory. saves 400 to 2k of RAM.
#define SerialprintPGM(x) serialprintPGM(MYPGM(x)) #define SerialprintPGM(x) serialprintPGM(MYPGM(x))

View file

@ -465,16 +465,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]);\
@ -541,6 +541,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[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;
destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR; destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR;
@ -723,7 +724,7 @@ FORCE_INLINE void process_commands()
if (code_seen('S')) setTargetBed(code_value()); if (code_seen('S')) setTargetBed(code_value());
break; break;
case 105 : // M105 case 105 : // M105
tmp_extruder = ACTIVE_EXTRUDER; tmp_extruder = active_extruder;
if(code_seen('T')) { if(code_seen('T')) {
tmp_extruder = code_value(); tmp_extruder = code_value();
if(tmp_extruder >= EXTRUDERS) { if(tmp_extruder >= EXTRUDERS) {
@ -743,6 +744,10 @@ FORCE_INLINE void process_commands()
#else #else
SERIAL_ERROR_START; SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("No thermistors - no temp"); SERIAL_ERRORLNPGM("No thermistors - no temp");
#endif
#ifdef PIDTEMP
SERIAL_PROTOCOLPGM(" @:");
SERIAL_PROTOCOL(getHeaterPower(tmp_extruder));
#endif #endif
SERIAL_PROTOCOLLN(""); SERIAL_PROTOCOLLN("");
return; return;
@ -788,24 +793,26 @@ FORCE_INLINE void process_commands()
while((residencyStart == -1) || 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 and remaining time 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) );
SERIAL_PROTOCOLPGM(" E:"); SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOLLN( (int)tmp_extruder ); SERIAL_PROTOCOLLN( (int)tmp_extruder );
SERIAL_PROTOCOLPGM(" W:"); #ifdef TEMP_RESIDENCY_TIME
if(residencyStart > -1) SERIAL_PROTOCOLPGM(" W:");
{ if(residencyStart > -1)
codenum = TEMP_RESIDENCY_TIME - ((millis() - residencyStart) / 1000); {
SERIAL_PROTOCOLLN( codenum ); codenum = TEMP_RESIDENCY_TIME - ((millis() - residencyStart) / 1000);
} SERIAL_PROTOCOLLN( codenum );
else }
{ else
SERIAL_PROTOCOLLN( "?" ); {
} SERIAL_PROTOCOLLN( "?" );
}
#endif
codenum = millis(); codenum = millis();
} }
manage_heater(); manage_heater();
@ -834,11 +841,11 @@ 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=degHotend(ACTIVE_EXTRUDER); float tt=degHotend(active_extruder);
SERIAL_PROTOCOLPGM("T:"); SERIAL_PROTOCOLPGM("T:");
SERIAL_PROTOCOL(tt); SERIAL_PROTOCOL(tt);
SERIAL_PROTOCOLPGM(" E:"); SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOLLN( (int)tmp_extruder ); SERIAL_PROTOCOLLN( (int)active_extruder );
SERIAL_PROTOCOLPGM(" B:"); SERIAL_PROTOCOLPGM(" B:");
SERIAL_PROTOCOLLN(degBed()); SERIAL_PROTOCOLLN(degBed());
codenum = millis(); codenum = millis();
@ -1191,6 +1198,7 @@ void manage_inactivity(byte debug)
void kill() void kill()
{ {
cli(); // Stop interrupts
disable_heater(); disable_heater();
disable_x(); disable_x();
@ -1207,4 +1215,4 @@ void kill()
while(1); // Wait for reset while(1); // Wait for reset
} }

View file

@ -1,2573 +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)
#if EXTRUDERS > 2 /// set pin as input
#define WRITE_E_STEP(v) { if(ACTIVE_EXTRUDER == 2) { WRITE(E2_STEP_PIN, v); } else { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}} #define _SET_INPUT(IO) do {DIO ## IO ## _DDR &= ~MASK(DIO ## IO ## _PIN); } while (0)
#define NORM_E_DIR() { if(ACTIVE_EXTRUDER == 2) { WRITE(E2_DIR_PIN, INVERT_E2_DIR); } else { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}} /// set pin as output
#define REV_E_DIR() { if(ACTIVE_EXTRUDER == 2) { WRITE(E2_DIR_PIN, !INVERT_E2_DIR); } else { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}} #define _SET_OUTPUT(IO) do {DIO ## IO ## _DDR |= MASK(DIO ## IO ## _PIN); } while (0)
#elif EXTRUDERS > 1
#define WRITE_E_STEP(v) { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }} /// check if pin is an input
#define NORM_E_DIR() { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }} #define _GET_INPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) == 0)
#define REV_E_DIR() { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }} /// check if pin is an output
#else #define _GET_OUTPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) != 0)
#define WRITE_E_STEP(v) WRITE(E0_STEP_PIN, v)
#define NORM_E_DIR() WRITE(E0_DIR_PIN, INVERT_E0_DIR) /// check if pin is an timer
#define REV_E_DIR() WRITE(E0_DIR_PIN, !INVERT_E0_DIR) #define _GET_TIMER(IO) ((DIO ## IO ## _PWM)
#endif
// why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
/// toggle a pin wrapper
#define TOGGLE(IO) _TOGGLE(IO) /// Read a pin wrapper
#define READ(IO) _READ(IO)
/// set pin as input wrapper /// Write to a pin wrapper
#define SET_INPUT(IO) _SET_INPUT(IO) #define WRITE(IO, v) _WRITE(IO, v)
/// set pin as output wrapper
#define SET_OUTPUT(IO) _SET_OUTPUT(IO) /// toggle a pin wrapper
#define TOGGLE(IO) _TOGGLE(IO)
/// check if pin is an input wrapper
#define GET_INPUT(IO) _GET_INPUT(IO) /// set pin as input wrapper
/// check if pin is an output wrapper #define SET_INPUT(IO) _SET_INPUT(IO)
#define GET_OUTPUT(IO) _GET_OUTPUT(IO) /// set pin as output wrapper
#define SET_OUTPUT(IO) _SET_OUTPUT(IO)
/*
ports and functions /// check if pin is an input wrapper
#define GET_INPUT(IO) _GET_INPUT(IO)
added as necessary or if I feel like it- not a comprehensive list! /// check if pin is an output wrapper
*/ #define GET_OUTPUT(IO) _GET_OUTPUT(IO)
#if defined (__AVR_ATmega168__) || defined (__AVR_ATmega328__) || defined (__AVR_ATmega328P__) /// check if pin is an timer wrapper
// UART #define GET_TIMER(IO) _GET_TIMER(IO)
#define RXD DIO0
#define TXD DIO1 /*
ports and functions
// SPI
#define SCK DIO13 added as necessary or if I feel like it- not a comprehensive list!
#define MISO DIO12 */
#define MOSI DIO11
#define SS DIO10 #if defined (__AVR_ATmega168__) || defined (__AVR_ATmega328__) || defined (__AVR_ATmega328P__)
// UART
// TWI (I2C) #define RXD DIO0
#define SCL AIO5 #define TXD DIO1
#define SDA AIO4
// SPI
// timers and PWM #define SCK DIO13
#define OC0A DIO6 #define MISO DIO12
#define OC0B DIO5 #define MOSI DIO11
#define OC1A DIO9 #define SS DIO10
#define OC1B DIO10
#define OC2A DIO11 // TWI (I2C)
#define OC2B DIO3 #define SCL AIO5
#define SDA AIO4
#define DEBUG_LED AIO5
// timers and PWM
/* #define OC0A DIO6
pins #define OC0B DIO5
*/ #define OC1A DIO9
#define OC1B DIO10
#define DIO0_PIN PIND0 #define OC2A DIO11
#define DIO0_RPORT PIND #define OC2B DIO3
#define DIO0_WPORT PORTD
#define DIO0_DDR DDRD #define DEBUG_LED AIO5
#define DIO0_PWM NULL
/*
#define DIO1_PIN PIND1 pins
#define DIO1_RPORT PIND */
#define DIO1_WPORT PORTD
#define DIO1_DDR DDRD #define DIO0_PIN PIND0
#define DIO1_PWM NULL #define DIO0_RPORT PIND
#define DIO0_WPORT PORTD
#define DIO2_PIN PIND2 #define DIO0_DDR DDRD
#define DIO2_RPORT PIND #define DIO0_PWM NULL
#define DIO2_WPORT PORTD
#define DIO2_DDR DDRD #define DIO1_PIN PIND1
#define DIO2_PWM NULL #define DIO1_RPORT PIND
#define DIO1_WPORT PORTD
#define DIO3_PIN PIND3 #define DIO1_DDR DDRD
#define DIO3_RPORT PIND #define DIO1_PWM NULL
#define DIO3_WPORT PORTD
#define DIO3_DDR DDRD #define DIO2_PIN PIND2
#define DIO3_PWM &OCR2B #define DIO2_RPORT PIND
#define DIO2_WPORT PORTD
#define DIO4_PIN PIND4 #define DIO2_DDR DDRD
#define DIO4_RPORT PIND #define DIO2_PWM NULL
#define DIO4_WPORT PORTD
#define DIO4_DDR DDRD #define DIO3_PIN PIND3
#define DIO4_PWM NULL #define DIO3_RPORT PIND
#define DIO3_WPORT PORTD
#define DIO5_PIN PIND5 #define DIO3_DDR DDRD
#define DIO5_RPORT PIND #define DIO3_PWM &OCR2B
#define DIO5_WPORT PORTD
#define DIO5_DDR DDRD #define DIO4_PIN PIND4
#define DIO5_PWM &OCR0B #define DIO4_RPORT PIND
#define DIO4_WPORT PORTD
#define DIO6_PIN PIND6 #define DIO4_DDR DDRD
#define DIO6_RPORT PIND #define DIO4_PWM NULL
#define DIO6_WPORT PORTD
#define DIO6_DDR DDRD #define DIO5_PIN PIND5
#define DIO6_PWM &OCR0A #define DIO5_RPORT PIND
#define DIO5_WPORT PORTD
#define DIO7_PIN PIND7 #define DIO5_DDR DDRD
#define DIO7_RPORT PIND #define DIO5_PWM &OCR0B
#define DIO7_WPORT PORTD
#define DIO7_DDR DDRD #define DIO6_PIN PIND6
#define DIO7_PWM NULL #define DIO6_RPORT PIND
#define DIO6_WPORT PORTD
#define DIO8_PIN PINB0 #define DIO6_DDR DDRD
#define DIO8_RPORT PINB #define DIO6_PWM &OCR0A
#define DIO8_WPORT PORTB
#define DIO8_DDR DDRB #define DIO7_PIN PIND7
#define DIO8_PWM NULL #define DIO7_RPORT PIND
#define DIO7_WPORT PORTD
#define DIO9_PIN PINB1 #define DIO7_DDR DDRD
#define DIO9_RPORT PINB #define DIO7_PWM NULL
#define DIO9_WPORT PORTB
#define DIO9_DDR DDRB #define DIO8_PIN PINB0
#define DIO9_PWM NULL #define DIO8_RPORT PINB
#define DIO8_WPORT PORTB
#define DIO10_PIN PINB2 #define DIO8_DDR DDRB
#define DIO10_RPORT PINB #define DIO8_PWM NULL
#define DIO10_WPORT PORTB
#define DIO10_DDR DDRB #define DIO9_PIN PINB1
#define DIO10_PWM NULL #define DIO9_RPORT PINB
#define DIO9_WPORT PORTB
#define DIO11_PIN PINB3 #define DIO9_DDR DDRB
#define DIO11_RPORT PINB #define DIO9_PWM NULL
#define DIO11_WPORT PORTB
#define DIO11_DDR DDRB #define DIO10_PIN PINB2
#define DIO11_PWM &OCR2A #define DIO10_RPORT PINB
#define DIO10_WPORT PORTB
#define DIO12_PIN PINB4 #define DIO10_DDR DDRB
#define DIO12_RPORT PINB #define DIO10_PWM NULL
#define DIO12_WPORT PORTB
#define DIO12_DDR DDRB #define DIO11_PIN PINB3
#define DIO12_PWM NULL #define DIO11_RPORT PINB
#define DIO11_WPORT PORTB
#define DIO13_PIN PINB5 #define DIO11_DDR DDRB
#define DIO13_RPORT PINB #define DIO11_PWM &OCR2A
#define DIO13_WPORT PORTB
#define DIO13_DDR DDRB #define DIO12_PIN PINB4
#define DIO13_PWM NULL #define DIO12_RPORT PINB
#define DIO12_WPORT PORTB
#define DIO12_DDR DDRB
#define DIO14_PIN PINC0 #define DIO12_PWM NULL
#define DIO14_RPORT PINC
#define DIO14_WPORT PORTC #define DIO13_PIN PINB5
#define DIO14_DDR DDRC #define DIO13_RPORT PINB
#define DIO14_PWM NULL #define DIO13_WPORT PORTB
#define DIO13_DDR DDRB
#define DIO15_PIN PINC1 #define DIO13_PWM NULL
#define DIO15_RPORT PINC
#define DIO15_WPORT PORTC
#define DIO15_DDR DDRC #define DIO14_PIN PINC0
#define DIO15_PWM NULL #define DIO14_RPORT PINC
#define DIO14_WPORT PORTC
#define DIO16_PIN PINC2 #define DIO14_DDR DDRC
#define DIO16_RPORT PINC #define DIO14_PWM NULL
#define DIO16_WPORT PORTC
#define DIO16_DDR DDRC #define DIO15_PIN PINC1
#define DIO16_PWM NULL #define DIO15_RPORT PINC
#define DIO15_WPORT PORTC
#define DIO17_PIN PINC3 #define DIO15_DDR DDRC
#define DIO17_RPORT PINC #define DIO15_PWM NULL
#define DIO17_WPORT PORTC
#define DIO17_DDR DDRC #define DIO16_PIN PINC2
#define DIO17_PWM NULL #define DIO16_RPORT PINC
#define DIO16_WPORT PORTC
#define DIO18_PIN PINC4 #define DIO16_DDR DDRC
#define DIO18_RPORT PINC #define DIO16_PWM NULL
#define DIO18_WPORT PORTC
#define DIO18_DDR DDRC #define DIO17_PIN PINC3
#define DIO18_PWM NULL #define DIO17_RPORT PINC
#define DIO17_WPORT PORTC
#define DIO19_PIN PINC5 #define DIO17_DDR DDRC
#define DIO19_RPORT PINC #define DIO17_PWM NULL
#define DIO19_WPORT PORTC
#define DIO19_DDR DDRC #define DIO18_PIN PINC4
#define DIO19_PWM NULL #define DIO18_RPORT PINC
#define DIO18_WPORT PORTC
#define DIO20_PIN PINC6 #define DIO18_DDR DDRC
#define DIO20_RPORT PINC #define DIO18_PWM NULL
#define DIO20_WPORT PORTC
#define DIO20_DDR DDRC #define DIO19_PIN PINC5
#define DIO20_PWM NULL #define DIO19_RPORT PINC
#define DIO19_WPORT PORTC
#define DIO21_PIN PINC7 #define DIO19_DDR DDRC
#define DIO21_RPORT PINC #define DIO19_PWM NULL
#define DIO21_WPORT PORTC
#define DIO21_DDR DDRC #define DIO20_PIN PINC6
#define DIO21_PWM NULL #define DIO20_RPORT PINC
#define DIO20_WPORT PORTC
#define DIO20_DDR DDRC
#define DIO20_PWM NULL
#undef PB0
#define PB0_PIN PINB0 #define DIO21_PIN PINC7
#define PB0_RPORT PINB #define DIO21_RPORT PINC
#define PB0_WPORT PORTB #define DIO21_WPORT PORTC
#define PB0_DDR DDRB #define DIO21_DDR DDRC
#define PB0_PWM NULL #define DIO21_PWM NULL
#undef PB1
#define PB1_PIN PINB1
#define PB1_RPORT PINB #undef PB0
#define PB1_WPORT PORTB #define PB0_PIN PINB0
#define PB1_DDR DDRB #define PB0_RPORT PINB
#define PB1_PWM NULL #define PB0_WPORT PORTB
#define PB0_DDR DDRB
#undef PB2 #define PB0_PWM NULL
#define PB2_PIN PINB2
#define PB2_RPORT PINB #undef PB1
#define PB2_WPORT PORTB #define PB1_PIN PINB1
#define PB2_DDR DDRB #define PB1_RPORT PINB
#define PB2_PWM NULL #define PB1_WPORT PORTB
#define PB1_DDR DDRB
#undef PB3 #define PB1_PWM NULL
#define PB3_PIN PINB3
#define PB3_RPORT PINB #undef PB2
#define PB3_WPORT PORTB #define PB2_PIN PINB2
#define PB3_DDR DDRB #define PB2_RPORT PINB
#define PB3_PWM &OCR2A #define PB2_WPORT PORTB
#define PB2_DDR DDRB
#undef PB4 #define PB2_PWM NULL
#define PB4_PIN PINB4
#define PB4_RPORT PINB #undef PB3
#define PB4_WPORT PORTB #define PB3_PIN PINB3
#define PB4_DDR DDRB #define PB3_RPORT PINB
#define PB4_PWM NULL #define PB3_WPORT PORTB
#define PB3_DDR DDRB
#undef PB5 #define PB3_PWM &OCR2A
#define PB5_PIN PINB5
#define PB5_RPORT PINB #undef PB4
#define PB5_WPORT PORTB #define PB4_PIN PINB4
#define PB5_DDR DDRB #define PB4_RPORT PINB
#define PB5_PWM NULL #define PB4_WPORT PORTB
#define PB4_DDR DDRB
#undef PB6 #define PB4_PWM NULL
#define PB6_PIN PINB6
#define PB6_RPORT PINB #undef PB5
#define PB6_WPORT PORTB #define PB5_PIN PINB5
#define PB6_DDR DDRB #define PB5_RPORT PINB
#define PB6_PWM NULL #define PB5_WPORT PORTB
#define PB5_DDR DDRB
#undef PB7 #define PB5_PWM NULL
#define PB7_PIN PINB7
#define PB7_RPORT PINB #undef PB6
#define PB7_WPORT PORTB #define PB6_PIN PINB6
#define PB7_DDR DDRB #define PB6_RPORT PINB
#define PB7_PWM NULL #define PB6_WPORT PORTB
#define PB6_DDR DDRB
#define PB6_PWM NULL
#undef PC0
#define PC0_PIN PINC0 #undef PB7
#define PC0_RPORT PINC #define PB7_PIN PINB7
#define PC0_WPORT PORTC #define PB7_RPORT PINB
#define PC0_DDR DDRC #define PB7_WPORT PORTB
#define PC0_PWM NULL #define PB7_DDR DDRB
#define PB7_PWM NULL
#undef PC1
#define PC1_PIN PINC1
#define PC1_RPORT PINC #undef PC0
#define PC1_WPORT PORTC #define PC0_PIN PINC0
#define PC1_DDR DDRC #define PC0_RPORT PINC
#define PC1_PWM NULL #define PC0_WPORT PORTC
#define PC0_DDR DDRC
#undef PC2 #define PC0_PWM NULL
#define PC2_PIN PINC2
#define PC2_RPORT PINC #undef PC1
#define PC2_WPORT PORTC #define PC1_PIN PINC1
#define PC2_DDR DDRC #define PC1_RPORT PINC
#define PC2_PWM NULL #define PC1_WPORT PORTC
#define PC1_DDR DDRC
#undef PC3 #define PC1_PWM NULL
#define PC3_PIN PINC3
#define PC3_RPORT PINC #undef PC2
#define PC3_WPORT PORTC #define PC2_PIN PINC2
#define PC3_DDR DDRC #define PC2_RPORT PINC
#define PC3_PWM NULL #define PC2_WPORT PORTC
#define PC2_DDR DDRC
#undef PC4 #define PC2_PWM NULL
#define PC4_PIN PINC4
#define PC4_RPORT PINC #undef PC3
#define PC4_WPORT PORTC #define PC3_PIN PINC3
#define PC4_DDR DDRC #define PC3_RPORT PINC
#define PC4_PWM NULL #define PC3_WPORT PORTC
#define PC3_DDR DDRC
#undef PC5 #define PC3_PWM NULL
#define PC5_PIN PINC5
#define PC5_RPORT PINC #undef PC4
#define PC5_WPORT PORTC #define PC4_PIN PINC4
#define PC5_DDR DDRC #define PC4_RPORT PINC
#define PC5_PWM NULL #define PC4_WPORT PORTC
#define PC4_DDR DDRC
#undef PC6 #define PC4_PWM NULL
#define PC6_PIN PINC6
#define PC6_RPORT PINC #undef PC5
#define PC6_WPORT PORTC #define PC5_PIN PINC5
#define PC6_DDR DDRC #define PC5_RPORT PINC
#define PC6_PWM NULL #define PC5_WPORT PORTC
#define PC5_DDR DDRC
#undef PC7 #define PC5_PWM NULL
#define PC7_PIN PINC7
#define PC7_RPORT PINC #undef PC6
#define PC7_WPORT PORTC #define PC6_PIN PINC6
#define PC7_DDR DDRC #define PC6_RPORT PINC
#define PC7_PWM NULL #define PC6_WPORT PORTC
#define PC6_DDR DDRC
#define PC6_PWM NULL
#undef PD0
#define PD0_PIN PIND0 #undef PC7
#define PD0_RPORT PIND #define PC7_PIN PINC7
#define PD0_WPORT PORTD #define PC7_RPORT PINC
#define PD0_DDR DDRD #define PC7_WPORT PORTC
#define PD0_PWM NULL #define PC7_DDR DDRC
#define PC7_PWM NULL
#undef PD1
#define PD1_PIN PIND1
#define PD1_RPORT PIND #undef PD0
#define PD1_WPORT PORTD #define PD0_PIN PIND0
#define PD1_DDR DDRD #define PD0_RPORT PIND
#define PD1_PWM NULL #define PD0_WPORT PORTD
#define PD0_DDR DDRD
#undef PD2 #define PD0_PWM NULL
#define PD2_PIN PIND2
#define PD2_RPORT PIND #undef PD1
#define PD2_WPORT PORTD #define PD1_PIN PIND1
#define PD2_DDR DDRD #define PD1_RPORT PIND
#define PD2_PWM NULL #define PD1_WPORT PORTD
#define PD1_DDR DDRD
#undef PD3 #define PD1_PWM NULL
#define PD3_PIN PIND3
#define PD3_RPORT PIND #undef PD2
#define PD3_WPORT PORTD #define PD2_PIN PIND2
#define PD3_DDR DDRD #define PD2_RPORT PIND
#define PD3_PWM &OCR2B #define PD2_WPORT PORTD
#define PD2_DDR DDRD
#undef PD4 #define PD2_PWM NULL
#define PD4_PIN PIND4
#define PD4_RPORT PIND #undef PD3
#define PD4_WPORT PORTD #define PD3_PIN PIND3
#define PD4_DDR DDRD #define PD3_RPORT PIND
#define PD4_PWM NULL #define PD3_WPORT PORTD
#define PD3_DDR DDRD
#undef PD5 #define PD3_PWM &OCR2B
#define PD5_PIN PIND5
#define PD5_RPORT PIND #undef PD4
#define PD5_WPORT PORTD #define PD4_PIN PIND4
#define PD5_DDR DDRD #define PD4_RPORT PIND
#define PD5_PWM &OCR0B #define PD4_WPORT PORTD
#define PD4_DDR DDRD
#undef PD6 #define PD4_PWM NULL
#define PD6_PIN PIND6
#define PD6_RPORT PIND #undef PD5
#define PD6_WPORT PORTD #define PD5_PIN PIND5
#define PD6_DDR DDRD #define PD5_RPORT PIND
#define PD6_PWM &OCR0A #define PD5_WPORT PORTD
#define PD5_DDR DDRD
#undef PD7 #define PD5_PWM &OCR0B
#define PD7_PIN PIND7
#define PD7_RPORT PIND #undef PD6
#define PD7_WPORT PORTD #define PD6_PIN PIND6
#define PD7_DDR DDRD #define PD6_RPORT PIND
#define PD7_PWM NULL #define PD6_WPORT PORTD
#endif /* _AVR_ATmega{168,328,328P}__ */ #define PD6_DDR DDRD
#define PD6_PWM &OCR0A
#if defined (__AVR_ATmega644__) || defined (__AVR_ATmega644P__) || defined (__AVR_ATmega644PA__)
// UART #undef PD7
#define RXD DIO8 #define PD7_PIN PIND7
#define TXD DIO9 #define PD7_RPORT PIND
#define RXD0 DIO8 #define PD7_WPORT PORTD
#define TXD0 DIO9 #define PD7_DDR DDRD
#define PD7_PWM NULL
#define RXD1 DIO10 #endif /* _AVR_ATmega{168,328,328P}__ */
#define TXD1 DIO11
#if defined (__AVR_ATmega644__) || defined (__AVR_ATmega644P__) || defined (__AVR_ATmega644PA__)
// SPI // UART
#define SCK DIO7 #define RXD DIO8
#define MISO DIO6 #define TXD DIO9
#define MOSI DIO5 #define RXD0 DIO8
#define SS DIO4 #define TXD0 DIO9
// TWI (I2C) #define RXD1 DIO10
#define SCL DIO16 #define TXD1 DIO11
#define SDA DIO17
// SPI
// timers and PWM #define SCK DIO7
#define OC0A DIO3 #define MISO DIO6
#define OC0B DIO4 #define MOSI DIO5
#define OC1A DIO13 #define SS DIO4
#define OC1B DIO12
#define OC2A DIO15 // TWI (I2C)
#define OC2B DIO14 #define SCL DIO16
#define SDA DIO17
#define DEBUG_LED DIO0
/* // timers and PWM
pins #define OC0A DIO3
*/ #define OC0B DIO4
#define OC1A DIO13
#define DIO0_PIN PINB0 #define OC1B DIO12
#define DIO0_RPORT PINB #define OC2A DIO15
#define DIO0_WPORT PORTB #define OC2B DIO14
#define DIO0_DDR DDRB
#define DIO0_PWM NULL #define DEBUG_LED DIO0
/*
#define DIO1_PIN PINB1 pins
#define DIO1_RPORT PINB */
#define DIO1_WPORT PORTB
#define DIO1_DDR DDRB #define DIO0_PIN PINB0
#define DIO1_PWM NULL #define DIO0_RPORT PINB
#define DIO0_WPORT PORTB
#define DIO2_PIN PINB2 #define DIO0_DDR DDRB
#define DIO2_RPORT PINB #define DIO0_PWM NULL
#define DIO2_WPORT PORTB
#define DIO2_DDR DDRB #define DIO1_PIN PINB1
#define DIO2_PWM NULL #define DIO1_RPORT PINB
#define DIO1_WPORT PORTB
#define DIO3_PIN PINB3 #define DIO1_DDR DDRB
#define DIO3_RPORT PINB #define DIO1_PWM NULL
#define DIO3_WPORT PORTB
#define DIO3_DDR DDRB #define DIO2_PIN PINB2
#define DIO3_PWM &OCR0A #define DIO2_RPORT PINB
#define DIO2_WPORT PORTB
#define DIO4_PIN PINB4 #define DIO2_DDR DDRB
#define DIO4_RPORT PINB #define DIO2_PWM NULL
#define DIO4_WPORT PORTB
#define DIO4_DDR DDRB #define DIO3_PIN PINB3
#define DIO4_PWM &OCR0B #define DIO3_RPORT PINB
#define DIO3_WPORT PORTB
#define DIO5_PIN PINB5 #define DIO3_DDR DDRB
#define DIO5_RPORT PINB #define DIO3_PWM OCR0A
#define DIO5_WPORT PORTB
#define DIO5_DDR DDRB #define DIO4_PIN PINB4
#define DIO5_PWM NULL #define DIO4_RPORT PINB
#define DIO4_WPORT PORTB
#define DIO6_PIN PINB6 #define DIO4_DDR DDRB
#define DIO6_RPORT PINB #define DIO4_PWM OCR0B
#define DIO6_WPORT PORTB
#define DIO6_DDR DDRB #define DIO5_PIN PINB5
#define DIO6_PWM NULL #define DIO5_RPORT PINB
#define DIO5_WPORT PORTB
#define DIO7_PIN PINB7 #define DIO5_DDR DDRB
#define DIO7_RPORT PINB #define DIO5_PWM NULL
#define DIO7_WPORT PORTB
#define DIO7_DDR DDRB #define DIO6_PIN PINB6
#define DIO7_PWM NULL #define DIO6_RPORT PINB
#define DIO6_WPORT PORTB
#define DIO8_PIN PIND0 #define DIO6_DDR DDRB
#define DIO8_RPORT PIND #define DIO6_PWM NULL
#define DIO8_WPORT PORTD
#define DIO8_DDR DDRD #define DIO7_PIN PINB7
#define DIO8_PWM NULL #define DIO7_RPORT PINB
#define DIO7_WPORT PORTB
#define DIO9_PIN PIND1 #define DIO7_DDR DDRB
#define DIO9_RPORT PIND #define DIO7_PWM NULL
#define DIO9_WPORT PORTD
#define DIO9_DDR DDRD #define DIO8_PIN PIND0
#define DIO9_PWM NULL #define DIO8_RPORT PIND
#define DIO8_WPORT PORTD
#define DIO10_PIN PIND2 #define DIO8_DDR DDRD
#define DIO10_RPORT PIND #define DIO8_PWM NULL
#define DIO10_WPORT PORTD
#define DIO10_DDR DDRD #define DIO9_PIN PIND1
#define DIO10_PWM NULL #define DIO9_RPORT PIND
#define DIO9_WPORT PORTD
#define DIO11_PIN PIND3 #define DIO9_DDR DDRD
#define DIO11_RPORT PIND #define DIO9_PWM NULL
#define DIO11_WPORT PORTD
#define DIO11_DDR DDRD #define DIO10_PIN PIND2
#define DIO11_PWM NULL #define DIO10_RPORT PIND
#define DIO10_WPORT PORTD
#define DIO12_PIN PIND4 #define DIO10_DDR DDRD
#define DIO12_RPORT PIND #define DIO10_PWM NULL
#define DIO12_WPORT PORTD
#define DIO12_DDR DDRD #define DIO11_PIN PIND3
#define DIO12_PWM NULL #define DIO11_RPORT PIND
#define DIO11_WPORT PORTD
#define DIO13_PIN PIND5 #define DIO11_DDR DDRD
#define DIO13_RPORT PIND #define DIO11_PWM NULL
#define DIO13_WPORT PORTD
#define DIO13_DDR DDRD #define DIO12_PIN PIND4
#define DIO13_PWM NULL #define DIO12_RPORT PIND
#define DIO12_WPORT PORTD
#define DIO14_PIN PIND6 #define DIO12_DDR DDRD
#define DIO14_RPORT PIND #define DIO12_PWM OCR1B
#define DIO14_WPORT PORTD
#define DIO14_DDR DDRD #define DIO13_PIN PIND5
#define DIO14_PWM &OCR2B #define DIO13_RPORT PIND
#define DIO13_WPORT PORTD
#define DIO15_PIN PIND7 #define DIO13_DDR DDRD
#define DIO15_RPORT PIND #define DIO13_PWM OCR1A
#define DIO15_WPORT PORTD
#define DIO15_DDR DDRD #define DIO14_PIN PIND6
#define DIO15_PWM &OCR2A #define DIO14_RPORT PIND
#define DIO14_WPORT PORTD
#define DIO16_PIN PINC0 #define DIO14_DDR DDRD
#define DIO16_RPORT PINC #define DIO14_PWM OCR2B
#define DIO16_WPORT PORTC
#define DIO16_DDR DDRC #define DIO15_PIN PIND7
#define DIO16_PWM NULL #define DIO15_RPORT PIND
#define DIO15_WPORT PORTD
#define DIO17_PIN PINC1 #define DIO15_DDR DDRD
#define DIO17_RPORT PINC #define DIO15_PWM OCR2A
#define DIO17_WPORT PORTC
#define DIO17_DDR DDRC #define DIO16_PIN PINC0
#define DIO17_PWM NULL #define DIO16_RPORT PINC
#define DIO16_WPORT PORTC
#define DIO18_PIN PINC2 #define DIO16_DDR DDRC
#define DIO18_RPORT PINC #define DIO16_PWM NULL
#define DIO18_WPORT PORTC
#define DIO18_DDR DDRC #define DIO17_PIN PINC1
#define DIO18_PWM NULL #define DIO17_RPORT PINC
#define DIO17_WPORT PORTC
#define DIO19_PIN PINC3 #define DIO17_DDR DDRC
#define DIO19_RPORT PINC #define DIO17_PWM NULL
#define DIO19_WPORT PORTC
#define DIO19_DDR DDRC #define DIO18_PIN PINC2
#define DIO19_PWM NULL #define DIO18_RPORT PINC
#define DIO18_WPORT PORTC
#define DIO20_PIN PINC4 #define DIO18_DDR DDRC
#define DIO20_RPORT PINC #define DIO18_PWM NULL
#define DIO20_WPORT PORTC
#define DIO20_DDR DDRC #define DIO19_PIN PINC3
#define DIO20_PWM NULL #define DIO19_RPORT PINC
#define DIO19_WPORT PORTC
#define DIO21_PIN PINC5 #define DIO19_DDR DDRC
#define DIO21_RPORT PINC #define DIO19_PWM NULL
#define DIO21_WPORT PORTC
#define DIO21_DDR DDRC #define DIO20_PIN PINC4
#define DIO21_PWM NULL #define DIO20_RPORT PINC
#define DIO20_WPORT PORTC
#define DIO22_PIN PINC6 #define DIO20_DDR DDRC
#define DIO22_RPORT PINC #define DIO20_PWM NULL
#define DIO22_WPORT PORTC
#define DIO22_DDR DDRC #define DIO21_PIN PINC5
#define DIO22_PWM NULL #define DIO21_RPORT PINC
#define DIO21_WPORT PORTC
#define DIO23_PIN PINC7 #define DIO21_DDR DDRC
#define DIO23_RPORT PINC #define DIO21_PWM NULL
#define DIO23_WPORT PORTC
#define DIO23_DDR DDRC #define DIO22_PIN PINC6
#define DIO23_PWM NULL #define DIO22_RPORT PINC
#define DIO22_WPORT PORTC
#define DIO24_PIN PINA7 #define DIO22_DDR DDRC
#define DIO24_RPORT PINA #define DIO22_PWM NULL
#define DIO24_WPORT PORTA
#define DIO24_DDR DDRA #define DIO23_PIN PINC7
#define DIO24_PWM NULL #define DIO23_RPORT PINC
#define DIO23_WPORT PORTC
#define DIO25_PIN PINA6 #define DIO23_DDR DDRC
#define DIO25_RPORT PINA #define DIO23_PWM NULL
#define DIO25_WPORT PORTA
#define DIO25_DDR DDRA #define DIO24_PIN PINA7
#define DIO25_PWM NULL #define DIO24_RPORT PINA
#define DIO24_WPORT PORTA
#define DIO26_PIN PINA5 #define DIO24_DDR DDRA
#define DIO26_RPORT PINA #define DIO24_PWM NULL
#define DIO26_WPORT PORTA
#define DIO26_DDR DDRA #define DIO25_PIN PINA6
#define DIO26_PWM NULL #define DIO25_RPORT PINA
#define DIO25_WPORT PORTA
#define DIO27_PIN PINA4 #define DIO25_DDR DDRA
#define DIO27_RPORT PINA #define DIO25_PWM NULL
#define DIO27_WPORT PORTA
#define DIO27_DDR DDRA #define DIO26_PIN PINA5
#define DIO27_PWM NULL #define DIO26_RPORT PINA
#define DIO26_WPORT PORTA
#define DIO28_PIN PINA3 #define DIO26_DDR DDRA
#define DIO28_RPORT PINA #define DIO26_PWM NULL
#define DIO28_WPORT PORTA
#define DIO28_DDR DDRA #define DIO27_PIN PINA4
#define DIO28_PWM NULL #define DIO27_RPORT PINA
#define DIO27_WPORT PORTA
#define DIO29_PIN PINA2 #define DIO27_DDR DDRA
#define DIO29_RPORT PINA #define DIO27_PWM NULL
#define DIO29_WPORT PORTA
#define DIO29_DDR DDRA #define DIO28_PIN PINA3
#define DIO29_PWM NULL #define DIO28_RPORT PINA
#define DIO28_WPORT PORTA
#define DIO30_PIN PINA1 #define DIO28_DDR DDRA
#define DIO30_RPORT PINA #define DIO28_PWM NULL
#define DIO30_WPORT PORTA
#define DIO30_DDR DDRA #define DIO29_PIN PINA2
#define DIO30_PWM NULL #define DIO29_RPORT PINA
#define DIO29_WPORT PORTA
#define DIO31_PIN PINA0 #define DIO29_DDR DDRA
#define DIO31_RPORT PINA #define DIO29_PWM NULL
#define DIO31_WPORT PORTA
#define DIO31_DDR DDRA #define DIO30_PIN PINA1
#define DIO31_PWM NULL #define DIO30_RPORT PINA
#define DIO30_WPORT PORTA
#define AIO0_PIN PINA0 #define DIO30_DDR DDRA
#define AIO0_RPORT PINA #define DIO30_PWM NULL
#define AIO0_WPORT PORTA
#define AIO0_DDR DDRA #define DIO31_PIN PINA0
#define AIO0_PWM NULL #define DIO31_RPORT PINA
#define DIO31_WPORT PORTA
#define AIO1_PIN PINA1 #define DIO31_DDR DDRA
#define AIO1_RPORT PINA #define DIO31_PWM NULL
#define AIO1_WPORT PORTA
#define AIO1_DDR DDRA #define AIO0_PIN PINA0
#define AIO1_PWM NULL #define AIO0_RPORT PINA
#define AIO0_WPORT PORTA
#define AIO2_PIN PINA2 #define AIO0_DDR DDRA
#define AIO2_RPORT PINA #define AIO0_PWM NULL
#define AIO2_WPORT PORTA
#define AIO2_DDR DDRA #define AIO1_PIN PINA1
#define AIO2_PWM NULL #define AIO1_RPORT PINA
#define AIO1_WPORT PORTA
#define AIO3_PIN PINA3 #define AIO1_DDR DDRA
#define AIO3_RPORT PINA #define AIO1_PWM NULL
#define AIO3_WPORT PORTA
#define AIO3_DDR DDRA #define AIO2_PIN PINA2
#define AIO3_PWM NULL #define AIO2_RPORT PINA
#define AIO2_WPORT PORTA
#define AIO4_PIN PINA4 #define AIO2_DDR DDRA
#define AIO4_RPORT PINA #define AIO2_PWM NULL
#define AIO4_WPORT PORTA
#define AIO4_DDR DDRA #define AIO3_PIN PINA3
#define AIO4_PWM NULL #define AIO3_RPORT PINA
#define AIO3_WPORT PORTA
#define AIO5_PIN PINA5 #define AIO3_DDR DDRA
#define AIO5_RPORT PINA #define AIO3_PWM NULL
#define AIO5_WPORT PORTA
#define AIO5_DDR DDRA #define AIO4_PIN PINA4
#define AIO5_PWM NULL #define AIO4_RPORT PINA
#define AIO4_WPORT PORTA
#define AIO6_PIN PINA6 #define AIO4_DDR DDRA
#define AIO6_RPORT PINA #define AIO4_PWM NULL
#define AIO6_WPORT PORTA
#define AIO6_DDR DDRA #define AIO5_PIN PINA5
#define AIO6_PWM NULL #define AIO5_RPORT PINA
#define AIO5_WPORT PORTA
#define AIO7_PIN PINA7 #define AIO5_DDR DDRA
#define AIO7_RPORT PINA #define AIO5_PWM NULL
#define AIO7_WPORT PORTA
#define AIO7_DDR DDRA #define AIO6_PIN PINA6
#define AIO7_PWM NULL #define AIO6_RPORT PINA
#define AIO6_WPORT PORTA
#define AIO6_DDR DDRA
#define AIO6_PWM NULL
#undef PA0
#define PA0_PIN PINA0 #define AIO7_PIN PINA7
#define PA0_RPORT PINA #define AIO7_RPORT PINA
#define PA0_WPORT PORTA #define AIO7_WPORT PORTA
#define PA0_DDR DDRA #define AIO7_DDR DDRA
#define PA0_PWM NULL #define AIO7_PWM NULL
#undef PA1
#define PA1_PIN PINA1
#define PA1_RPORT PINA #undef PA0
#define PA1_WPORT PORTA #define PA0_PIN PINA0
#define PA1_DDR DDRA #define PA0_RPORT PINA
#define PA1_PWM NULL #define PA0_WPORT PORTA
#define PA0_DDR DDRA
#undef PA2 #define PA0_PWM NULL
#define PA2_PIN PINA2
#define PA2_RPORT PINA #undef PA1
#define PA2_WPORT PORTA #define PA1_PIN PINA1
#define PA2_DDR DDRA #define PA1_RPORT PINA
#define PA2_PWM NULL #define PA1_WPORT PORTA
#define PA1_DDR DDRA
#undef PA3 #define PA1_PWM NULL
#define PA3_PIN PINA3
#define PA3_RPORT PINA #undef PA2
#define PA3_WPORT PORTA #define PA2_PIN PINA2
#define PA3_DDR DDRA #define PA2_RPORT PINA
#define PA3_PWM NULL #define PA2_WPORT PORTA
#define PA2_DDR DDRA
#undef PA4 #define PA2_PWM NULL
#define PA4_PIN PINA4
#define PA4_RPORT PINA #undef PA3
#define PA4_WPORT PORTA #define PA3_PIN PINA3
#define PA4_DDR DDRA #define PA3_RPORT PINA
#define PA4_PWM NULL #define PA3_WPORT PORTA
#define PA3_DDR DDRA
#undef PA5 #define PA3_PWM NULL
#define PA5_PIN PINA5
#define PA5_RPORT PINA #undef PA4
#define PA5_WPORT PORTA #define PA4_PIN PINA4
#define PA5_DDR DDRA #define PA4_RPORT PINA
#define PA5_PWM NULL #define PA4_WPORT PORTA
#define PA4_DDR DDRA
#undef PA6 #define PA4_PWM NULL
#define PA6_PIN PINA6
#define PA6_RPORT PINA #undef PA5
#define PA6_WPORT PORTA #define PA5_PIN PINA5
#define PA6_DDR DDRA #define PA5_RPORT PINA
#define PA6_PWM NULL #define PA5_WPORT PORTA
#define PA5_DDR DDRA
#undef PA7 #define PA5_PWM NULL
#define PA7_PIN PINA7
#define PA7_RPORT PINA #undef PA6
#define PA7_WPORT PORTA #define PA6_PIN PINA6
#define PA7_DDR DDRA #define PA6_RPORT PINA
#define PA7_PWM NULL #define PA6_WPORT PORTA
#define PA6_DDR DDRA
#define PA6_PWM NULL
#undef PB0
#define PB0_PIN PINB0 #undef PA7
#define PB0_RPORT PINB #define PA7_PIN PINA7
#define PB0_WPORT PORTB #define PA7_RPORT PINA
#define PB0_DDR DDRB #define PA7_WPORT PORTA
#define PB0_PWM NULL #define PA7_DDR DDRA
#define PA7_PWM NULL
#undef PB1
#define PB1_PIN PINB1
#define PB1_RPORT PINB #undef PB0
#define PB1_WPORT PORTB #define PB0_PIN PINB0
#define PB1_DDR DDRB #define PB0_RPORT PINB
#define PB1_PWM NULL #define PB0_WPORT PORTB
#define PB0_DDR DDRB
#undef PB2 #define PB0_PWM NULL
#define PB2_PIN PINB2
#define PB2_RPORT PINB #undef PB1
#define PB2_WPORT PORTB #define PB1_PIN PINB1
#define PB2_DDR DDRB #define PB1_RPORT PINB
#define PB2_PWM NULL #define PB1_WPORT PORTB
#define PB1_DDR DDRB
#undef PB3 #define PB1_PWM NULL
#define PB3_PIN PINB3
#define PB3_RPORT PINB #undef PB2
#define PB3_WPORT PORTB #define PB2_PIN PINB2
#define PB3_DDR DDRB #define PB2_RPORT PINB
#define PB3_PWM &OCR0A #define PB2_WPORT PORTB
#define PB2_DDR DDRB
#undef PB4 #define PB2_PWM NULL
#define PB4_PIN PINB4
#define PB4_RPORT PINB #undef PB3
#define PB4_WPORT PORTB #define PB3_PIN PINB3
#define PB4_DDR DDRB #define PB3_RPORT PINB
#define PB4_PWM &OCR0B #define PB3_WPORT PORTB
#define PB3_DDR DDRB
#undef PB5 #define PB3_PWM OCR0A
#define PB5_PIN PINB5
#define PB5_RPORT PINB #undef PB4
#define PB5_WPORT PORTB #define PB4_PIN PINB4
#define PB5_DDR DDRB #define PB4_RPORT PINB
#define PB5_PWM NULL #define PB4_WPORT PORTB
#define PB4_DDR DDRB
#undef PB6 #define PB4_PWM OCR0B
#define PB6_PIN PINB6
#define PB6_RPORT PINB #undef PB5
#define PB6_WPORT PORTB #define PB5_PIN PINB5
#define PB6_DDR DDRB #define PB5_RPORT PINB
#define PB6_PWM NULL #define PB5_WPORT PORTB
#define PB5_DDR DDRB
#undef PB7 #define PB5_PWM NULL
#define PB7_PIN PINB7
#define PB7_RPORT PINB #undef PB6
#define PB7_WPORT PORTB #define PB6_PIN PINB6
#define PB7_DDR DDRB #define PB6_RPORT PINB
#define PB7_PWM NULL #define PB6_WPORT PORTB
#define PB6_DDR DDRB
#define PB6_PWM NULL
#undef PC0
#define PC0_PIN PINC0 #undef PB7
#define PC0_RPORT PINC #define PB7_PIN PINB7
#define PC0_WPORT PORTC #define PB7_RPORT PINB
#define PC0_DDR DDRC #define PB7_WPORT PORTB
#define PC0_PWM NULL #define PB7_DDR DDRB
#define PB7_PWM NULL
#undef PC1
#define PC1_PIN PINC1
#define PC1_RPORT PINC #undef PC0
#define PC1_WPORT PORTC #define PC0_PIN PINC0
#define PC1_DDR DDRC #define PC0_RPORT PINC
#define PC1_PWM NULL #define PC0_WPORT PORTC
#define PC0_DDR DDRC
#undef PC2 #define PC0_PWM NULL
#define PC2_PIN PINC2
#define PC2_RPORT PINC #undef PC1
#define PC2_WPORT PORTC #define PC1_PIN PINC1
#define PC2_DDR DDRC #define PC1_RPORT PINC
#define PC2_PWM NULL #define PC1_WPORT PORTC
#define PC1_DDR DDRC
#undef PC3 #define PC1_PWM NULL
#define PC3_PIN PINC3
#define PC3_RPORT PINC #undef PC2
#define PC3_WPORT PORTC #define PC2_PIN PINC2
#define PC3_DDR DDRC #define PC2_RPORT PINC
#define PC3_PWM NULL #define PC2_WPORT PORTC
#define PC2_DDR DDRC
#undef PC4 #define PC2_PWM NULL
#define PC4_PIN PINC4
#define PC4_RPORT PINC #undef PC3
#define PC4_WPORT PORTC #define PC3_PIN PINC3
#define PC4_DDR DDRC #define PC3_RPORT PINC
#define PC4_PWM NULL #define PC3_WPORT PORTC
#define PC3_DDR DDRC
#undef PC5 #define PC3_PWM NULL
#define PC5_PIN PINC5
#define PC5_RPORT PINC #undef PC4
#define PC5_WPORT PORTC #define PC4_PIN PINC4
#define PC5_DDR DDRC #define PC4_RPORT PINC
#define PC5_PWM NULL #define PC4_WPORT PORTC
#define PC4_DDR DDRC
#undef PC6 #define PC4_PWM NULL
#define PC6_PIN PINC6
#define PC6_RPORT PINC #undef PC5
#define PC6_WPORT PORTC #define PC5_PIN PINC5
#define PC6_DDR DDRC #define PC5_RPORT PINC
#define PC6_PWM NULL #define PC5_WPORT PORTC
#define PC5_DDR DDRC
#undef PC7 #define PC5_PWM NULL
#define PC7_PIN PINC7
#define PC7_RPORT PINC #undef PC6
#define PC7_WPORT PORTC #define PC6_PIN PINC6
#define PC7_DDR DDRC #define PC6_RPORT PINC
#define PC7_PWM NULL #define PC6_WPORT PORTC
#define PC6_DDR DDRC
#define PC6_PWM NULL
#undef PD0
#define PD0_PIN PIND0 #undef PC7
#define PD0_RPORT PIND #define PC7_PIN PINC7
#define PD0_WPORT PORTD #define PC7_RPORT PINC
#define PD0_DDR DDRD #define PC7_WPORT PORTC
#define PD0_PWM NULL #define PC7_DDR DDRC
#define PC7_PWM NULL
#undef PD1
#define PD1_PIN PIND1
#define PD1_RPORT PIND #undef PD0
#define PD1_WPORT PORTD #define PD0_PIN PIND0
#define PD1_DDR DDRD #define PD0_RPORT PIND
#define PD1_PWM NULL #define PD0_WPORT PORTD
#define PD0_DDR DDRD
#undef PD2 #define PD0_PWM NULL
#define PD2_PIN PIND2
#define PD2_RPORT PIND #undef PD1
#define PD2_WPORT PORTD #define PD1_PIN PIND1
#define PD2_DDR DDRD #define PD1_RPORT PIND
#define PD2_PWM NULL #define PD1_WPORT PORTD
#define PD1_DDR DDRD
#undef PD3 #define PD1_PWM NULL
#define PD3_PIN PIND3
#define PD3_RPORT PIND #undef PD2
#define PD3_WPORT PORTD #define PD2_PIN PIND2
#define PD3_DDR DDRD #define PD2_RPORT PIND
#define PD3_PWM NULL #define PD2_WPORT PORTD
#define PD2_DDR DDRD
#undef PD4 #define PD2_PWM NULL
#define PD4_PIN PIND4
#define PD4_RPORT PIND #undef PD3
#define PD4_WPORT PORTD #define PD3_PIN PIND3
#define PD4_DDR DDRD #define PD3_RPORT PIND
#define PD4_PWM NULL #define PD3_WPORT PORTD
#define PD3_DDR DDRD
#undef PD5 #define PD3_PWM NULL
#define PD5_PIN PIND5
#define PD5_RPORT PIND #undef PD4
#define PD5_WPORT PORTD #define PD4_PIN PIND4
#define PD5_DDR DDRD #define PD4_RPORT PIND
#define PD5_PWM NULL #define PD4_WPORT PORTD
#define PD4_DDR DDRD
#undef PD6 #define PD4_PWM NULL
#define PD6_PIN PIND6
#define PD6_RPORT PIND #undef PD5
#define PD6_WPORT PORTD #define PD5_PIN PIND5
#define PD6_DDR DDRD #define PD5_RPORT PIND
#define PD6_PWM &OCR2B #define PD5_WPORT PORTD
#define PD5_DDR DDRD
#undef PD7 #define PD5_PWM NULL
#define PD7_PIN PIND7
#define PD7_RPORT PIND #undef PD6
#define PD7_WPORT PORTD #define PD6_PIN PIND6
#define PD7_DDR DDRD #define PD6_RPORT PIND
#define PD7_PWM &OCR2A #define PD6_WPORT PORTD
#endif /* _AVR_ATmega{644,644P,644PA}__ */ #define PD6_DDR DDRD
#define PD6_PWM OCR2B
#if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
// UART #undef PD7
#define RXD DIO0 #define PD7_PIN PIND7
#define TXD DIO1 #define PD7_RPORT PIND
#define PD7_WPORT PORTD
// SPI #define PD7_DDR DDRD
#define SCK DIO52 #define PD7_PWM OCR2A
#define MISO DIO50 #endif /* _AVR_ATmega{644,644P,644PA}__ */
#define MOSI DIO51
#define SS DIO53 #if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
// UART
// TWI (I2C) #define RXD DIO0
#define SCL DIO21 #define TXD DIO1
#define SDA DIO20
// SPI
// timers and PWM #define SCK DIO52
#define OC0A DIO13 #define MISO DIO50
#define OC0B DIO4 #define MOSI DIO51
#define OC1A DIO11 #define SS DIO53
#define OC1B DIO12
#define OC2A DIO10 // TWI (I2C)
#define OC2B DIO9 #define SCL DIO21
#define OC3A DIO5 #define SDA DIO20
#define OC3B DIO2
#define OC3C DIO3 // timers and PWM
#define OC4A DIO6 #define OC0A DIO13
#define OC4B DIO7 #define OC0B DIO4
#define OC4C DIO8 #define OC1A DIO11
#define OC5A DIO46 #define OC1B DIO12
#define OC5B DIO45 #define OC2A DIO10
#define OC5C DIO44 #define OC2B DIO9
#define OC3A DIO5
// change for your board #define OC3B DIO2
#define DEBUG_LED DIO21 #define OC3C DIO3
#define OC4A DIO6
/* #define OC4B DIO7
pins #define OC4C DIO8
*/ #define OC5A DIO46
#define DIO0_PIN PINE0 #define OC5B DIO45
#define DIO0_RPORT PINE #define OC5C DIO44
#define DIO0_WPORT PORTE
#define DIO0_DDR DDRE // change for your board
#define DIO0_PWM NULL #define DEBUG_LED DIO21
#define DIO1_PIN PINE1 /*
#define DIO1_RPORT PINE pins
#define DIO1_WPORT PORTE */
#define DIO1_DDR DDRE #define DIO0_PIN PINE0
#define DIO1_PWM NULL #define DIO0_RPORT PINE
#define DIO0_WPORT PORTE
#define DIO2_PIN PINE4 #define DIO0_DDR DDRE
#define DIO2_RPORT PINE #define DIO0_PWM NULL
#define DIO2_WPORT PORTE
#define DIO2_DDR DDRE #define DIO1_PIN PINE1
#define DIO2_PWM &OCR3BL #define DIO1_RPORT PINE
#define DIO1_WPORT PORTE
#define DIO3_PIN PINE5 #define DIO1_DDR DDRE
#define DIO3_RPORT PINE #define DIO1_PWM NULL
#define DIO3_WPORT PORTE
#define DIO3_DDR DDRE #define DIO2_PIN PINE4
#define DIO3_PWM &OCR3CL #define DIO2_RPORT PINE
#define DIO2_WPORT PORTE
#define DIO4_PIN PING5 #define DIO2_DDR DDRE
#define DIO4_RPORT PING #define DIO2_PWM &OCR3BL
#define DIO4_WPORT PORTG
#define DIO4_DDR DDRG #define DIO3_PIN PINE5
#define DIO4_PWM &OCR0B #define DIO3_RPORT PINE
#define DIO3_WPORT PORTE
#define DIO5_PIN PINE3 #define DIO3_DDR DDRE
#define DIO5_RPORT PINE #define DIO3_PWM &OCR3CL
#define DIO5_WPORT PORTE
#define DIO5_DDR DDRE #define DIO4_PIN PING5
#define DIO5_PWM &OCR3AL #define DIO4_RPORT PING
#define DIO4_WPORT PORTG
#define DIO6_PIN PINH3 #define DIO4_DDR DDRG
#define DIO6_RPORT PINH #define DIO4_PWM &OCR0B
#define DIO6_WPORT PORTH
#define DIO6_DDR DDRH #define DIO5_PIN PINE3
#define DIO6_PWM &OCR4AL #define DIO5_RPORT PINE
#define DIO5_WPORT PORTE
#define DIO7_PIN PINH4 #define DIO5_DDR DDRE
#define DIO7_RPORT PINH #define DIO5_PWM &OCR3AL
#define DIO7_WPORT PORTH
#define DIO7_DDR DDRH #define DIO6_PIN PINH3
#define DIO7_PWM &OCR4BL #define DIO6_RPORT PINH
#define DIO6_WPORT PORTH
#define DIO8_PIN PINH5 #define DIO6_DDR DDRH
#define DIO8_RPORT PINH #define DIO6_PWM &OCR4AL
#define DIO8_WPORT PORTH
#define DIO8_DDR DDRH #define DIO7_PIN PINH4
#define DIO8_PWM &OCR4CL #define DIO7_RPORT PINH
#define DIO7_WPORT PORTH
#define DIO9_PIN PINH6 #define DIO7_DDR DDRH
#define DIO9_RPORT PINH #define DIO7_PWM &OCR4BL
#define DIO9_WPORT PORTH
#define DIO9_DDR DDRH #define DIO8_PIN PINH5
#define DIO9_PWM &OCR2B #define DIO8_RPORT PINH
#define DIO8_WPORT PORTH
#define DIO10_PIN PINB4 #define DIO8_DDR DDRH
#define DIO10_RPORT PINB #define DIO8_PWM &OCR4CL
#define DIO10_WPORT PORTB
#define DIO10_DDR DDRB #define DIO9_PIN PINH6
#define DIO10_PWM &OCR2A #define DIO9_RPORT PINH
#define DIO9_WPORT PORTH
#define DIO11_PIN PINB5 #define DIO9_DDR DDRH
#define DIO11_RPORT PINB #define DIO9_PWM &OCR2B
#define DIO11_WPORT PORTB
#define DIO11_DDR DDRB #define DIO10_PIN PINB4
#define DIO11_PWM NULL #define DIO10_RPORT PINB
#define DIO10_WPORT PORTB
#define DIO12_PIN PINB6 #define DIO10_DDR DDRB
#define DIO12_RPORT PINB #define DIO10_PWM &OCR2A
#define DIO12_WPORT PORTB
#define DIO12_DDR DDRB #define DIO11_PIN PINB5
#define DIO12_PWM NULL #define DIO11_RPORT PINB
#define DIO11_WPORT PORTB
#define DIO13_PIN PINB7 #define DIO11_DDR DDRB
#define DIO13_RPORT PINB #define DIO11_PWM NULL
#define DIO13_WPORT PORTB
#define DIO13_DDR DDRB #define DIO12_PIN PINB6
#define DIO13_PWM &OCR0A #define DIO12_RPORT PINB
#define DIO12_WPORT PORTB
#define DIO14_PIN PINJ1 #define DIO12_DDR DDRB
#define DIO14_RPORT PINJ #define DIO12_PWM NULL
#define DIO14_WPORT PORTJ
#define DIO14_DDR DDRJ #define DIO13_PIN PINB7
#define DIO14_PWM NULL #define DIO13_RPORT PINB
#define DIO13_WPORT PORTB
#define DIO15_PIN PINJ0 #define DIO13_DDR DDRB
#define DIO15_RPORT PINJ #define DIO13_PWM &OCR0A
#define DIO15_WPORT PORTJ
#define DIO15_DDR DDRJ #define DIO14_PIN PINJ1
#define DIO15_PWM NULL #define DIO14_RPORT PINJ
#define DIO14_WPORT PORTJ
#define DIO16_PIN PINH1 #define DIO14_DDR DDRJ
#define DIO16_RPORT PINH #define DIO14_PWM NULL
#define DIO16_WPORT PORTH
#define DIO16_DDR DDRH #define DIO15_PIN PINJ0
#define DIO16_PWM NULL #define DIO15_RPORT PINJ
#define DIO15_WPORT PORTJ
#define DIO17_PIN PINH0 #define DIO15_DDR DDRJ
#define DIO17_RPORT PINH #define DIO15_PWM NULL
#define DIO17_WPORT PORTH
#define DIO17_DDR DDRH #define DIO16_PIN PINH1
#define DIO17_PWM NULL #define DIO16_RPORT PINH
#define DIO16_WPORT PORTH
#define DIO18_PIN PIND3 #define DIO16_DDR DDRH
#define DIO18_RPORT PIND #define DIO16_PWM NULL
#define DIO18_WPORT PORTD
#define DIO18_DDR DDRD #define DIO17_PIN PINH0
#define DIO18_PWM NULL #define DIO17_RPORT PINH
#define DIO17_WPORT PORTH
#define DIO19_PIN PIND2 #define DIO17_DDR DDRH
#define DIO19_RPORT PIND #define DIO17_PWM NULL
#define DIO19_WPORT PORTD
#define DIO19_DDR DDRD #define DIO18_PIN PIND3
#define DIO19_PWM NULL #define DIO18_RPORT PIND
#define DIO18_WPORT PORTD
#define DIO20_PIN PIND1 #define DIO18_DDR DDRD
#define DIO20_RPORT PIND #define DIO18_PWM NULL
#define DIO20_WPORT PORTD
#define DIO20_DDR DDRD #define DIO19_PIN PIND2
#define DIO20_PWM NULL #define DIO19_RPORT PIND
#define DIO19_WPORT PORTD
#define DIO21_PIN PIND0 #define DIO19_DDR DDRD
#define DIO21_RPORT PIND #define DIO19_PWM NULL
#define DIO21_WPORT PORTD
#define DIO21_DDR DDRD #define DIO20_PIN PIND1
#define DIO21_PWM NULL #define DIO20_RPORT PIND
#define DIO20_WPORT PORTD
#define DIO22_PIN PINA0 #define DIO20_DDR DDRD
#define DIO22_RPORT PINA #define DIO20_PWM NULL
#define DIO22_WPORT PORTA
#define DIO22_DDR DDRA #define DIO21_PIN PIND0
#define DIO22_PWM NULL #define DIO21_RPORT PIND
#define DIO21_WPORT PORTD
#define DIO23_PIN PINA1 #define DIO21_DDR DDRD
#define DIO23_RPORT PINA #define DIO21_PWM NULL
#define DIO23_WPORT PORTA
#define DIO23_DDR DDRA #define DIO22_PIN PINA0
#define DIO23_PWM NULL #define DIO22_RPORT PINA
#define DIO22_WPORT PORTA
#define DIO24_PIN PINA2 #define DIO22_DDR DDRA
#define DIO24_RPORT PINA #define DIO22_PWM NULL
#define DIO24_WPORT PORTA
#define DIO24_DDR DDRA #define DIO23_PIN PINA1
#define DIO24_PWM NULL #define DIO23_RPORT PINA
#define DIO23_WPORT PORTA
#define DIO25_PIN PINA3 #define DIO23_DDR DDRA
#define DIO25_RPORT PINA #define DIO23_PWM NULL
#define DIO25_WPORT PORTA
#define DIO25_DDR DDRA #define DIO24_PIN PINA2
#define DIO25_PWM NULL #define DIO24_RPORT PINA
#define DIO24_WPORT PORTA
#define DIO26_PIN PINA4 #define DIO24_DDR DDRA
#define DIO26_RPORT PINA #define DIO24_PWM NULL
#define DIO26_WPORT PORTA
#define DIO26_DDR DDRA #define DIO25_PIN PINA3
#define DIO26_PWM NULL #define DIO25_RPORT PINA
#define DIO25_WPORT PORTA
#define DIO27_PIN PINA5 #define DIO25_DDR DDRA
#define DIO27_RPORT PINA #define DIO25_PWM NULL
#define DIO27_WPORT PORTA
#define DIO27_DDR DDRA #define DIO26_PIN PINA4
#define DIO27_PWM NULL #define DIO26_RPORT PINA
#define DIO26_WPORT PORTA
#define DIO28_PIN PINA6 #define DIO26_DDR DDRA
#define DIO28_RPORT PINA #define DIO26_PWM NULL
#define DIO28_WPORT PORTA
#define DIO28_DDR DDRA #define DIO27_PIN PINA5
#define DIO28_PWM NULL #define DIO27_RPORT PINA
#define DIO27_WPORT PORTA
#define DIO29_PIN PINA7 #define DIO27_DDR DDRA
#define DIO29_RPORT PINA #define DIO27_PWM NULL
#define DIO29_WPORT PORTA
#define DIO29_DDR DDRA #define DIO28_PIN PINA6
#define DIO29_PWM NULL #define DIO28_RPORT PINA
#define DIO28_WPORT PORTA
#define DIO30_PIN PINC7 #define DIO28_DDR DDRA
#define DIO30_RPORT PINC #define DIO28_PWM NULL
#define DIO30_WPORT PORTC
#define DIO30_DDR DDRC #define DIO29_PIN PINA7
#define DIO30_PWM NULL #define DIO29_RPORT PINA
#define DIO29_WPORT PORTA
#define DIO31_PIN PINC6 #define DIO29_DDR DDRA
#define DIO31_RPORT PINC #define DIO29_PWM NULL
#define DIO31_WPORT PORTC
#define DIO31_DDR DDRC #define DIO30_PIN PINC7
#define DIO31_PWM NULL #define DIO30_RPORT PINC
#define DIO30_WPORT PORTC
#define DIO32_PIN PINC5 #define DIO30_DDR DDRC
#define DIO32_RPORT PINC #define DIO30_PWM NULL
#define DIO32_WPORT PORTC
#define DIO32_DDR DDRC #define DIO31_PIN PINC6
#define DIO32_PWM NULL #define DIO31_RPORT PINC
#define DIO31_WPORT PORTC
#define DIO33_PIN PINC4 #define DIO31_DDR DDRC
#define DIO33_RPORT PINC #define DIO31_PWM NULL
#define DIO33_WPORT PORTC
#define DIO33_DDR DDRC #define DIO32_PIN PINC5
#define DIO33_PWM NULL #define DIO32_RPORT PINC
#define DIO32_WPORT PORTC
#define DIO34_PIN PINC3 #define DIO32_DDR DDRC
#define DIO34_RPORT PINC #define DIO32_PWM NULL
#define DIO34_WPORT PORTC
#define DIO34_DDR DDRC #define DIO33_PIN PINC4
#define DIO34_PWM NULL #define DIO33_RPORT PINC
#define DIO33_WPORT PORTC
#define DIO35_PIN PINC2 #define DIO33_DDR DDRC
#define DIO35_RPORT PINC #define DIO33_PWM NULL
#define DIO35_WPORT PORTC
#define DIO35_DDR DDRC #define DIO34_PIN PINC3
#define DIO35_PWM NULL #define DIO34_RPORT PINC
#define DIO34_WPORT PORTC
#define DIO36_PIN PINC1 #define DIO34_DDR DDRC
#define DIO36_RPORT PINC #define DIO34_PWM NULL
#define DIO36_WPORT PORTC
#define DIO36_DDR DDRC #define DIO35_PIN PINC2
#define DIO36_PWM NULL #define DIO35_RPORT PINC
#define DIO35_WPORT PORTC
#define DIO37_PIN PINC0 #define DIO35_DDR DDRC
#define DIO37_RPORT PINC #define DIO35_PWM NULL
#define DIO37_WPORT PORTC
#define DIO37_DDR DDRC #define DIO36_PIN PINC1
#define DIO37_PWM NULL #define DIO36_RPORT PINC
#define DIO36_WPORT PORTC
#define DIO38_PIN PIND7 #define DIO36_DDR DDRC
#define DIO38_RPORT PIND #define DIO36_PWM NULL
#define DIO38_WPORT PORTD
#define DIO38_DDR DDRD #define DIO37_PIN PINC0
#define DIO38_PWM NULL #define DIO37_RPORT PINC
#define DIO37_WPORT PORTC
#define DIO39_PIN PING2 #define DIO37_DDR DDRC
#define DIO39_RPORT PING #define DIO37_PWM NULL
#define DIO39_WPORT PORTG
#define DIO39_DDR DDRG #define DIO38_PIN PIND7
#define DIO39_PWM NULL #define DIO38_RPORT PIND
#define DIO38_WPORT PORTD
#define DIO40_PIN PING1 #define DIO38_DDR DDRD
#define DIO40_RPORT PING #define DIO38_PWM NULL
#define DIO40_WPORT PORTG
#define DIO40_DDR DDRG #define DIO39_PIN PING2
#define DIO40_PWM NULL #define DIO39_RPORT PING
#define DIO39_WPORT PORTG
#define DIO41_PIN PING0 #define DIO39_DDR DDRG
#define DIO41_RPORT PING #define DIO39_PWM NULL
#define DIO41_WPORT PORTG
#define DIO41_DDR DDRG #define DIO40_PIN PING1
#define DIO41_PWM NULL #define DIO40_RPORT PING
#define DIO40_WPORT PORTG
#define DIO42_PIN PINL7 #define DIO40_DDR DDRG
#define DIO42_RPORT PINL #define DIO40_PWM NULL
#define DIO42_WPORT PORTL
#define DIO42_DDR DDRL #define DIO41_PIN PING0
#define DIO42_PWM NULL #define DIO41_RPORT PING
#define DIO41_WPORT PORTG
#define DIO43_PIN PINL6 #define DIO41_DDR DDRG
#define DIO43_RPORT PINL #define DIO41_PWM NULL
#define DIO43_WPORT PORTL
#define DIO43_DDR DDRL #define DIO42_PIN PINL7
#define DIO43_PWM NULL #define DIO42_RPORT PINL
#define DIO42_WPORT PORTL
#define DIO44_PIN PINL5 #define DIO42_DDR DDRL
#define DIO44_RPORT PINL #define DIO42_PWM NULL
#define DIO44_WPORT PORTL
#define DIO44_DDR DDRL #define DIO43_PIN PINL6
#define DIO44_PWM &OCR5CL #define DIO43_RPORT PINL
#define DIO43_WPORT PORTL
#define DIO45_PIN PINL4 #define DIO43_DDR DDRL
#define DIO45_RPORT PINL #define DIO43_PWM NULL
#define DIO45_WPORT PORTL
#define DIO45_DDR DDRL #define DIO44_PIN PINL5
#define DIO45_PWM &OCR5BL #define DIO44_RPORT PINL
#define DIO44_WPORT PORTL
#define DIO46_PIN PINL3 #define DIO44_DDR DDRL
#define DIO46_RPORT PINL #define DIO44_PWM &OCR5CL
#define DIO46_WPORT PORTL
#define DIO46_DDR DDRL #define DIO45_PIN PINL4
#define DIO46_PWM &OCR5AL #define DIO45_RPORT PINL
#define DIO45_WPORT PORTL
#define DIO47_PIN PINL2 #define DIO45_DDR DDRL
#define DIO47_RPORT PINL #define DIO45_PWM &OCR5BL
#define DIO47_WPORT PORTL
#define DIO47_DDR DDRL #define DIO46_PIN PINL3
#define DIO47_PWM NULL #define DIO46_RPORT PINL
#define DIO46_WPORT PORTL
#define DIO48_PIN PINL1 #define DIO46_DDR DDRL
#define DIO48_RPORT PINL #define DIO46_PWM &OCR5AL
#define DIO48_WPORT PORTL
#define DIO48_DDR DDRL #define DIO47_PIN PINL2
#define DIO48_PWM NULL #define DIO47_RPORT PINL
#define DIO47_WPORT PORTL
#define DIO49_PIN PINL0 #define DIO47_DDR DDRL
#define DIO49_RPORT PINL #define DIO47_PWM NULL
#define DIO49_WPORT PORTL
#define DIO49_DDR DDRL #define DIO48_PIN PINL1
#define DIO49_PWM NULL #define DIO48_RPORT PINL
#define DIO48_WPORT PORTL
#define DIO50_PIN PINB3 #define DIO48_DDR DDRL
#define DIO50_RPORT PINB #define DIO48_PWM NULL
#define DIO50_WPORT PORTB
#define DIO50_DDR DDRB #define DIO49_PIN PINL0
#define DIO50_PWM NULL #define DIO49_RPORT PINL
#define DIO49_WPORT PORTL
#define DIO51_PIN PINB2 #define DIO49_DDR DDRL
#define DIO51_RPORT PINB #define DIO49_PWM NULL
#define DIO51_WPORT PORTB
#define DIO51_DDR DDRB #define DIO50_PIN PINB3
#define DIO51_PWM NULL #define DIO50_RPORT PINB
#define DIO50_WPORT PORTB
#define DIO52_PIN PINB1 #define DIO50_DDR DDRB
#define DIO52_RPORT PINB #define DIO50_PWM NULL
#define DIO52_WPORT PORTB
#define DIO52_DDR DDRB #define DIO51_PIN PINB2
#define DIO52_PWM NULL #define DIO51_RPORT PINB
#define DIO51_WPORT PORTB
#define DIO53_PIN PINB0 #define DIO51_DDR DDRB
#define DIO53_RPORT PINB #define DIO51_PWM NULL
#define DIO53_WPORT PORTB
#define DIO53_DDR DDRB #define DIO52_PIN PINB1
#define DIO53_PWM NULL #define DIO52_RPORT PINB
#define DIO52_WPORT PORTB
#define DIO54_PIN PINF0 #define DIO52_DDR DDRB
#define DIO54_RPORT PINF #define DIO52_PWM NULL
#define DIO54_WPORT PORTF
#define DIO54_DDR DDRF #define DIO53_PIN PINB0
#define DIO54_PWM NULL #define DIO53_RPORT PINB
#define DIO53_WPORT PORTB
#define DIO55_PIN PINF1 #define DIO53_DDR DDRB
#define DIO55_RPORT PINF #define DIO53_PWM NULL
#define DIO55_WPORT PORTF
#define DIO55_DDR DDRF #define DIO54_PIN PINF0
#define DIO55_PWM NULL #define DIO54_RPORT PINF
#define DIO54_WPORT PORTF
#define DIO56_PIN PINF2 #define DIO54_DDR DDRF
#define DIO56_RPORT PINF #define DIO54_PWM NULL
#define DIO56_WPORT PORTF
#define DIO56_DDR DDRF #define DIO55_PIN PINF1
#define DIO56_PWM NULL #define DIO55_RPORT PINF
#define DIO55_WPORT PORTF
#define DIO57_PIN PINF3 #define DIO55_DDR DDRF
#define DIO57_RPORT PINF #define DIO55_PWM NULL
#define DIO57_WPORT PORTF
#define DIO57_DDR DDRF #define DIO56_PIN PINF2
#define DIO57_PWM NULL #define DIO56_RPORT PINF
#define DIO56_WPORT PORTF
#define DIO58_PIN PINF4 #define DIO56_DDR DDRF
#define DIO58_RPORT PINF #define DIO56_PWM NULL
#define DIO58_WPORT PORTF
#define DIO58_DDR DDRF #define DIO57_PIN PINF3
#define DIO58_PWM NULL #define DIO57_RPORT PINF
#define DIO57_WPORT PORTF
#define DIO59_PIN PINF5 #define DIO57_DDR DDRF
#define DIO59_RPORT PINF #define DIO57_PWM NULL
#define DIO59_WPORT PORTF
#define DIO59_DDR DDRF #define DIO58_PIN PINF4
#define DIO59_PWM NULL #define DIO58_RPORT PINF
#define DIO58_WPORT PORTF
#define DIO60_PIN PINF6 #define DIO58_DDR DDRF
#define DIO60_RPORT PINF #define DIO58_PWM NULL
#define DIO60_WPORT PORTF
#define DIO60_DDR DDRF #define DIO59_PIN PINF5
#define DIO60_PWM NULL #define DIO59_RPORT PINF
#define DIO59_WPORT PORTF
#define DIO61_PIN PINF7 #define DIO59_DDR DDRF
#define DIO61_RPORT PINF #define DIO59_PWM NULL
#define DIO61_WPORT PORTF
#define DIO61_DDR DDRF #define DIO60_PIN PINF6
#define DIO61_PWM NULL #define DIO60_RPORT PINF
#define DIO60_WPORT PORTF
#define DIO62_PIN PINK0 #define DIO60_DDR DDRF
#define DIO62_RPORT PINK #define DIO60_PWM NULL
#define DIO62_WPORT PORTK
#define DIO62_DDR DDRK #define DIO61_PIN PINF7
#define DIO62_PWM NULL #define DIO61_RPORT PINF
#define DIO61_WPORT PORTF
#define DIO63_PIN PINK1 #define DIO61_DDR DDRF
#define DIO63_RPORT PINK #define DIO61_PWM NULL
#define DIO63_WPORT PORTK
#define DIO63_DDR DDRK #define DIO62_PIN PINK0
#define DIO63_PWM NULL #define DIO62_RPORT PINK
#define DIO62_WPORT PORTK
#define DIO64_PIN PINK2 #define DIO62_DDR DDRK
#define DIO64_RPORT PINK #define DIO62_PWM NULL
#define DIO64_WPORT PORTK
#define DIO64_DDR DDRK #define DIO63_PIN PINK1
#define DIO64_PWM NULL #define DIO63_RPORT PINK
#define DIO63_WPORT PORTK
#define DIO65_PIN PINK3 #define DIO63_DDR DDRK
#define DIO65_RPORT PINK #define DIO63_PWM NULL
#define DIO65_WPORT PORTK
#define DIO65_DDR DDRK #define DIO64_PIN PINK2
#define DIO65_PWM NULL #define DIO64_RPORT PINK
#define DIO64_WPORT PORTK
#define DIO66_PIN PINK4 #define DIO64_DDR DDRK
#define DIO66_RPORT PINK #define DIO64_PWM NULL
#define DIO66_WPORT PORTK
#define DIO66_DDR DDRK #define DIO65_PIN PINK3
#define DIO66_PWM NULL #define DIO65_RPORT PINK
#define DIO65_WPORT PORTK
#define DIO67_PIN PINK5 #define DIO65_DDR DDRK
#define DIO67_RPORT PINK #define DIO65_PWM NULL
#define DIO67_WPORT PORTK
#define DIO67_DDR DDRK #define DIO66_PIN PINK4
#define DIO67_PWM NULL #define DIO66_RPORT PINK
#define DIO66_WPORT PORTK
#define DIO68_PIN PINK6 #define DIO66_DDR DDRK
#define DIO68_RPORT PINK #define DIO66_PWM NULL
#define DIO68_WPORT PORTK
#define DIO68_DDR DDRK #define DIO67_PIN PINK5
#define DIO68_PWM NULL #define DIO67_RPORT PINK
#define DIO67_WPORT PORTK
#define DIO69_PIN PINK7 #define DIO67_DDR DDRK
#define DIO69_RPORT PINK #define DIO67_PWM NULL
#define DIO69_WPORT PORTK
#define DIO69_DDR DDRK #define DIO68_PIN PINK6
#define DIO69_PWM NULL #define DIO68_RPORT PINK
#define DIO68_WPORT PORTK
#define DIO68_DDR DDRK
#define DIO68_PWM NULL
#undef PA0
#define PA0_PIN PINA0 #define DIO69_PIN PINK7
#define PA0_RPORT PINA #define DIO69_RPORT PINK
#define PA0_WPORT PORTA #define DIO69_WPORT PORTK
#define PA0_DDR DDRA #define DIO69_DDR DDRK
#define PA0_PWM NULL #define DIO69_PWM NULL
#undef PA1
#define PA1_PIN PINA1
#define PA1_RPORT PINA
#define PA1_WPORT PORTA #undef PA0
#define PA1_DDR DDRA #define PA0_PIN PINA0
#define PA1_PWM NULL #define PA0_RPORT PINA
#undef PA2 #define PA0_WPORT PORTA
#define PA2_PIN PINA2 #define PA0_DDR DDRA
#define PA2_RPORT PINA #define PA0_PWM NULL
#define PA2_WPORT PORTA #undef PA1
#define PA2_DDR DDRA #define PA1_PIN PINA1
#define PA2_PWM NULL #define PA1_RPORT PINA
#undef PA3 #define PA1_WPORT PORTA
#define PA3_PIN PINA3 #define PA1_DDR DDRA
#define PA3_RPORT PINA #define PA1_PWM NULL
#define PA3_WPORT PORTA #undef PA2
#define PA3_DDR DDRA #define PA2_PIN PINA2
#define PA3_PWM NULL #define PA2_RPORT PINA
#undef PA4 #define PA2_WPORT PORTA
#define PA4_PIN PINA4 #define PA2_DDR DDRA
#define PA4_RPORT PINA #define PA2_PWM NULL
#define PA4_WPORT PORTA #undef PA3
#define PA4_DDR DDRA #define PA3_PIN PINA3
#define PA4_PWM NULL #define PA3_RPORT PINA
#undef PA5 #define PA3_WPORT PORTA
#define PA5_PIN PINA5 #define PA3_DDR DDRA
#define PA5_RPORT PINA #define PA3_PWM NULL
#define PA5_WPORT PORTA #undef PA4
#define PA5_DDR DDRA #define PA4_PIN PINA4
#define PA5_PWM NULL #define PA4_RPORT PINA
#undef PA6 #define PA4_WPORT PORTA
#define PA6_PIN PINA6 #define PA4_DDR DDRA
#define PA6_RPORT PINA #define PA4_PWM NULL
#define PA6_WPORT PORTA #undef PA5
#define PA6_DDR DDRA #define PA5_PIN PINA5
#define PA6_PWM NULL #define PA5_RPORT PINA
#undef PA7 #define PA5_WPORT PORTA
#define PA7_PIN PINA7 #define PA5_DDR DDRA
#define PA7_RPORT PINA #define PA5_PWM NULL
#define PA7_WPORT PORTA #undef PA6
#define PA7_DDR DDRA #define PA6_PIN PINA6
#define PA7_PWM NULL #define PA6_RPORT PINA
#define PA6_WPORT PORTA
#undef PB0 #define PA6_DDR DDRA
#define PB0_PIN PINB0 #define PA6_PWM NULL
#define PB0_RPORT PINB #undef PA7
#define PB0_WPORT PORTB #define PA7_PIN PINA7
#define PB0_DDR DDRB #define PA7_RPORT PINA
#define PB0_PWM NULL #define PA7_WPORT PORTA
#undef PB1 #define PA7_DDR DDRA
#define PB1_PIN PINB1 #define PA7_PWM NULL
#define PB1_RPORT PINB
#define PB1_WPORT PORTB #undef PB0
#define PB1_DDR DDRB #define PB0_PIN PINB0
#define PB1_PWM NULL #define PB0_RPORT PINB
#undef PB2 #define PB0_WPORT PORTB
#define PB2_PIN PINB2 #define PB0_DDR DDRB
#define PB2_RPORT PINB #define PB0_PWM NULL
#define PB2_WPORT PORTB #undef PB1
#define PB2_DDR DDRB #define PB1_PIN PINB1
#define PB2_PWM NULL #define PB1_RPORT PINB
#undef PB3 #define PB1_WPORT PORTB
#define PB3_PIN PINB3 #define PB1_DDR DDRB
#define PB3_RPORT PINB #define PB1_PWM NULL
#define PB3_WPORT PORTB #undef PB2
#define PB3_DDR DDRB #define PB2_PIN PINB2
#define PB3_PWM NULL #define PB2_RPORT PINB
#undef PB4 #define PB2_WPORT PORTB
#define PB4_PIN PINB4 #define PB2_DDR DDRB
#define PB4_RPORT PINB #define PB2_PWM NULL
#define PB4_WPORT PORTB #undef PB3
#define PB4_DDR DDRB #define PB3_PIN PINB3
#define PB4_PWM &OCR2A #define PB3_RPORT PINB
#undef PB5 #define PB3_WPORT PORTB
#define PB5_PIN PINB5 #define PB3_DDR DDRB
#define PB5_RPORT PINB #define PB3_PWM NULL
#define PB5_WPORT PORTB #undef PB4
#define PB5_DDR DDRB #define PB4_PIN PINB4
#define PB5_PWM NULL #define PB4_RPORT PINB
#undef PB6 #define PB4_WPORT PORTB
#define PB6_PIN PINB6 #define PB4_DDR DDRB
#define PB6_RPORT PINB #define PB4_PWM &OCR2A
#define PB6_WPORT PORTB #undef PB5
#define PB6_DDR DDRB #define PB5_PIN PINB5
#define PB6_PWM NULL #define PB5_RPORT PINB
#undef PB7 #define PB5_WPORT PORTB
#define PB7_PIN PINB7 #define PB5_DDR DDRB
#define PB7_RPORT PINB #define PB5_PWM NULL
#define PB7_WPORT PORTB #undef PB6
#define PB7_DDR DDRB #define PB6_PIN PINB6
#define PB7_PWM &OCR0A #define PB6_RPORT PINB
#define PB6_WPORT PORTB
#undef PC0 #define PB6_DDR DDRB
#define PC0_PIN PINC0 #define PB6_PWM NULL
#define PC0_RPORT PINC #undef PB7
#define PC0_WPORT PORTC #define PB7_PIN PINB7
#define PC0_DDR DDRC #define PB7_RPORT PINB
#define PC0_PWM NULL #define PB7_WPORT PORTB
#undef PC1 #define PB7_DDR DDRB
#define PC1_PIN PINC1 #define PB7_PWM &OCR0A
#define PC1_RPORT PINC
#define PC1_WPORT PORTC #undef PC0
#define PC1_DDR DDRC #define PC0_PIN PINC0
#define PC1_PWM NULL #define PC0_RPORT PINC
#undef PC2 #define PC0_WPORT PORTC
#define PC2_PIN PINC2 #define PC0_DDR DDRC
#define PC2_RPORT PINC #define PC0_PWM NULL
#define PC2_WPORT PORTC #undef PC1
#define PC2_DDR DDRC #define PC1_PIN PINC1
#define PC2_PWM NULL #define PC1_RPORT PINC
#undef PC3 #define PC1_WPORT PORTC
#define PC3_PIN PINC3 #define PC1_DDR DDRC
#define PC3_RPORT PINC #define PC1_PWM NULL
#define PC3_WPORT PORTC #undef PC2
#define PC3_DDR DDRC #define PC2_PIN PINC2
#define PC3_PWM NULL #define PC2_RPORT PINC
#undef PC4 #define PC2_WPORT PORTC
#define PC4_PIN PINC4 #define PC2_DDR DDRC
#define PC4_RPORT PINC #define PC2_PWM NULL
#define PC4_WPORT PORTC #undef PC3
#define PC4_DDR DDRC #define PC3_PIN PINC3
#define PC4_PWM NULL #define PC3_RPORT PINC
#undef PC5 #define PC3_WPORT PORTC
#define PC5_PIN PINC5 #define PC3_DDR DDRC
#define PC5_RPORT PINC #define PC3_PWM NULL
#define PC5_WPORT PORTC #undef PC4
#define PC5_DDR DDRC #define PC4_PIN PINC4
#define PC5_PWM NULL #define PC4_RPORT PINC
#undef PC6 #define PC4_WPORT PORTC
#define PC6_PIN PINC6 #define PC4_DDR DDRC
#define PC6_RPORT PINC #define PC4_PWM NULL
#define PC6_WPORT PORTC #undef PC5
#define PC6_DDR DDRC #define PC5_PIN PINC5
#define PC6_PWM NULL #define PC5_RPORT PINC
#undef PC7 #define PC5_WPORT PORTC
#define PC7_PIN PINC7 #define PC5_DDR DDRC
#define PC7_RPORT PINC #define PC5_PWM NULL
#define PC7_WPORT PORTC #undef PC6
#define PC7_DDR DDRC #define PC6_PIN PINC6
#define PC7_PWM NULL #define PC6_RPORT PINC
#define PC6_WPORT PORTC
#undef PD0 #define PC6_DDR DDRC
#define PD0_PIN PIND0 #define PC6_PWM NULL
#define PD0_RPORT PIND #undef PC7
#define PD0_WPORT PORTD #define PC7_PIN PINC7
#define PD0_DDR DDRD #define PC7_RPORT PINC
#define PD0_PWM NULL #define PC7_WPORT PORTC
#undef PD1 #define PC7_DDR DDRC
#define PD1_PIN PIND1 #define PC7_PWM NULL
#define PD1_RPORT PIND
#define PD1_WPORT PORTD #undef PD0
#define PD1_DDR DDRD #define PD0_PIN PIND0
#define PD1_PWM NULL #define PD0_RPORT PIND
#undef PD2 #define PD0_WPORT PORTD
#define PD2_PIN PIND2 #define PD0_DDR DDRD
#define PD2_RPORT PIND #define PD0_PWM NULL
#define PD2_WPORT PORTD #undef PD1
#define PD2_DDR DDRD #define PD1_PIN PIND1
#define PD2_PWM NULL #define PD1_RPORT PIND
#undef PD3 #define PD1_WPORT PORTD
#define PD3_PIN PIND3 #define PD1_DDR DDRD
#define PD3_RPORT PIND #define PD1_PWM NULL
#define PD3_WPORT PORTD #undef PD2
#define PD3_DDR DDRD #define PD2_PIN PIND2
#define PD3_PWM NULL #define PD2_RPORT PIND
#undef PD4 #define PD2_WPORT PORTD
#define PD4_PIN PIND4 #define PD2_DDR DDRD
#define PD4_RPORT PIND #define PD2_PWM NULL
#define PD4_WPORT PORTD #undef PD3
#define PD4_DDR DDRD #define PD3_PIN PIND3
#define PD4_PWM NULL #define PD3_RPORT PIND
#undef PD5 #define PD3_WPORT PORTD
#define PD5_PIN PIND5 #define PD3_DDR DDRD
#define PD5_RPORT PIND #define PD3_PWM NULL
#define PD5_WPORT PORTD #undef PD4
#define PD5_DDR DDRD #define PD4_PIN PIND4
#define PD5_PWM NULL #define PD4_RPORT PIND
#undef PD6 #define PD4_WPORT PORTD
#define PD6_PIN PIND6 #define PD4_DDR DDRD
#define PD6_RPORT PIND #define PD4_PWM NULL
#define PD6_WPORT PORTD #undef PD5
#define PD6_DDR DDRD #define PD5_PIN PIND5
#define PD6_PWM NULL #define PD5_RPORT PIND
#undef PD7 #define PD5_WPORT PORTD
#define PD7_PIN PIND7 #define PD5_DDR DDRD
#define PD7_RPORT PIND #define PD5_PWM NULL
#define PD7_WPORT PORTD #undef PD6
#define PD7_DDR DDRD #define PD6_PIN PIND6
#define PD7_PWM NULL #define PD6_RPORT PIND
#define PD6_WPORT PORTD
#undef PE0 #define PD6_DDR DDRD
#define PE0_PIN PINE0 #define PD6_PWM NULL
#define PE0_RPORT PINE #undef PD7
#define PE0_WPORT PORTE #define PD7_PIN PIND7
#define PE0_DDR DDRE #define PD7_RPORT PIND
#define PE0_PWM NULL #define PD7_WPORT PORTD
#undef PE1 #define PD7_DDR DDRD
#define PE1_PIN PINE1 #define PD7_PWM NULL
#define PE1_RPORT PINE
#define PE1_WPORT PORTE #undef PE0
#define PE1_DDR DDRE #define PE0_PIN PINE0
#define PE1_PWM NULL #define PE0_RPORT PINE
#undef PE2 #define PE0_WPORT PORTE
#define PE2_PIN PINE2 #define PE0_DDR DDRE
#define PE2_RPORT PINE #define PE0_PWM NULL
#define PE2_WPORT PORTE #undef PE1
#define PE2_DDR DDRE #define PE1_PIN PINE1
#define PE2_PWM NULL #define PE1_RPORT PINE
#undef PE3 #define PE1_WPORT PORTE
#define PE3_PIN PINE3 #define PE1_DDR DDRE
#define PE3_RPORT PINE #define PE1_PWM NULL
#define PE3_WPORT PORTE #undef PE2
#define PE3_DDR DDRE #define PE2_PIN PINE2
#define PE3_PWM &OCR3AL #define PE2_RPORT PINE
#undef PE4 #define PE2_WPORT PORTE
#define PE4_PIN PINE4 #define PE2_DDR DDRE
#define PE4_RPORT PINE #define PE2_PWM NULL
#define PE4_WPORT PORTE #undef PE3
#define PE4_DDR DDRE #define PE3_PIN PINE3
#define PE4_PWM &OCR3BL #define PE3_RPORT PINE
#undef PE5 #define PE3_WPORT PORTE
#define PE5_PIN PINE5 #define PE3_DDR DDRE
#define PE5_RPORT PINE #define PE3_PWM &OCR3AL
#define PE5_WPORT PORTE #undef PE4
#define PE5_DDR DDRE #define PE4_PIN PINE4
#define PE5_PWM &OCR3CL #define PE4_RPORT PINE
#undef PE6 #define PE4_WPORT PORTE
#define PE6_PIN PINE6 #define PE4_DDR DDRE
#define PE6_RPORT PINE #define PE4_PWM &OCR3BL
#define PE6_WPORT PORTE #undef PE5
#define PE6_DDR DDRE #define PE5_PIN PINE5
#define PE6_PWM NULL #define PE5_RPORT PINE
#undef PE7 #define PE5_WPORT PORTE
#define PE7_PIN PINE7 #define PE5_DDR DDRE
#define PE7_RPORT PINE #define PE5_PWM &OCR3CL
#define PE7_WPORT PORTE #undef PE6
#define PE7_DDR DDRE #define PE6_PIN PINE6
#define PE7_PWM NULL #define PE6_RPORT PINE
#define PE6_WPORT PORTE
#undef PF0 #define PE6_DDR DDRE
#define PF0_PIN PINF0 #define PE6_PWM NULL
#define PF0_RPORT PINF #undef PE7
#define PF0_WPORT PORTF #define PE7_PIN PINE7
#define PF0_DDR DDRF #define PE7_RPORT PINE
#define PF0_PWM NULL #define PE7_WPORT PORTE
#undef PF1 #define PE7_DDR DDRE
#define PF1_PIN PINF1 #define PE7_PWM NULL
#define PF1_RPORT PINF
#define PF1_WPORT PORTF #undef PF0
#define PF1_DDR DDRF #define PF0_PIN PINF0
#define PF1_PWM NULL #define PF0_RPORT PINF
#undef PF2 #define PF0_WPORT PORTF
#define PF2_PIN PINF2 #define PF0_DDR DDRF
#define PF2_RPORT PINF #define PF0_PWM NULL
#define PF2_WPORT PORTF #undef PF1
#define PF2_DDR DDRF #define PF1_PIN PINF1
#define PF2_PWM NULL #define PF1_RPORT PINF
#undef PF3 #define PF1_WPORT PORTF
#define PF3_PIN PINF3 #define PF1_DDR DDRF
#define PF3_RPORT PINF #define PF1_PWM NULL
#define PF3_WPORT PORTF #undef PF2
#define PF3_DDR DDRF #define PF2_PIN PINF2
#define PF3_PWM NULL #define PF2_RPORT PINF
#undef PF4 #define PF2_WPORT PORTF
#define PF4_PIN PINF4 #define PF2_DDR DDRF
#define PF4_RPORT PINF #define PF2_PWM NULL
#define PF4_WPORT PORTF #undef PF3
#define PF4_DDR DDRF #define PF3_PIN PINF3
#define PF4_PWM NULL #define PF3_RPORT PINF
#undef PF5 #define PF3_WPORT PORTF
#define PF5_PIN PINF5 #define PF3_DDR DDRF
#define PF5_RPORT PINF #define PF3_PWM NULL
#define PF5_WPORT PORTF #undef PF4
#define PF5_DDR DDRF #define PF4_PIN PINF4
#define PF5_PWM NULL #define PF4_RPORT PINF
#undef PF6 #define PF4_WPORT PORTF
#define PF6_PIN PINF6 #define PF4_DDR DDRF
#define PF6_RPORT PINF #define PF4_PWM NULL
#define PF6_WPORT PORTF #undef PF5
#define PF6_DDR DDRF #define PF5_PIN PINF5
#define PF6_PWM NULL #define PF5_RPORT PINF
#undef PF7 #define PF5_WPORT PORTF
#define PF7_PIN PINF7 #define PF5_DDR DDRF
#define PF7_RPORT PINF #define PF5_PWM NULL
#define PF7_WPORT PORTF #undef PF6
#define PF7_DDR DDRF #define PF6_PIN PINF6
#define PF7_PWM NULL #define PF6_RPORT PINF
#define PF6_WPORT PORTF
#undef PG0 #define PF6_DDR DDRF
#define PG0_PIN PING0 #define PF6_PWM NULL
#define PG0_RPORT PING #undef PF7
#define PG0_WPORT PORTG #define PF7_PIN PINF7
#define PG0_DDR DDRG #define PF7_RPORT PINF
#define PG0_PWM NULL #define PF7_WPORT PORTF
#undef PG1 #define PF7_DDR DDRF
#define PG1_PIN PING1 #define PF7_PWM NULL
#define PG1_RPORT PING
#define PG1_WPORT PORTG #undef PG0
#define PG1_DDR DDRG #define PG0_PIN PING0
#define PG1_PWM NULL #define PG0_RPORT PING
#undef PG2 #define PG0_WPORT PORTG
#define PG2_PIN PING2 #define PG0_DDR DDRG
#define PG2_RPORT PING #define PG0_PWM NULL
#define PG2_WPORT PORTG #undef PG1
#define PG2_DDR DDRG #define PG1_PIN PING1
#define PG2_PWM NULL #define PG1_RPORT PING
#undef PG3 #define PG1_WPORT PORTG
#define PG3_PIN PING3 #define PG1_DDR DDRG
#define PG3_RPORT PING #define PG1_PWM NULL
#define PG3_WPORT PORTG #undef PG2
#define PG3_DDR DDRG #define PG2_PIN PING2
#define PG3_PWM NULL #define PG2_RPORT PING
#undef PG4 #define PG2_WPORT PORTG
#define PG4_PIN PING4 #define PG2_DDR DDRG
#define PG4_RPORT PING #define PG2_PWM NULL
#define PG4_WPORT PORTG #undef PG3
#define PG4_DDR DDRG #define PG3_PIN PING3
#define PG4_PWM NULL #define PG3_RPORT PING
#undef PG5 #define PG3_WPORT PORTG
#define PG5_PIN PING5 #define PG3_DDR DDRG
#define PG5_RPORT PING #define PG3_PWM NULL
#define PG5_WPORT PORTG #undef PG4
#define PG5_DDR DDRG #define PG4_PIN PING4
#define PG5_PWM &OCR0B #define PG4_RPORT PING
#undef PG6 #define PG4_WPORT PORTG
#define PG6_PIN PING6 #define PG4_DDR DDRG
#define PG6_RPORT PING #define PG4_PWM NULL
#define PG6_WPORT PORTG #undef PG5
#define PG6_DDR DDRG #define PG5_PIN PING5
#define PG6_PWM NULL #define PG5_RPORT PING
#undef PG7 #define PG5_WPORT PORTG
#define PG7_PIN PING7 #define PG5_DDR DDRG
#define PG7_RPORT PING #define PG5_PWM &OCR0B
#define PG7_WPORT PORTG #undef PG6
#define PG7_DDR DDRG #define PG6_PIN PING6
#define PG7_PWM NULL #define PG6_RPORT PING
#define PG6_WPORT PORTG
#undef PH0 #define PG6_DDR DDRG
#define PH0_PIN PINH0 #define PG6_PWM NULL
#define PH0_RPORT PINH #undef PG7
#define PH0_WPORT PORTH #define PG7_PIN PING7
#define PH0_DDR DDRH #define PG7_RPORT PING
#define PH0_PWM NULL #define PG7_WPORT PORTG
#undef PH1 #define PG7_DDR DDRG
#define PH1_PIN PINH1 #define PG7_PWM NULL
#define PH1_RPORT PINH
#define PH1_WPORT PORTH #undef PH0
#define PH1_DDR DDRH #define PH0_PIN PINH0
#define PH1_PWM NULL #define PH0_RPORT PINH
#undef PH2 #define PH0_WPORT PORTH
#define PH2_PIN PINH2 #define PH0_DDR DDRH
#define PH2_RPORT PINH #define PH0_PWM NULL
#define PH2_WPORT PORTH #undef PH1
#define PH2_DDR DDRH #define PH1_PIN PINH1
#define PH2_PWM NULL #define PH1_RPORT PINH
#undef PH3 #define PH1_WPORT PORTH
#define PH3_PIN PINH3 #define PH1_DDR DDRH
#define PH3_RPORT PINH #define PH1_PWM NULL
#define PH3_WPORT PORTH #undef PH2
#define PH3_DDR DDRH #define PH2_PIN PINH2
#define PH3_PWM &OCR4AL #define PH2_RPORT PINH
#undef PH4 #define PH2_WPORT PORTH
#define PH4_PIN PINH4 #define PH2_DDR DDRH
#define PH4_RPORT PINH #define PH2_PWM NULL
#define PH4_WPORT PORTH #undef PH3
#define PH4_DDR DDRH #define PH3_PIN PINH3
#define PH4_PWM &OCR4BL #define PH3_RPORT PINH
#undef PH5 #define PH3_WPORT PORTH
#define PH5_PIN PINH5 #define PH3_DDR DDRH
#define PH5_RPORT PINH #define PH3_PWM &OCR4AL
#define PH5_WPORT PORTH #undef PH4
#define PH5_DDR DDRH #define PH4_PIN PINH4
#define PH5_PWM &OCR4CL #define PH4_RPORT PINH
#undef PH6 #define PH4_WPORT PORTH
#define PH6_PIN PINH6 #define PH4_DDR DDRH
#define PH6_RPORT PINH #define PH4_PWM &OCR4BL
#define PH6_WPORT PORTH #undef PH5
#define PH6_DDR DDRH #define PH5_PIN PINH5
#define PH6_PWM &OCR2B #define PH5_RPORT PINH
#undef PH7 #define PH5_WPORT PORTH
#define PH7_PIN PINH7 #define PH5_DDR DDRH
#define PH7_RPORT PINH #define PH5_PWM &OCR4CL
#define PH7_WPORT PORTH #undef PH6
#define PH7_DDR DDRH #define PH6_PIN PINH6
#define PH7_PWM NULL #define PH6_RPORT PINH
#define PH6_WPORT PORTH
#undef PJ0 #define PH6_DDR DDRH
#define PJ0_PIN PINJ0 #define PH6_PWM &OCR2B
#define PJ0_RPORT PINJ #undef PH7
#define PJ0_WPORT PORTJ #define PH7_PIN PINH7
#define PJ0_DDR DDRJ #define PH7_RPORT PINH
#define PJ0_PWM NULL #define PH7_WPORT PORTH
#undef PJ1 #define PH7_DDR DDRH
#define PJ1_PIN PINJ1 #define PH7_PWM NULL
#define PJ1_RPORT PINJ
#define PJ1_WPORT PORTJ #undef PJ0
#define PJ1_DDR DDRJ #define PJ0_PIN PINJ0
#define PJ1_PWM NULL #define PJ0_RPORT PINJ
#undef PJ2 #define PJ0_WPORT PORTJ
#define PJ2_PIN PINJ2 #define PJ0_DDR DDRJ
#define PJ2_RPORT PINJ #define PJ0_PWM NULL
#define PJ2_WPORT PORTJ #undef PJ1
#define PJ2_DDR DDRJ #define PJ1_PIN PINJ1
#define PJ2_PWM NULL #define PJ1_RPORT PINJ
#undef PJ3 #define PJ1_WPORT PORTJ
#define PJ3_PIN PINJ3 #define PJ1_DDR DDRJ
#define PJ3_RPORT PINJ #define PJ1_PWM NULL
#define PJ3_WPORT PORTJ #undef PJ2
#define PJ3_DDR DDRJ #define PJ2_PIN PINJ2
#define PJ3_PWM NULL #define PJ2_RPORT PINJ
#undef PJ4 #define PJ2_WPORT PORTJ
#define PJ4_PIN PINJ4 #define PJ2_DDR DDRJ
#define PJ4_RPORT PINJ #define PJ2_PWM NULL
#define PJ4_WPORT PORTJ #undef PJ3
#define PJ4_DDR DDRJ #define PJ3_PIN PINJ3
#define PJ4_PWM NULL #define PJ3_RPORT PINJ
#undef PJ5 #define PJ3_WPORT PORTJ
#define PJ5_PIN PINJ5 #define PJ3_DDR DDRJ
#define PJ5_RPORT PINJ #define PJ3_PWM NULL
#define PJ5_WPORT PORTJ #undef PJ4
#define PJ5_DDR DDRJ #define PJ4_PIN PINJ4
#define PJ5_PWM NULL #define PJ4_RPORT PINJ
#undef PJ6 #define PJ4_WPORT PORTJ
#define PJ6_PIN PINJ6 #define PJ4_DDR DDRJ
#define PJ6_RPORT PINJ #define PJ4_PWM NULL
#define PJ6_WPORT PORTJ #undef PJ5
#define PJ6_DDR DDRJ #define PJ5_PIN PINJ5
#define PJ6_PWM NULL #define PJ5_RPORT PINJ
#undef PJ7 #define PJ5_WPORT PORTJ
#define PJ7_PIN PINJ7 #define PJ5_DDR DDRJ
#define PJ7_RPORT PINJ #define PJ5_PWM NULL
#define PJ7_WPORT PORTJ #undef PJ6
#define PJ7_DDR DDRJ #define PJ6_PIN PINJ6
#define PJ7_PWM NULL #define PJ6_RPORT PINJ
#define PJ6_WPORT PORTJ
#undef PK0 #define PJ6_DDR DDRJ
#define PK0_PIN PINK0 #define PJ6_PWM NULL
#define PK0_RPORT PINK #undef PJ7
#define PK0_WPORT PORTK #define PJ7_PIN PINJ7
#define PK0_DDR DDRK #define PJ7_RPORT PINJ
#define PK0_PWM NULL #define PJ7_WPORT PORTJ
#undef PK1 #define PJ7_DDR DDRJ
#define PK1_PIN PINK1 #define PJ7_PWM NULL
#define PK1_RPORT PINK
#define PK1_WPORT PORTK #undef PK0
#define PK1_DDR DDRK #define PK0_PIN PINK0
#define PK1_PWM NULL #define PK0_RPORT PINK
#undef PK2 #define PK0_WPORT PORTK
#define PK2_PIN PINK2 #define PK0_DDR DDRK
#define PK2_RPORT PINK #define PK0_PWM NULL
#define PK2_WPORT PORTK #undef PK1
#define PK2_DDR DDRK #define PK1_PIN PINK1
#define PK2_PWM NULL #define PK1_RPORT PINK
#undef PK3 #define PK1_WPORT PORTK
#define PK3_PIN PINK3 #define PK1_DDR DDRK
#define PK3_RPORT PINK #define PK1_PWM NULL
#define PK3_WPORT PORTK #undef PK2
#define PK3_DDR DDRK #define PK2_PIN PINK2
#define PK3_PWM NULL #define PK2_RPORT PINK
#undef PK4 #define PK2_WPORT PORTK
#define PK4_PIN PINK4 #define PK2_DDR DDRK
#define PK4_RPORT PINK #define PK2_PWM NULL
#define PK4_WPORT PORTK #undef PK3
#define PK4_DDR DDRK #define PK3_PIN PINK3
#define PK4_PWM NULL #define PK3_RPORT PINK
#undef PK5 #define PK3_WPORT PORTK
#define PK5_PIN PINK5 #define PK3_DDR DDRK
#define PK5_RPORT PINK #define PK3_PWM NULL
#define PK5_WPORT PORTK #undef PK4
#define PK5_DDR DDRK #define PK4_PIN PINK4
#define PK5_PWM NULL #define PK4_RPORT PINK
#undef PK6 #define PK4_WPORT PORTK
#define PK6_PIN PINK6 #define PK4_DDR DDRK
#define PK6_RPORT PINK #define PK4_PWM NULL
#define PK6_WPORT PORTK #undef PK5
#define PK6_DDR DDRK #define PK5_PIN PINK5
#define PK6_PWM NULL #define PK5_RPORT PINK
#undef PK7 #define PK5_WPORT PORTK
#define PK7_PIN PINK7 #define PK5_DDR DDRK
#define PK7_RPORT PINK #define PK5_PWM NULL
#define PK7_WPORT PORTK #undef PK6
#define PK7_DDR DDRK #define PK6_PIN PINK6
#define PK7_PWM NULL #define PK6_RPORT PINK
#define PK6_WPORT PORTK
#undef PL0 #define PK6_DDR DDRK
#define PL0_PIN PINL0 #define PK6_PWM NULL
#define PL0_RPORT PINL #undef PK7
#define PL0_WPORT PORTL #define PK7_PIN PINK7
#define PL0_DDR DDRL #define PK7_RPORT PINK
#define PL0_PWM NULL #define PK7_WPORT PORTK
#undef PL1 #define PK7_DDR DDRK
#define PL1_PIN PINL1 #define PK7_PWM NULL
#define PL1_RPORT PINL
#define PL1_WPORT PORTL #undef PL0
#define PL1_DDR DDRL #define PL0_PIN PINL0
#define PL1_PWM NULL #define PL0_RPORT PINL
#undef PL2 #define PL0_WPORT PORTL
#define PL2_PIN PINL2 #define PL0_DDR DDRL
#define PL2_RPORT PINL #define PL0_PWM NULL
#define PL2_WPORT PORTL #undef PL1
#define PL2_DDR DDRL #define PL1_PIN PINL1
#define PL2_PWM NULL #define PL1_RPORT PINL
#undef PL3 #define PL1_WPORT PORTL
#define PL3_PIN PINL3 #define PL1_DDR DDRL
#define PL3_RPORT PINL #define PL1_PWM NULL
#define PL3_WPORT PORTL #undef PL2
#define PL3_DDR DDRL #define PL2_PIN PINL2
#define PL3_PWM &OCR5AL #define PL2_RPORT PINL
#undef PL4 #define PL2_WPORT PORTL
#define PL4_PIN PINL4 #define PL2_DDR DDRL
#define PL4_RPORT PINL #define PL2_PWM NULL
#define PL4_WPORT PORTL #undef PL3
#define PL4_DDR DDRL #define PL3_PIN PINL3
#define PL4_PWM &OCR5BL #define PL3_RPORT PINL
#undef PL5 #define PL3_WPORT PORTL
#define PL5_PIN PINL5 #define PL3_DDR DDRL
#define PL5_RPORT PINL #define PL3_PWM &OCR5AL
#define PL5_WPORT PORTL #undef PL4
#define PL5_DDR DDRL #define PL4_PIN PINL4
#define PL5_PWM &OCR5CL #define PL4_RPORT PINL
#undef PL6 #define PL4_WPORT PORTL
#define PL6_PIN PINL6 #define PL4_DDR DDRL
#define PL6_RPORT PINL #define PL4_PWM &OCR5BL
#define PL6_WPORT PORTL #undef PL5
#define PL6_DDR DDRL #define PL5_PIN PINL5
#define PL6_PWM NULL #define PL5_RPORT PINL
#undef PL7 #define PL5_WPORT PORTL
#define PL7_PIN PINL7 #define PL5_DDR DDRL
#define PL7_RPORT PINL #define PL5_PWM &OCR5CL
#define PL7_WPORT PORTL #undef PL6
#define PL7_DDR DDRL #define PL6_PIN PINL6
#define PL7_PWM NULL #define PL6_RPORT PINL
#define PL6_WPORT PORTL
#endif #define PL6_DDR DDRL
#define PL6_PWM NULL
#if defined (__AVR_AT90USB1287__) #undef PL7
// SPI #define PL7_PIN PINL7
#define SCK DIO9 #define PL7_RPORT PINL
#define MISO DIO11 #define PL7_WPORT PORTL
#define MOSI DIO10 #define PL7_DDR DDRL
#define SS DIO8 #define PL7_PWM NULL
// change for your board #endif
#define DEBUG_LED DIO31 /* led D5 red */
#if defined (__AVR_AT90USB1287__)
/* // SPI
pins #define SCK DIO9
*/ #define MISO DIO11
#define DIO0_PIN PINA0 #define MOSI DIO10
#define DIO0_RPORT PINA #define SS DIO8
#define DIO0_WPORT PORTA
#define DIO0_PWM NULL // change for your board
#define DIO0_DDR DDRA #define DEBUG_LED DIO31 /* led D5 red */
#define DIO1_PIN PINA1 /*
#define DIO1_RPORT PINA pins
#define DIO1_WPORT PORTA */
#define DIO1_PWM NULL #define DIO0_PIN PINA0
#define DIO1_DDR DDRA #define DIO0_RPORT PINA
#define DIO0_WPORT PORTA
#define DIO2_PIN PINA2 #define DIO0_PWM NULL
#define DIO2_RPORT PINA #define DIO0_DDR DDRA
#define DIO2_WPORT PORTA
#define DIO2_PWM NULL #define DIO1_PIN PINA1
#define DIO2_DDR DDRA #define DIO1_RPORT PINA
#define DIO1_WPORT PORTA
#define DIO3_PIN PINA3 #define DIO1_PWM NULL
#define DIO3_RPORT PINA #define DIO1_DDR DDRA
#define DIO3_WPORT PORTA
#define DIO3_PWM NULL #define DIO2_PIN PINA2
#define DIO3_DDR DDRA #define DIO2_RPORT PINA
#define DIO2_WPORT PORTA
#define DIO4_PIN PINA4 #define DIO2_PWM NULL
#define DIO4_RPORT PINA #define DIO2_DDR DDRA
#define DIO4_WPORT PORTA
#define DIO4_PWM NULL #define DIO3_PIN PINA3
#define DIO4_DDR DDRA #define DIO3_RPORT PINA
#define DIO3_WPORT PORTA
#define DIO5_PIN PINA5 #define DIO3_PWM NULL
#define DIO5_RPORT PINA #define DIO3_DDR DDRA
#define DIO5_WPORT PORTA
#define DIO5_PWM NULL #define DIO4_PIN PINA4
#define DIO5_DDR DDRA #define DIO4_RPORT PINA
#define DIO4_WPORT PORTA
#define DIO6_PIN PINA6 #define DIO4_PWM NULL
#define DIO6_RPORT PINA #define DIO4_DDR DDRA
#define DIO6_WPORT PORTA
#define DIO6_PWM NULL #define DIO5_PIN PINA5
#define DIO6_DDR DDRA #define DIO5_RPORT PINA
#define DIO5_WPORT PORTA
#define DIO7_PIN PINA7 #define DIO5_PWM NULL
#define DIO7_RPORT PINA #define DIO5_DDR DDRA
#define DIO7_WPORT PORTA
#define DIO7_PWM NULL #define DIO6_PIN PINA6
#define DIO7_DDR DDRA #define DIO6_RPORT PINA
#define DIO6_WPORT PORTA
#define DIO8_PIN PINB0 #define DIO6_PWM NULL
#define DIO8_RPORT PINB #define DIO6_DDR DDRA
#define DIO8_WPORT PORTB
#define DIO8_PWM NULL #define DIO7_PIN PINA7
#define DIO8_DDR DDRB #define DIO7_RPORT PINA
#define DIO7_WPORT PORTA
#define DIO9_PIN PINB1 #define DIO7_PWM NULL
#define DIO9_RPORT PINB #define DIO7_DDR DDRA
#define DIO9_WPORT PORTB
#define DIO9_PWM NULL #define DIO8_PIN PINB0
#define DIO9_DDR DDRB #define DIO8_RPORT PINB
#define DIO8_WPORT PORTB
#define DIO10_PIN PINB2 #define DIO8_PWM NULL
#define DIO10_RPORT PINB #define DIO8_DDR DDRB
#define DIO10_WPORT PORTB
#define DIO10_PWM NULL #define DIO9_PIN PINB1
#define DIO10_DDR DDRB #define DIO9_RPORT PINB
#define DIO9_WPORT PORTB
#define DIO11_PIN PINB3 #define DIO9_PWM NULL
#define DIO11_RPORT PINB #define DIO9_DDR DDRB
#define DIO11_WPORT PORTB
#define DIO11_PWM NULL #define DIO10_PIN PINB2
#define DIO11_DDR DDRB #define DIO10_RPORT PINB
#define DIO10_WPORT PORTB
#define DIO12_PIN PINB4 #define DIO10_PWM NULL
#define DIO12_RPORT PINB #define DIO10_DDR DDRB
#define DIO12_WPORT PORTB
#define DIO12_PWM NULL #define DIO11_PIN PINB3
#define DIO12_DDR DDRB #define DIO11_RPORT PINB
#define DIO11_WPORT PORTB
#define DIO13_PIN PINB5 #define DIO11_PWM NULL
#define DIO13_RPORT PINB #define DIO11_DDR DDRB
#define DIO13_WPORT PORTB
#define DIO13_PWM NULL #define DIO12_PIN PINB4
#define DIO13_DDR DDRB #define DIO12_RPORT PINB
#define DIO12_WPORT PORTB
#define DIO14_PIN PINB6 #define DIO12_PWM NULL
#define DIO14_RPORT PINB #define DIO12_DDR DDRB
#define DIO14_WPORT PORTB
#define DIO14_PWM NULL #define DIO13_PIN PINB5
#define DIO14_DDR DDRB #define DIO13_RPORT PINB
#define DIO13_WPORT PORTB
#define DIO15_PIN PINB7 #define DIO13_PWM NULL
#define DIO15_RPORT PINB #define DIO13_DDR DDRB
#define DIO15_WPORT PORTB
#define DIO15_PWM NULL #define DIO14_PIN PINB6
#define DIO15_DDR DDRB #define DIO14_RPORT PINB
#define DIO14_WPORT PORTB
#define DIO16_PIN PINC0 #define DIO14_PWM NULL
#define DIO16_RPORT PINC #define DIO14_DDR DDRB
#define DIO16_WPORT PORTC
#define DIO16_PWM NULL #define DIO15_PIN PINB7
#define DIO16_DDR DDRC #define DIO15_RPORT PINB
#define DIO15_WPORT PORTB
#define DIO17_PIN PINC1 #define DIO15_PWM NULL
#define DIO17_RPORT PINC #define DIO15_DDR DDRB
#define DIO17_WPORT PORTC
#define DIO17_PWM NULL #define DIO16_PIN PINC0
#define DIO17_DDR DDRC #define DIO16_RPORT PINC
#define DIO16_WPORT PORTC
#define DIO18_PIN PINC2 #define DIO16_PWM NULL
#define DIO18_RPORT PINC #define DIO16_DDR DDRC
#define DIO18_WPORT PORTC
#define DIO18_PWM NULL #define DIO17_PIN PINC1
#define DIO18_DDR DDRC #define DIO17_RPORT PINC
#define DIO17_WPORT PORTC
#define DIO19_PIN PINC3 #define DIO17_PWM NULL
#define DIO19_RPORT PINC #define DIO17_DDR DDRC
#define DIO19_WPORT PORTC
#define DIO19_PWM NULL #define DIO18_PIN PINC2
#define DIO19_DDR DDRC #define DIO18_RPORT PINC
#define DIO18_WPORT PORTC
#define DIO20_PIN PINC4 #define DIO18_PWM NULL
#define DIO20_RPORT PINC #define DIO18_DDR DDRC
#define DIO20_WPORT PORTC
#define DIO20_PWM NULL #define DIO19_PIN PINC3
#define DIO20_DDR DDRC #define DIO19_RPORT PINC
#define DIO19_WPORT PORTC
#define DIO21_PIN PINC5 #define DIO19_PWM NULL
#define DIO21_RPORT PINC #define DIO19_DDR DDRC
#define DIO21_WPORT PORTC
#define DIO21_PWM NULL #define DIO20_PIN PINC4
#define DIO21_DDR DDRC #define DIO20_RPORT PINC
#define DIO20_WPORT PORTC
#define DIO22_PIN PINC6 #define DIO20_PWM NULL
#define DIO22_RPORT PINC #define DIO20_DDR DDRC
#define DIO22_WPORT PORTC
#define DIO22_PWM NULL #define DIO21_PIN PINC5
#define DIO22_DDR DDRC #define DIO21_RPORT PINC
#define DIO21_WPORT PORTC
#define DIO23_PIN PINC7 #define DIO21_PWM NULL
#define DIO23_RPORT PINC #define DIO21_DDR DDRC
#define DIO23_WPORT PORTC
#define DIO23_PWM NULL #define DIO22_PIN PINC6
#define DIO23_DDR DDRC #define DIO22_RPORT PINC
#define DIO22_WPORT PORTC
#define DIO24_PIN PIND0 #define DIO22_PWM NULL
#define DIO24_RPORT PIND #define DIO22_DDR DDRC
#define DIO24_WPORT PORTD
#define DIO24_PWM NULL #define DIO23_PIN PINC7
#define DIO24_DDR DDRD #define DIO23_RPORT PINC
#define DIO23_WPORT PORTC
#define DIO25_PIN PIND1 #define DIO23_PWM NULL
#define DIO25_RPORT PIND #define DIO23_DDR DDRC
#define DIO25_WPORT PORTD
#define DIO25_PWM NULL #define DIO24_PIN PIND0
#define DIO25_DDR DDRD #define DIO24_RPORT PIND
#define DIO24_WPORT PORTD
#define DIO26_PIN PIND2 #define DIO24_PWM NULL
#define DIO26_RPORT PIND #define DIO24_DDR DDRD
#define DIO26_WPORT PORTD
#define DIO26_PWM NULL #define DIO25_PIN PIND1
#define DIO26_DDR DDRD #define DIO25_RPORT PIND
#define DIO25_WPORT PORTD
#define DIO27_PIN PIND3 #define DIO25_PWM NULL
#define DIO27_RPORT PIND #define DIO25_DDR DDRD
#define DIO27_WPORT PORTD
#define DIO27_PWM NULL #define DIO26_PIN PIND2
#define DIO27_DDR DDRD #define DIO26_RPORT PIND
#define DIO26_WPORT PORTD
#define DIO28_PIN PIND4 #define DIO26_PWM NULL
#define DIO28_RPORT PIND #define DIO26_DDR DDRD
#define DIO28_WPORT PORTD
#define DIO28_PWM NULL #define DIO27_PIN PIND3
#define DIO28_DDR DDRD #define DIO27_RPORT PIND
#define DIO27_WPORT PORTD
#define DIO29_PIN PIND5 #define DIO27_PWM NULL
#define DIO29_RPORT PIND #define DIO27_DDR DDRD
#define DIO29_WPORT PORTD
#define DIO29_PWM NULL #define DIO28_PIN PIND4
#define DIO29_DDR DDRD #define DIO28_RPORT PIND
#define DIO28_WPORT PORTD
#define DIO30_PIN PIND6 #define DIO28_PWM NULL
#define DIO30_RPORT PIND #define DIO28_DDR DDRD
#define DIO30_WPORT PORTD
#define DIO30_PWM NULL #define DIO29_PIN PIND5
#define DIO30_DDR DDRD #define DIO29_RPORT PIND
#define DIO29_WPORT PORTD
#define DIO31_PIN PIND7 #define DIO29_PWM NULL
#define DIO31_RPORT PIND #define DIO29_DDR DDRD
#define DIO31_WPORT PORTD
#define DIO31_PWM NULL #define DIO30_PIN PIND6
#define DIO31_DDR DDRD #define DIO30_RPORT PIND
#define DIO30_WPORT PORTD
#define DIO30_PWM NULL
#define DIO32_PIN PINE0 #define DIO30_DDR DDRD
#define DIO32_RPORT PINE
#define DIO32_WPORT PORTE #define DIO31_PIN PIND7
#define DIO32_PWM NULL #define DIO31_RPORT PIND
#define DIO32_DDR DDRE #define DIO31_WPORT PORTD
#define DIO31_PWM NULL
#define DIO33_PIN PINE1 #define DIO31_DDR DDRD
#define DIO33_RPORT PINE
#define DIO33_WPORT PORTE
#define DIO33_PWM NULL #define DIO32_PIN PINE0
#define DIO33_DDR DDRE #define DIO32_RPORT PINE
#define DIO32_WPORT PORTE
#define DIO34_PIN PINE2 #define DIO32_PWM NULL
#define DIO34_RPORT PINE #define DIO32_DDR DDRE
#define DIO34_WPORT PORTE
#define DIO34_PWM NULL #define DIO33_PIN PINE1
#define DIO34_DDR DDRE #define DIO33_RPORT PINE
#define DIO33_WPORT PORTE
#define DIO35_PIN PINE3 #define DIO33_PWM NULL
#define DIO35_RPORT PINE #define DIO33_DDR DDRE
#define DIO35_WPORT PORTE
#define DIO35_PWM NULL #define DIO34_PIN PINE2
#define DIO35_DDR DDRE #define DIO34_RPORT PINE
#define DIO34_WPORT PORTE
#define DIO36_PIN PINE4 #define DIO34_PWM NULL
#define DIO36_RPORT PINE #define DIO34_DDR DDRE
#define DIO36_WPORT PORTE
#define DIO36_PWM NULL #define DIO35_PIN PINE3
#define DIO36_DDR DDRE #define DIO35_RPORT PINE
#define DIO35_WPORT PORTE
#define DIO37_PIN PINE5 #define DIO35_PWM NULL
#define DIO37_RPORT PINE #define DIO35_DDR DDRE
#define DIO37_WPORT PORTE
#define DIO37_PWM NULL #define DIO36_PIN PINE4
#define DIO37_DDR DDRE #define DIO36_RPORT PINE
#define DIO36_WPORT PORTE
#define DIO38_PIN PINE6 #define DIO36_PWM NULL
#define DIO38_RPORT PINE #define DIO36_DDR DDRE
#define DIO38_WPORT PORTE
#define DIO38_PWM NULL #define DIO37_PIN PINE5
#define DIO38_DDR DDRE #define DIO37_RPORT PINE
#define DIO37_WPORT PORTE
#define DIO39_PIN PINE7 #define DIO37_PWM NULL
#define DIO39_RPORT PINE #define DIO37_DDR DDRE
#define DIO39_WPORT PORTE
#define DIO39_PWM NULL #define DIO38_PIN PINE6
#define DIO39_DDR DDRE #define DIO38_RPORT PINE
#define DIO38_WPORT PORTE
#define AIO0_PIN PINF0 #define DIO38_PWM NULL
#define AIO0_RPORT PINF #define DIO38_DDR DDRE
#define AIO0_WPORT PORTF
#define AIO0_PWM NULL #define DIO39_PIN PINE7
#define AIO0_DDR DDRF #define DIO39_RPORT PINE
#define DIO39_WPORT PORTE
#define AIO1_PIN PINF1 #define DIO39_PWM NULL
#define AIO1_RPORT PINF #define DIO39_DDR DDRE
#define AIO1_WPORT PORTF
#define AIO1_PWM NULL #define AIO0_PIN PINF0
#define AIO1_DDR DDRF #define AIO0_RPORT PINF
#define AIO0_WPORT PORTF
#define AIO2_PIN PINF2 #define AIO0_PWM NULL
#define AIO2_RPORT PINF #define AIO0_DDR DDRF
#define AIO2_WPORT PORTF
#define AIO2_PWM NULL #define AIO1_PIN PINF1
#define AIO2_DDR DDRF #define AIO1_RPORT PINF
#define AIO1_WPORT PORTF
#define AIO3_PIN PINF3 #define AIO1_PWM NULL
#define AIO3_RPORT PINF #define AIO1_DDR DDRF
#define AIO3_WPORT PORTF
#define AIO3_PWM NULL #define AIO2_PIN PINF2
#define AIO3_DDR DDRF #define AIO2_RPORT PINF
#define AIO2_WPORT PORTF
#define AIO4_PIN PINF4 #define AIO2_PWM NULL
#define AIO4_RPORT PINF #define AIO2_DDR DDRF
#define AIO4_WPORT PORTF
#define AIO4_PWM NULL #define AIO3_PIN PINF3
#define AIO4_DDR DDRF #define AIO3_RPORT PINF
#define AIO3_WPORT PORTF
#define AIO5_PIN PINF5 #define AIO3_PWM NULL
#define AIO5_RPORT PINF #define AIO3_DDR DDRF
#define AIO5_WPORT PORTF
#define AIO5_PWM NULL #define AIO4_PIN PINF4
#define AIO5_DDR DDRF #define AIO4_RPORT PINF
#define AIO4_WPORT PORTF
#define AIO6_PIN PINF6 #define AIO4_PWM NULL
#define AIO6_RPORT PINF #define AIO4_DDR DDRF
#define AIO6_WPORT PORTF
#define AIO6_PWM NULL #define AIO5_PIN PINF5
#define AIO6_DDR DDRF #define AIO5_RPORT PINF
#define AIO5_WPORT PORTF
#define AIO7_PIN PINF7 #define AIO5_PWM NULL
#define AIO7_RPORT PINF #define AIO5_DDR DDRF
#define AIO7_WPORT PORTF
#define AIO7_PWM NULL #define AIO6_PIN PINF6
#define AIO7_DDR DDRF #define AIO6_RPORT PINF
#define AIO6_WPORT PORTF
#define DIO40_PIN PINF0 #define AIO6_PWM NULL
#define DIO40_RPORT PINF #define AIO6_DDR DDRF
#define DIO40_WPORT PORTF
#define DIO40_PWM NULL #define AIO7_PIN PINF7
#define DIO40_DDR DDRF #define AIO7_RPORT PINF
#define AIO7_WPORT PORTF
#define DIO41_PIN PINF1 #define AIO7_PWM NULL
#define DIO41_RPORT PINF #define AIO7_DDR DDRF
#define DIO41_WPORT PORTF
#define DIO41_PWM NULL #define DIO40_PIN PINF0
#define DIO41_DDR DDRF #define DIO40_RPORT PINF
#define DIO40_WPORT PORTF
#define DIO42_PIN PINF2 #define DIO40_PWM NULL
#define DIO42_RPORT PINF #define DIO40_DDR DDRF
#define DIO42_WPORT PORTF
#define DIO42_PWM NULL #define DIO41_PIN PINF1
#define DIO42_DDR DDRF #define DIO41_RPORT PINF
#define DIO41_WPORT PORTF
#define DIO43_PIN PINF3 #define DIO41_PWM NULL
#define DIO43_RPORT PINF #define DIO41_DDR DDRF
#define DIO43_WPORT PORTF
#define DIO43_PWM NULL #define DIO42_PIN PINF2
#define DIO43_DDR DDRF #define DIO42_RPORT PINF
#define DIO42_WPORT PORTF
#define DIO44_PIN PINF4 #define DIO42_PWM NULL
#define DIO44_RPORT PINF #define DIO42_DDR DDRF
#define DIO44_WPORT PORTF
#define DIO44_PWM NULL #define DIO43_PIN PINF3
#define DIO44_DDR DDRF #define DIO43_RPORT PINF
#define DIO43_WPORT PORTF
#define DIO45_PIN PINF5 #define DIO43_PWM NULL
#define DIO45_RPORT PINF #define DIO43_DDR DDRF
#define DIO45_WPORT PORTF
#define DIO45_PWM NULL #define DIO44_PIN PINF4
#define DIO45_DDR DDRF #define DIO44_RPORT PINF
#define DIO44_WPORT PORTF
#define DIO46_PIN PINF6 #define DIO44_PWM NULL
#define DIO46_RPORT PINF #define DIO44_DDR DDRF
#define DIO46_WPORT PORTF
#define DIO46_PWM NULL #define DIO45_PIN PINF5
#define DIO46_DDR DDRF #define DIO45_RPORT PINF
#define DIO45_WPORT PORTF
#define DIO47_PIN PINF7 #define DIO45_PWM NULL
#define DIO47_RPORT PINF #define DIO45_DDR DDRF
#define DIO47_WPORT PORTF
#define DIO47_PWM NULL #define DIO46_PIN PINF6
#define DIO47_DDR DDRF #define DIO46_RPORT PINF
#define DIO46_WPORT PORTF
#define DIO46_PWM NULL
#define DIO46_DDR DDRF
#undef PA0
#define PA0_PIN PINA0 #define DIO47_PIN PINF7
#define PA0_RPORT PINA #define DIO47_RPORT PINF
#define PA0_WPORT PORTA #define DIO47_WPORT PORTF
#define PA0_PWM NULL #define DIO47_PWM NULL
#define PA0_DDR DDRA #define DIO47_DDR DDRF
#undef PA1
#define PA1_PIN PINA1
#define PA1_RPORT PINA
#define PA1_WPORT PORTA #undef PA0
#define PA1_PWM NULL #define PA0_PIN PINA0
#define PA1_DDR DDRA #define PA0_RPORT PINA
#undef PA2 #define PA0_WPORT PORTA
#define PA2_PIN PINA2 #define PA0_PWM NULL
#define PA2_RPORT PINA #define PA0_DDR DDRA
#define PA2_WPORT PORTA #undef PA1
#define PA2_PWM NULL #define PA1_PIN PINA1
#define PA2_DDR DDRA #define PA1_RPORT PINA
#undef PA3 #define PA1_WPORT PORTA
#define PA3_PIN PINA3 #define PA1_PWM NULL
#define PA3_RPORT PINA #define PA1_DDR DDRA
#define PA3_WPORT PORTA #undef PA2
#define PA3_PWM NULL #define PA2_PIN PINA2
#define PA3_DDR DDRA #define PA2_RPORT PINA
#undef PA4 #define PA2_WPORT PORTA
#define PA4_PIN PINA4 #define PA2_PWM NULL
#define PA4_RPORT PINA #define PA2_DDR DDRA
#define PA4_WPORT PORTA #undef PA3
#define PA4_PWM NULL #define PA3_PIN PINA3
#define PA4_DDR DDRA #define PA3_RPORT PINA
#undef PA5 #define PA3_WPORT PORTA
#define PA5_PIN PINA5 #define PA3_PWM NULL
#define PA5_RPORT PINA #define PA3_DDR DDRA
#define PA5_WPORT PORTA #undef PA4
#define PA5_PWM NULL #define PA4_PIN PINA4
#define PA5_DDR DDRA #define PA4_RPORT PINA
#undef PA6 #define PA4_WPORT PORTA
#define PA6_PIN PINA6 #define PA4_PWM NULL
#define PA6_RPORT PINA #define PA4_DDR DDRA
#define PA6_WPORT PORTA #undef PA5
#define PA6_PWM NULL #define PA5_PIN PINA5
#define PA6_DDR DDRA #define PA5_RPORT PINA
#undef PA7 #define PA5_WPORT PORTA
#define PA7_PIN PINA7 #define PA5_PWM NULL
#define PA7_RPORT PINA #define PA5_DDR DDRA
#define PA7_WPORT PORTA #undef PA6
#define PA7_PWM NULL #define PA6_PIN PINA6
#define PA7_DDR DDRA #define PA6_RPORT PINA
#define PA6_WPORT PORTA
#undef PB0 #define PA6_PWM NULL
#define PB0_PIN PINB0 #define PA6_DDR DDRA
#define PB0_RPORT PINB #undef PA7
#define PB0_WPORT PORTB #define PA7_PIN PINA7
#define PB0_PWM NULL #define PA7_RPORT PINA
#define PB0_DDR DDRB #define PA7_WPORT PORTA
#undef PB1 #define PA7_PWM NULL
#define PB1_PIN PINB1 #define PA7_DDR DDRA
#define PB1_RPORT PINB
#define PB1_WPORT PORTB #undef PB0
#define PB1_PWM NULL #define PB0_PIN PINB0
#define PB1_DDR DDRB #define PB0_RPORT PINB
#undef PB2 #define PB0_WPORT PORTB
#define PB2_PIN PINB2 #define PB0_PWM NULL
#define PB2_RPORT PINB #define PB0_DDR DDRB
#define PB2_WPORT PORTB #undef PB1
#define PB2_PWM NULL #define PB1_PIN PINB1
#define PB2_DDR DDRB #define PB1_RPORT PINB
#undef PB3 #define PB1_WPORT PORTB
#define PB3_PIN PINB3 #define PB1_PWM NULL
#define PB3_RPORT PINB #define PB1_DDR DDRB
#define PB3_WPORT PORTB #undef PB2
#define PB3_PWM NULL #define PB2_PIN PINB2
#define PB3_DDR DDRB #define PB2_RPORT PINB
#undef PB4 #define PB2_WPORT PORTB
#define PB4_PIN PINB4 #define PB2_PWM NULL
#define PB4_RPORT PINB #define PB2_DDR DDRB
#define PB4_WPORT PORTB #undef PB3
#define PB4_PWM NULL #define PB3_PIN PINB3
#define PB4_DDR DDRB #define PB3_RPORT PINB
#undef PB5 #define PB3_WPORT PORTB
#define PB5_PIN PINB5 #define PB3_PWM NULL
#define PB5_RPORT PINB #define PB3_DDR DDRB
#define PB5_WPORT PORTB #undef PB4
#define PB5_PWM NULL #define PB4_PIN PINB4
#define PB5_DDR DDRB #define PB4_RPORT PINB
#undef PB6 #define PB4_WPORT PORTB
#define PB6_PIN PINB6 #define PB4_PWM NULL
#define PB6_RPORT PINB #define PB4_DDR DDRB
#define PB6_WPORT PORTB #undef PB5
#define PB6_PWM NULL #define PB5_PIN PINB5
#define PB6_DDR DDRB #define PB5_RPORT PINB
#undef PB7 #define PB5_WPORT PORTB
#define PB7_PIN PINB7 #define PB5_PWM NULL
#define PB7_RPORT PINB #define PB5_DDR DDRB
#define PB7_WPORT PORTB #undef PB6
#define PB7_PWM NULL #define PB6_PIN PINB6
#define PB7_DDR DDRB #define PB6_RPORT PINB
#define PB6_WPORT PORTB
#undef PC0 #define PB6_PWM NULL
#define PC0_PIN PINC0 #define PB6_DDR DDRB
#define PC0_RPORT PINC #undef PB7
#define PC0_WPORT PORTC #define PB7_PIN PINB7
#define PC0_PWM NULL #define PB7_RPORT PINB
#define PC0_DDR DDRC #define PB7_WPORT PORTB
#undef PC1 #define PB7_PWM NULL
#define PC1_PIN PINC1 #define PB7_DDR DDRB
#define PC1_RPORT PINC
#define PC1_WPORT PORTC #undef PC0
#define PC1_PWM NULL #define PC0_PIN PINC0
#define PC1_DDR DDRC #define PC0_RPORT PINC
#undef PC2 #define PC0_WPORT PORTC
#define PC2_PIN PINC2 #define PC0_PWM NULL
#define PC2_RPORT PINC #define PC0_DDR DDRC
#define PC2_WPORT PORTC #undef PC1
#define PC2_PWM NULL #define PC1_PIN PINC1
#define PC2_DDR DDRC #define PC1_RPORT PINC
#undef PC3 #define PC1_WPORT PORTC
#define PC3_PIN PINC3 #define PC1_PWM NULL
#define PC3_RPORT PINC #define PC1_DDR DDRC
#define PC3_WPORT PORTC #undef PC2
#define PC3_PWM NULL #define PC2_PIN PINC2
#define PC3_DDR DDRC #define PC2_RPORT PINC
#undef PC4 #define PC2_WPORT PORTC
#define PC4_PIN PINC4 #define PC2_PWM NULL
#define PC4_RPORT PINC #define PC2_DDR DDRC
#define PC4_WPORT PORTC #undef PC3
#define PC4_PWM NULL #define PC3_PIN PINC3
#define PC4_DDR DDRC #define PC3_RPORT PINC
#undef PC5 #define PC3_WPORT PORTC
#define PC5_PIN PINC5 #define PC3_PWM NULL
#define PC5_RPORT PINC #define PC3_DDR DDRC
#define PC5_WPORT PORTC #undef PC4
#define PC5_PWM NULL #define PC4_PIN PINC4
#define PC5_DDR DDRC #define PC4_RPORT PINC
#undef PC6 #define PC4_WPORT PORTC
#define PC6_PIN PINC6 #define PC4_PWM NULL
#define PC6_RPORT PINC #define PC4_DDR DDRC
#define PC6_WPORT PORTC #undef PC5
#define PC6_PWM NULL #define PC5_PIN PINC5
#define PC6_DDR DDRC #define PC5_RPORT PINC
#undef PC7 #define PC5_WPORT PORTC
#define PC7_PIN PINC7 #define PC5_PWM NULL
#define PC7_RPORT PINC #define PC5_DDR DDRC
#define PC7_WPORT PORTC #undef PC6
#define PC7_PWM NULL #define PC6_PIN PINC6
#define PC7_DDR DDRC #define PC6_RPORT PINC
#define PC6_WPORT PORTC
#undef PD0 #define PC6_PWM NULL
#define PD0_PIN PIND0 #define PC6_DDR DDRC
#define PD0_RPORT PIND #undef PC7
#define PD0_WPORT PORTD #define PC7_PIN PINC7
#define PD0_PWM NULL #define PC7_RPORT PINC
#define PD0_DDR DDRD #define PC7_WPORT PORTC
#undef PD1 #define PC7_PWM NULL
#define PD1_PIN PIND1 #define PC7_DDR DDRC
#define PD1_RPORT PIND
#define PD1_WPORT PORTD #undef PD0
#define PD1_PWM NULL #define PD0_PIN PIND0
#define PD1_DDR DDRD #define PD0_RPORT PIND
#undef PD2 #define PD0_WPORT PORTD
#define PD2_PIN PIND2 #define PD0_PWM NULL
#define PD2_RPORT PIND #define PD0_DDR DDRD
#define PD2_WPORT PORTD #undef PD1
#define PD2_PWM NULL #define PD1_PIN PIND1
#define PD2_DDR DDRD #define PD1_RPORT PIND
#undef PD3 #define PD1_WPORT PORTD
#define PD3_PIN PIND3 #define PD1_PWM NULL
#define PD3_RPORT PIND #define PD1_DDR DDRD
#define PD3_WPORT PORTD #undef PD2
#define PD3_PWM NULL #define PD2_PIN PIND2
#define PD3_DDR DDRD #define PD2_RPORT PIND
#undef PD4 #define PD2_WPORT PORTD
#define PD4_PIN PIND4 #define PD2_PWM NULL
#define PD4_RPORT PIND #define PD2_DDR DDRD
#define PD4_WPORT PORTD #undef PD3
#define PD4_PWM NULL #define PD3_PIN PIND3
#define PD4_DDR DDRD #define PD3_RPORT PIND
#undef PD5 #define PD3_WPORT PORTD
#define PD5_PIN PIND5 #define PD3_PWM NULL
#define PD5_RPORT PIND #define PD3_DDR DDRD
#define PD5_WPORT PORTD #undef PD4
#define PD5_PWM NULL #define PD4_PIN PIND4
#define PD5_DDR DDRD #define PD4_RPORT PIND
#undef PD6 #define PD4_WPORT PORTD
#define PD6_PIN PIND6 #define PD4_PWM NULL
#define PD6_RPORT PIND #define PD4_DDR DDRD
#define PD6_WPORT PORTD #undef PD5
#define PD6_PWM NULL #define PD5_PIN PIND5
#define PD6_DDR DDRD #define PD5_RPORT PIND
#undef PD7 #define PD5_WPORT PORTD
#define PD7_PIN PIND7 #define PD5_PWM NULL
#define PD7_RPORT PIND #define PD5_DDR DDRD
#define PD7_WPORT PORTD #undef PD6
#define PD7_PWM NULL #define PD6_PIN PIND6
#define PD7_DDR DDRD #define PD6_RPORT PIND
#define PD6_WPORT PORTD
#undef PE0 #define PD6_PWM NULL
#define PE0_PIN PINE0 #define PD6_DDR DDRD
#define PE0_RPORT PINE #undef PD7
#define PE0_WPORT PORTE #define PD7_PIN PIND7
#define PE0_PWM NULL #define PD7_RPORT PIND
#define PE0_DDR DDRE #define PD7_WPORT PORTD
#undef PE1 #define PD7_PWM NULL
#define PE1_PIN PINE1 #define PD7_DDR DDRD
#define PE1_RPORT PINE
#define PE1_WPORT PORTE #undef PE0
#define PE1_PWM NULL #define PE0_PIN PINE0
#define PE1_DDR DDRE #define PE0_RPORT PINE
#undef PE2 #define PE0_WPORT PORTE
#define PE2_PIN PINE2 #define PE0_PWM NULL
#define PE2_RPORT PINE #define PE0_DDR DDRE
#define PE2_WPORT PORTE #undef PE1
#define PE2_PWM NULL #define PE1_PIN PINE1
#define PE2_DDR DDRE #define PE1_RPORT PINE
#undef PE3 #define PE1_WPORT PORTE
#define PE3_PIN PINE3 #define PE1_PWM NULL
#define PE3_RPORT PINE #define PE1_DDR DDRE
#define PE3_WPORT PORTE #undef PE2
#define PE3_PWM NULL #define PE2_PIN PINE2
#define PE3_DDR DDRE #define PE2_RPORT PINE
#undef PE4 #define PE2_WPORT PORTE
#define PE4_PIN PINE4 #define PE2_PWM NULL
#define PE4_RPORT PINE #define PE2_DDR DDRE
#define PE4_WPORT PORTE #undef PE3
#define PE4_PWM NULL #define PE3_PIN PINE3
#define PE4_DDR DDRE #define PE3_RPORT PINE
#undef PE5 #define PE3_WPORT PORTE
#define PE5_PIN PINE5 #define PE3_PWM NULL
#define PE5_RPORT PINE #define PE3_DDR DDRE
#define PE5_WPORT PORTE #undef PE4
#define PE5_PWM NULL #define PE4_PIN PINE4
#define PE5_DDR DDRE #define PE4_RPORT PINE
#undef PE6 #define PE4_WPORT PORTE
#define PE6_PIN PINE6 #define PE4_PWM NULL
#define PE6_RPORT PINE #define PE4_DDR DDRE
#define PE6_WPORT PORTE #undef PE5
#define PE6_PWM NULL #define PE5_PIN PINE5
#define PE6_DDR DDRE #define PE5_RPORT PINE
#undef PE7 #define PE5_WPORT PORTE
#define PE7_PIN PINE7 #define PE5_PWM NULL
#define PE7_RPORT PINE #define PE5_DDR DDRE
#define PE7_WPORT PORTE #undef PE6
#define PE7_PWM NULL #define PE6_PIN PINE6
#define PE7_DDR DDRE #define PE6_RPORT PINE
#define PE6_WPORT PORTE
#undef PF0 #define PE6_PWM NULL
#define PF0_PIN PINF0 #define PE6_DDR DDRE
#define PF0_RPORT PINF #undef PE7
#define PF0_WPORT PORTF #define PE7_PIN PINE7
#define PF0_PWM NULL #define PE7_RPORT PINE
#define PF0_DDR DDRF #define PE7_WPORT PORTE
#undef PF1 #define PE7_PWM NULL
#define PF1_PIN PINF1 #define PE7_DDR DDRE
#define PF1_RPORT PINF
#define PF1_WPORT PORTF #undef PF0
#define PF1_PWM NULL #define PF0_PIN PINF0
#define PF1_DDR DDRF #define PF0_RPORT PINF
#undef PF2 #define PF0_WPORT PORTF
#define PF2_PIN PINF2 #define PF0_PWM NULL
#define PF2_RPORT PINF #define PF0_DDR DDRF
#define PF2_WPORT PORTF #undef PF1
#define PF2_PWM NULL #define PF1_PIN PINF1
#define PF2_DDR DDRF #define PF1_RPORT PINF
#undef PF3 #define PF1_WPORT PORTF
#define PF3_PIN PINF3 #define PF1_PWM NULL
#define PF3_RPORT PINF #define PF1_DDR DDRF
#define PF3_WPORT PORTF #undef PF2
#define PF3_PWM NULL #define PF2_PIN PINF2
#define PF3_DDR DDRF #define PF2_RPORT PINF
#undef PF4 #define PF2_WPORT PORTF
#define PF4_PIN PINF4 #define PF2_PWM NULL
#define PF4_RPORT PINF #define PF2_DDR DDRF
#define PF4_WPORT PORTF #undef PF3
#define PF4_PWM NULL #define PF3_PIN PINF3
#define PF4_DDR DDRF #define PF3_RPORT PINF
#undef PF5 #define PF3_WPORT PORTF
#define PF5_PIN PINF5 #define PF3_PWM NULL
#define PF5_RPORT PINF #define PF3_DDR DDRF
#define PF5_WPORT PORTF #undef PF4
#define PF5_PWM NULL #define PF4_PIN PINF4
#define PF5_DDR DDRF #define PF4_RPORT PINF
#undef PF6 #define PF4_WPORT PORTF
#define PF6_PIN PINF6 #define PF4_PWM NULL
#define PF6_RPORT PINF #define PF4_DDR DDRF
#define PF6_WPORT PORTF #undef PF5
#define PF6_PWM NULL #define PF5_PIN PINF5
#define PF6_DDR DDRF #define PF5_RPORT PINF
#undef PF7 #define PF5_WPORT PORTF
#define PF7_PIN PINF7 #define PF5_PWM NULL
#define PF7_RPORT PINF #define PF5_DDR DDRF
#define PF7_WPORT PORTF #undef PF6
#define PF7_PWM NULL #define PF6_PIN PINF6
#define PF7_DDR DDRF #define PF6_RPORT PINF
#endif #define PF6_WPORT PORTF
#define PF6_PWM NULL
#ifndef DIO0_PIN #define PF6_DDR DDRF
#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 #undef PF7
#endif #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,738 +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 E0_STEP_PIN 11 #define E0_STEP_PIN 11
#define E0_DIR_PIN 12 #define E0_DIR_PIN 12
#define E0_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 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!!!!!!!!! #define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define TEMP_1_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #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 TEMP_2_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define HEATER_BED_PIN -1 #define HEATER_BED_PIN -1
#define TEMP_BED_PIN -1 #define TEMP_BED_PIN -1
#endif #endif
/**************************************************************************************** /****************************************************************************************
* Sanguino/RepRap Motherboard with direct-drive extruders * Sanguino/RepRap Motherboard with direct-drive extruders
* *
* ATMega644P * ATMega644P
* *
* +---\/---+ * +---\/---+
* (D 0) PB0 1| |40 PA0 (AI 0 / D31) * (D 0) PB0 1| |40 PA0 (AI 0 / D31)
* (D 1) PB1 2| |39 PA1 (AI 1 / D30) * (D 1) PB1 2| |39 PA1 (AI 1 / D30)
* INT2 (D 2) PB2 3| |38 PA2 (AI 2 / D29) * INT2 (D 2) PB2 3| |38 PA2 (AI 2 / D29)
* PWM (D 3) PB3 4| |37 PA3 (AI 3 / D28) * PWM (D 3) PB3 4| |37 PA3 (AI 3 / D28)
* PWM (D 4) PB4 5| |36 PA4 (AI 4 / D27) * PWM (D 4) PB4 5| |36 PA4 (AI 4 / D27)
* MOSI (D 5) PB5 6| |35 PA5 (AI 5 / D26) * MOSI (D 5) PB5 6| |35 PA5 (AI 5 / D26)
* MISO (D 6) PB6 7| |34 PA6 (AI 6 / D25) * MISO (D 6) PB6 7| |34 PA6 (AI 6 / D25)
* SCK (D 7) PB7 8| |33 PA7 (AI 7 / D24) * SCK (D 7) PB7 8| |33 PA7 (AI 7 / D24)
* RST 9| |32 AREF * RST 9| |32 AREF
* VCC 10| |31 GND * VCC 10| |31 GND
* GND 11| |30 AVCC * GND 11| |30 AVCC
* XTAL2 12| |29 PC7 (D 23) * XTAL2 12| |29 PC7 (D 23)
* XTAL1 13| |28 PC6 (D 22) * XTAL1 13| |28 PC6 (D 22)
* RX0 (D 8) PD0 14| |27 PC5 (D 21) TDI * RX0 (D 8) PD0 14| |27 PC5 (D 21) TDI
* TX0 (D 9) PD1 15| |26 PC4 (D 20) TDO * TX0 (D 9) PD1 15| |26 PC4 (D 20) TDO
* INT0 RX1 (D 10) PD2 16| |25 PC3 (D 19) TMS * INT0 RX1 (D 10) PD2 16| |25 PC3 (D 19) TMS
* INT1 TX1 (D 11) PD3 17| |24 PC2 (D 18) TCK * INT1 TX1 (D 11) PD3 17| |24 PC2 (D 18) TCK
* PWM (D 12) PD4 18| |23 PC1 (D 17) SDA * PWM (D 12) PD4 18| |23 PC1 (D 17) SDA
* PWM (D 13) PD5 19| |22 PC0 (D 16) SCL * PWM (D 13) PD5 19| |22 PC0 (D 16) SCL
* PWM (D 14) PD6 20| |21 PD7 (D 15) PWM * PWM (D 14) PD6 20| |21 PD7 (D 15) PWM
* +--------+ * +--------+
* *
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 1 #if MOTHERBOARD == 1
#define KNOWN_BOARD 1 #define KNOWN_BOARD 1
#ifndef __AVR_ATmega644P__ #ifndef __AVR_ATmega644P__
#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
#endif #endif
#define X_STEP_PIN 15 #define X_STEP_PIN 15
#define X_DIR_PIN 18 #define X_DIR_PIN 18
#define X_ENABLE_PIN 19 #define X_ENABLE_PIN 19
#define X_MIN_PIN 20 #define X_MIN_PIN 20
#define X_MAX_PIN 21 #define X_MAX_PIN 21
#define Y_STEP_PIN 23 #define Y_STEP_PIN 23
#define Y_DIR_PIN 22 #define Y_DIR_PIN 22
#define Y_ENABLE_PIN 19 #define Y_ENABLE_PIN 19
#define Y_MIN_PIN 25 #define Y_MIN_PIN 25
#define Y_MAX_PIN 26 #define Y_MAX_PIN 26
#define Z_STEP_PIN 29 #define Z_STEP_PIN 29
#define Z_DIR_PIN 30 #define Z_DIR_PIN 30
#define Z_ENABLE_PIN 31 #define Z_ENABLE_PIN 31
#define Z_MIN_PIN 2 #define Z_MIN_PIN 2
#define Z_MAX_PIN 1 #define Z_MAX_PIN 1
#define E0_STEP_PIN 12 #define E0_STEP_PIN 12
#define E0_DIR_PIN 16 #define E0_DIR_PIN 16
#define E0_ENABLE_PIN 3 #define E0_ENABLE_PIN 3
#define SDPOWER -1 #define SDPOWER -1
#define SDSS -1 #define SDSS -1
#define LED_PIN 0 #define LED_PIN 0
#define FAN_PIN -1 #define FAN_PIN -1
#define PS_ON_PIN -1 #define PS_ON_PIN -1
#define KILL_PIN -1 #define KILL_PIN -1
#define HEATER_0_PIN 14 #define HEATER_0_PIN 14
#define HEATER_1_PIN -1 #define HEATER_1_PIN -1
#define HEATER_2_PIN -1 #define HEATER_2_PIN -1
#define TEMP_0_PIN 4 //D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define TEMP_0_PIN 4 //D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define TEMP_1_PIN -1 #define TEMP_1_PIN -1
#define TEMP_2_PIN -1 #define TEMP_2_PIN -1
#define HEATER_BED_PIN -1 #define HEATER_BED_PIN -1
#define TEMP_BED_PIN -1 #define TEMP_BED_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) */ /* 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) */
#endif #endif
/**************************************************************************************** /****************************************************************************************
* RepRap Motherboard ****---NOOOOOO RS485/EXTRUDER CONTROLLER!!!!!!!!!!!!!!!!!---******* * RepRap Motherboard ****---NOOOOOO RS485/EXTRUDER CONTROLLER!!!!!!!!!!!!!!!!!---*******
* *
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 2 #if MOTHERBOARD == 2
#define KNOWN_BOARD 1 #define KNOWN_BOARD 1
#ifndef __AVR_ATmega644P__ #ifndef __AVR_ATmega644P__
#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
#endif #endif
#define X_STEP_PIN 15 #define X_STEP_PIN 15
#define X_DIR_PIN 18 #define X_DIR_PIN 18
#define X_ENABLE_PIN 19 #define X_ENABLE_PIN 19
#define X_MIN_PIN 20 #define X_MIN_PIN 20
#define X_MAX_PIN 21 #define X_MAX_PIN 21
#define Y_STEP_PIN 23 #define Y_STEP_PIN 23
#define Y_DIR_PIN 22 #define Y_DIR_PIN 22
#define Y_ENABLE_PIN 24 #define Y_ENABLE_PIN 24
#define Y_MIN_PIN 25 #define Y_MIN_PIN 25
#define Y_MAX_PIN 26 #define Y_MAX_PIN 26
#define Z_STEP_PINN 27 #define Z_STEP_PINN 27
#define Z_DIR_PINN 28 #define Z_DIR_PINN 28
#define Z_ENABLE_PIN 29 #define Z_ENABLE_PIN 29
#define Z_MIN_PIN 30 #define Z_MIN_PIN 30
#define Z_MAX_PIN 31 #define Z_MAX_PIN 31
#define E0_STEP_PIN 17 #define E0_STEP_PIN 17
#define E0_DIR_PIN 16 #define E0_DIR_PIN 16
#define E0_ENABLE_PIN -1 #define E0_ENABLE_PIN -1
#define SDPOWER -1 #define SDPOWER -1
#define SDSS 4 #define SDSS 4
#define LED_PIN 0 #define LED_PIN 0
#define SD_CARD_WRITE 2 #define SD_CARD_WRITE 2
#define SD_CARD_DETECT 3 #define SD_CARD_DETECT 3
#define SD_CARD_SELECT 4 #define SD_CARD_SELECT 4
//our RS485 pins //our RS485 pins
#define TX_ENABLE_PIN 12 #define TX_ENABLE_PIN 12
#define RX_ENABLE_PIN 13 #define RX_ENABLE_PIN 13
//pin for controlling the PSU. //pin for controlling the PSU.
#define PS_ON_PIN 14 #define PS_ON_PIN 14
#define FAN_PIN -1 #define FAN_PIN -1
#define KILL_PIN -1 #define KILL_PIN -1
#define HEATER_0_PIN -1 #define HEATER_0_PIN -1
#define HEATER_1_PIN -1 #define HEATER_1_PIN -1
#define HEATER_2_PIN -1 #define HEATER_2_PIN -1
#define TEMP_0_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define TEMP_0_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define TEMP_1_PIN -1 #define TEMP_1_PIN -1
#define TEMP_2_PIN -1 #define TEMP_2_PIN -1
#define HEATER_BED_PIN -1 #define HEATER_BED_PIN -1
#define TEMP_BED_PIN -1 #define TEMP_BED_PIN -1
#endif #endif
/**************************************************************************************** /****************************************************************************************
* Arduino Mega pin assignment * Arduino Mega pin assignment
* *
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 33 #if MOTHERBOARD == 33
#define MOTHERBOARD 3 #define MOTHERBOARD 3
#define RAMPS_V_1_3 #define RAMPS_V_1_3
#endif #endif
#if MOTHERBOARD == 3 #if MOTHERBOARD == 3
#define KNOWN_BOARD 1 #define KNOWN_BOARD 1
//////////////////FIX THIS////////////// //////////////////FIX THIS//////////////
#ifndef __AVR_ATmega1280__ #ifndef __AVR_ATmega1280__
#ifndef __AVR_ATmega2560__ #ifndef __AVR_ATmega2560__
#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. #error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
#endif #endif
#endif #endif
// uncomment one of the following lines for RAMPS v1.3 or v1.0, comment both for v1.2 or 1.1 // 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 RAMPS_V_1_3
// #define RAMPS_V_1_0 // #define RAMPS_V_1_0
#ifdef RAMPS_V_1_3 #ifdef RAMPS_V_1_3
#define X_STEP_PIN 54 #define X_STEP_PIN 54
#define X_DIR_PIN 55 #define X_DIR_PIN 55
#define X_ENABLE_PIN 38 #define X_ENABLE_PIN 38
#define X_MIN_PIN 3 #define X_MIN_PIN 3
#define X_MAX_PIN 2 //2 //Max endstops default to disabled "-1", set to commented value to enable. #define X_MAX_PIN 2 //2 //Max endstops default to disabled "-1", set to commented value to enable.
#define Y_STEP_PIN 60 #define Y_STEP_PIN 60
#define Y_DIR_PIN 61 #define Y_DIR_PIN 61
#define Y_ENABLE_PIN 56 #define Y_ENABLE_PIN 56
#define Y_MIN_PIN 14 #define Y_MIN_PIN 14
#define Y_MAX_PIN 15 //15 #define Y_MAX_PIN 15 //15
#define Z_STEP_PIN 46 #define Z_STEP_PIN 46
#define Z_DIR_PIN 48 #define Z_DIR_PIN 48
#define Z_ENABLE_PIN 62 #define Z_ENABLE_PIN 62
#define Z_MIN_PIN 18 #define Z_MIN_PIN 18
#define Z_MAX_PIN 19 //19 #define Z_MAX_PIN 19 //19
#define E0_STEP_PIN 26 #define E0_STEP_PIN 26
#define E0_DIR_PIN 28 #define E0_DIR_PIN 28
#define E0_ENABLE_PIN 24 #define E0_ENABLE_PIN 24
#define E1_STEP_PIN 36 #define E1_STEP_PIN 36
#define E1_DIR_PIN 34 #define E1_DIR_PIN 34
#define E1_ENABLE_PIN 30 #define E1_ENABLE_PIN 30
#define SDPOWER -1 #define SDPOWER -1
#define SDSS 53 #define SDSS 53
#define LED_PIN 13 #define LED_PIN 13
#define FAN_PIN 4 #define FAN_PIN 4
#define PS_ON_PIN 12 #define PS_ON_PIN 12
#define KILL_PIN -1 #define KILL_PIN -1
#define HEATER_0_PIN 10 // EXTRUDER 1 #define HEATER_0_PIN 10 // EXTRUDER 1
#define HEATER_1_PIN 9 // EXTRUDER 2 #define HEATER_1_PIN 9 // EXTRUDER 2
#define HEATER_2_PIN -1 // EXTRUDER 2 #define HEATER_2_PIN -1 // EXTRUDER 2
#define TEMP_0_PIN 13 // ANALOG NUMBERING #define TEMP_0_PIN 13 // ANALOG NUMBERING
#define TEMP_1_PIN 15 // ANALOG NUMBERING #define TEMP_1_PIN 15 // ANALOG NUMBERING
#define TEMP_2_PIN -1 // ANALOG NUMBERING #define TEMP_2_PIN -1 // ANALOG NUMBERING
#define HEATER_BED_PIN 8 // BED #define HEATER_BED_PIN 8 // BED
#define TEMP_BED_PIN 14 // ANALOG NUMBERING #define TEMP_BED_PIN 14 // ANALOG NUMBERING
#else // RAMPS_V_1_1 or RAMPS_V_1_2 as default #else // RAMPS_V_1_1 or RAMPS_V_1_2 as default
#define X_STEP_PIN 26 #define X_STEP_PIN 26
#define X_DIR_PIN 28 #define X_DIR_PIN 28
#define X_ENABLE_PIN 24 #define X_ENABLE_PIN 24
#define X_MIN_PIN 3 #define X_MIN_PIN 3
#define X_MAX_PIN -1 //2 #define X_MAX_PIN -1 //2
#define Y_STEP_PIN 38 #define Y_STEP_PIN 38
#define Y_DIR_PIN 40 #define Y_DIR_PIN 40
#define Y_ENABLE_PIN 36 #define Y_ENABLE_PIN 36
#define Y_MIN_PIN 16 #define Y_MIN_PIN 16
#define Y_MAX_PIN -1 //17 #define Y_MAX_PIN -1 //17
#define Z_STEP_PIN 44 #define Z_STEP_PIN 44
#define Z_DIR_PIN 46 #define Z_DIR_PIN 46
#define Z_ENABLE_PIN 42 #define Z_ENABLE_PIN 42
#define Z_MIN_PIN 18 #define Z_MIN_PIN 18
#define Z_MAX_PIN -1 //19 #define Z_MAX_PIN -1 //19
#define E0_STEP_PIN 32 #define E0_STEP_PIN 32
#define E0_DIR_PIN 34 #define E0_DIR_PIN 34
#define E0_ENABLE_PIN 30 #define E0_ENABLE_PIN 30
#define SDPOWER 48 #define SDPOWER 48
#define SDSS 53 #define SDSS 53
#define LED_PIN 13 #define LED_PIN 13
#define PS_ON_PIN -1 #define PS_ON_PIN -1
#define KILL_PIN -1 #define KILL_PIN -1
#ifdef RAMPS_V_1_0 // RAMPS_V_1_0 #ifdef RAMPS_V_1_0 // RAMPS_V_1_0
#define HEATER_0_PIN 12 // RAMPS 1.0 #define HEATER_0_PIN 12 // RAMPS 1.0
#define HEATER_BED_PIN -1 // RAMPS 1.0 #define HEATER_BED_PIN -1 // RAMPS 1.0
#define FAN_PIN 11 // RAMPS 1.0 #define FAN_PIN 11 // RAMPS 1.0
#else // RAMPS_V_1_1 or RAMPS_V_1_2 #else // RAMPS_V_1_1 or RAMPS_V_1_2
#define HEATER_0_PIN 10 // RAMPS 1.1 #define HEATER_0_PIN 10 // RAMPS 1.1
#define HEATER_BED_PIN 8 // RAMPS 1.1 #define HEATER_BED_PIN 8 // RAMPS 1.1
#define FAN_PIN 9 // RAMPS 1.1 #define FAN_PIN 9 // RAMPS 1.1
#endif #endif
#define HEATER_1_PIN -1 #define HEATER_1_PIN -1
#define HEATER_2_PIN -1 #define HEATER_2_PIN -1
#define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define TEMP_1_PIN -1 #define TEMP_1_PIN -1
#define TEMP_2_PIN -1 #define TEMP_2_PIN -1
#define TEMP_BED_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define TEMP_BED_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#endif #endif
// SPI for Max6675 Thermocouple // SPI for Max6675 Thermocouple
#ifndef SDSUPPORT #ifndef SDSUPPORT
// these pins are defined in the SD library if building with SD support #define SCK_PIN 52 // these pins are defined in the SD library if building with SD support #define SCK_PIN 52
#define MISO_PIN 50 #define MISO_PIN 50
#define MOSI_PIN 51 #define MOSI_PIN 51
#define MAX6675_SS 53 #define MAX6675_SS 53
#else #else
#define MAX6675_SS 49 #define MAX6675_SS 49
#endif #endif
#endif #endif
/**************************************************************************************** /****************************************************************************************
* Duemilanove w/ ATMega328P pin assignment * Duemilanove w/ ATMega328P pin assignment
* *
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 4 #if MOTHERBOARD == 4
#define KNOWN_BOARD 1 #define KNOWN_BOARD 1
#ifndef __AVR_ATmega328P__ #ifndef __AVR_ATmega328P__
#error Oops! Make sure you have 'Arduino Duemilanove w/ ATMega328' selected from the 'Tools -> Boards' menu. #error Oops! Make sure you have 'Arduino Duemilanove w/ ATMega328' selected from the 'Tools -> Boards' menu.
#endif #endif
#define X_STEP_PIN 19 #define X_STEP_PIN 19
#define X_DIR_PIN 18 #define X_DIR_PIN 18
#define X_ENABLE_PIN -1 #define X_ENABLE_PIN -1
#define X_MIN_PIN 17 #define X_MIN_PIN 17
#define X_MAX_PIN -1 #define X_MAX_PIN -1
#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 -1 #define Y_MAX_PIN -1
#define Z_STEP_PIN 13 #define Z_STEP_PIN 13
#define Z_DIR_PIN 3 #define Z_DIR_PIN 3
#define Z_ENABLE_PIN 2 #define Z_ENABLE_PIN 2
#define Z_MIN_PIN 4 #define Z_MIN_PIN 4
#define Z_MAX_PIN -1 #define Z_MAX_PIN -1
#define E0_STEP_PIN 11 #define E0_STEP_PIN 11
#define E0_DIR_PIN 12 #define E0_DIR_PIN 12
#define E0_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 5 #define FAN_PIN 5
#define PS_ON_PIN -1 #define PS_ON_PIN -1
#define KILL_PIN -1 #define KILL_PIN -1
#define HEATER_0_PIN 6 #define HEATER_0_PIN 6
#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!!!!!!!!! #define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
#define TEMP_1_PIN -1 #define TEMP_1_PIN -1
#define TEMP_2_PIN -1 #define TEMP_2_PIN -1
#define HEATER_BED_PIN -1 #define HEATER_BED_PIN -1
#define TEMP_BED_PIN -1 #define TEMP_BED_PIN -1
#endif #endif
/**************************************************************************************** /****************************************************************************************
* Gen6 pin assignment * Gen6 pin assignment
* *
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 5 #if MOTHERBOARD == 5
#define KNOWN_BOARD 1 #define KNOWN_BOARD 1
#ifndef __AVR_ATmega644P__ #ifndef __AVR_ATmega644P__
#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
#endif #endif
//x axis pins //x axis pins
#define X_STEP_PIN 15 #define X_STEP_PIN 15
#define X_DIR_PIN 18 #define X_DIR_PIN 18
#define X_ENABLE_PIN 19 #define X_ENABLE_PIN 19
#define X_MIN_PIN 20 #define X_MIN_PIN 20
#define X_MAX_PIN -1 #define X_MAX_PIN -1
//y axis pins //y axis pins
#define Y_STEP_PIN 23 #define Y_STEP_PIN 23
#define Y_DIR_PIN 22 #define Y_DIR_PIN 22
#define Y_ENABLE_PIN 24 #define Y_ENABLE_PIN 24
#define Y_MIN_PIN 25 #define Y_MIN_PIN 25
#define Y_MAX_PIN -1 #define Y_MAX_PIN -1
//z axis pins //z axis pins
#define Z_STEP_PIN 27 #define Z_STEP_PIN 27
#define Z_DIR_PIN 28 #define Z_DIR_PIN 28
#define Z_ENABLE_PIN 29 #define Z_ENABLE_PIN 29
#define Z_MIN_PIN 30 #define Z_MIN_PIN 30
#define Z_MAX_PIN -1 #define Z_MAX_PIN -1
//extruder pins //extruder pins
#define E0_STEP_PIN 4 //Edited @ EJE Electronics 20100715 #define E0_STEP_PIN 4 //Edited @ EJE Electronics 20100715
#define E0_DIR_PIN 2 //Edited @ EJE Electronics 20100715 #define E0_DIR_PIN 2 //Edited @ EJE Electronics 20100715
#define E0_ENABLE_PIN 3 //Added @ EJE Electronics 20100715 #define E0_ENABLE_PIN 3 //Added @ EJE Electronics 20100715
#define TEMP_0_PIN 5 //changed @ rkoeppl 20110410 #define TEMP_0_PIN 5 //changed @ rkoeppl 20110410
#define TEMP_1_PIN -1 //changed @ rkoeppl 20110410 #define TEMP_1_PIN -1 //changed @ rkoeppl 20110410
#define TEMP_2_PIN -1 //changed @ rkoeppl 20110410 #define TEMP_2_PIN -1 //changed @ rkoeppl 20110410
#define HEATER_0_PIN 14 //changed @ rkoeppl 20110410 #define HEATER_0_PIN 14 //changed @ rkoeppl 20110410
#define HEATER_1_PIN -1 #define HEATER_1_PIN -1
#define HEATER_2_PIN -1 #define HEATER_2_PIN -1
#define HEATER_BED_PIN -1 //changed @ rkoeppl 20110410 #define HEATER_BED_PIN -1 //changed @ rkoeppl 20110410
#define TEMP_BED_PIN -1 //changed @ rkoeppl 20110410 #define TEMP_BED_PIN -1 //changed @ rkoeppl 20110410
#define SDPOWER -1 #define SDPOWER -1
#define SDSS 17 #define SDSS 17
#define LED_PIN -1 //changed @ rkoeppl 20110410 #define LED_PIN -1 //changed @ rkoeppl 20110410
#define FAN_PIN -1 //changed @ rkoeppl 20110410 #define FAN_PIN -1 //changed @ rkoeppl 20110410
#define PS_ON_PIN -1 //changed @ rkoeppl 20110410 #define PS_ON_PIN -1 //changed @ rkoeppl 20110410
//our pin for debugging. //our pin for debugging.
#define DEBUG_PIN 0 #define DEBUG_PIN 0
//our RS485 pins //our RS485 pins
#define TX_ENABLE_PIN 12 #define TX_ENABLE_PIN 12
#define RX_ENABLE_PIN 13 #define RX_ENABLE_PIN 13
#endif #endif
/**************************************************************************************** /****************************************************************************************
* Sanguinololu pin assignment * Sanguinololu pin assignment
* *
****************************************************************************************/ ****************************************************************************************/
#if MOTHERBOARD == 62 #if MOTHERBOARD == 62
#define MOTHERBOARD 6 #define MOTHERBOARD 6
#define SANGUINOLOLU_V_1_2 #define SANGUINOLOLU_V_1_2
#endif #endif
#if MOTHERBOARD == 6 #if MOTHERBOARD == 6
#define KNOWN_BOARD 1 #define KNOWN_BOARD 1
#ifndef __AVR_ATmega644P__ #ifndef __AVR_ATmega644P__
#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
#endif #endif
#define X_STEP_PIN 15 #define X_STEP_PIN 15
#define X_DIR_PIN 21 #define X_DIR_PIN 21
#define X_MIN_PIN 18 #define X_MIN_PIN 18
#define X_MAX_PIN -2 #define X_MAX_PIN -2
#define Y_STEP_PIN 22 #define Y_STEP_PIN 22
#define Y_DIR_PIN 23 #define Y_DIR_PIN 23
#define Y_MIN_PIN 19 #define Y_MIN_PIN 19
#define Y_MAX_PIN -1 #define Y_MAX_PIN -1
#define Z_STEP_PIN 3 #define Z_STEP_PIN 3
#define Z_DIR_PIN 2 #define Z_DIR_PIN 2
#define Z_MIN_PIN 20 #define Z_MIN_PIN 20
#define Z_MAX_PIN -1 #define Z_MAX_PIN -1
#define E0_STEP_PIN 1 #define E0_STEP_PIN 1
#define E0_DIR_PIN 0 #define E0_DIR_PIN 0
#define LED_PIN -1 #define LED_PIN -1
#define FAN_PIN -1 #define FAN_PIN -1
#define PS_ON_PIN -1 #define PS_ON_PIN -1
#define KILL_PIN -1 #define KILL_PIN -1
#define HEATER_0_PIN 13 // (extruder) #define HEATER_0_PIN 13 // (extruder)
#define HEATER_1_PIN -1 #define HEATER_1_PIN -1
#define HEATER_2_PIN -1 #define HEATER_2_PIN -1
#ifdef SANGUINOLOLU_V_1_2 #ifdef SANGUINOLOLU_V_1_2
#define HEATER_BED_PIN 12 // (bed) #define HEATER_BED_PIN 12 // (bed)
#define X_ENABLE_PIN 14 #define X_ENABLE_PIN 14
#define Y_ENABLE_PIN 14 #define Y_ENABLE_PIN 14
#define Z_ENABLE_PIN 26 #define Z_ENABLE_PIN 26
#define E0_ENABLE_PIN 14 #define E0_ENABLE_PIN 14
#else #else
#define HEATER_BED_PIN 14 // (bed) #define HEATER_BED_PIN 14 // (bed)
#define X_ENABLE_PIN -1 #define X_ENABLE_PIN -1
#define Y_ENABLE_PIN -1 #define Y_ENABLE_PIN -1
#define Z_ENABLE_PIN -1 #define Z_ENABLE_PIN -1
#define E0_ENABLE_PIN -1 #define E0_ENABLE_PIN -1
#endif #endif
#define TEMP_0_PIN 7 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) #define TEMP_0_PIN 7 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder)
#define TEMP_1_PIN -1 #define TEMP_1_PIN -1
#define TEMP_2_PIN -1 #define TEMP_2_PIN -1
#define TEMP_BED_PIN 6 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) #define TEMP_BED_PIN 6 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
#define SDPOWER -1 #define SDPOWER -1
#define SDSS 31 #define SDSS 31
#endif #endif
#if MOTHERBOARD == 7 #if MOTHERBOARD == 7
#define KNOWN_BOARD #define KNOWN_BOARD
/***************************************************************** /*****************************************************************
* Ultimaker pin assignment * Ultimaker pin assignment
******************************************************************/ ******************************************************************/
#ifndef __AVR_ATmega1280__ #ifndef __AVR_ATmega1280__
#ifndef __AVR_ATmega2560__ #ifndef __AVR_ATmega2560__
#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. #error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
#endif #endif
#endif #endif
#define X_STEP_PIN 25 #define X_STEP_PIN 25
#define X_DIR_PIN 23 #define X_DIR_PIN 23
#define X_MIN_PIN 22 #define X_MIN_PIN 22
#define X_MAX_PIN 24 #define X_MAX_PIN 24
#define X_ENABLE_PIN 27 #define X_ENABLE_PIN 27
#define Y_STEP_PIN 31 #define Y_STEP_PIN 31
#define Y_DIR_PIN 33 #define Y_DIR_PIN 33
#define Y_MIN_PIN 26 #define Y_MIN_PIN 26
#define Y_MAX_PIN 28 #define Y_MAX_PIN 28
#define Y_ENABLE_PIN 29 #define Y_ENABLE_PIN 29
#define Z_STEP_PIN 37 #define Z_STEP_PIN 37
#define Z_DIR_PIN 39 #define Z_DIR_PIN 39
#define Z_MIN_PIN 30 #define Z_MIN_PIN 30
#define Z_MAX_PIN 32 #define Z_MAX_PIN 32
#define Z_ENABLE_PIN 35 #define Z_ENABLE_PIN 35
#define HEATER_BED_PIN 4 #define HEATER_BED_PIN 4
#define TEMP_BED_PIN 11 #define TEMP_BED_PIN 11
#define EXTRUDER_0_STEP_PIN 43 #define HEATER_0_PIN 2
#define EXTRUDER_0_DIR_PIN 45 #define TEMP_0_PIN 8
#define EXTRUDER_0_ENABLE_PIN 41
#define HEATER_0_PIN 2 #define EXTRUDER_1_HEATER_PIN 3
#define TEMP_0_PIN 8 #define EXTRUDER_1_TEMPERATURE_PIN 10
#define HEATER_1_PIN 51
#define EXTRUDER_1_STEP_PIN 49 #define TEMP_1_PIN 3
#define EXTRUDER_1_DIR_PIN 47
#define EXTRUDER_1_ENABLE_PIN 51 #define HEATER_2_PIN -1
#define EXTRUDER_1_HEATER_PIN 3 #define TEMP_2_PIN -1
#define EXTRUDER_1_TEMPERATURE_PIN 10
#define HEATER_1_PIN 51 #define E0_STEP_PIN 43
#define TEMP_1_PIN 3 #define E0_DIR_PIN 45
#define E0_ENABLE_PIN 41
#define E1_STEP_PIN 49
#define E0_STEP_PIN EXTRUDER_0_STEP_PIN #define E1_DIR_PIN 47
#define E0_DIR_PIN EXTRUDER_0_DIR_PIN #define E1_ENABLE_PIN 51
#define E0_ENABLE_PIN EXTRUDER_0_ENABLE_PIN
#define SDPOWER -1
#define SDPOWER -1 #define SDSS 53
#define SDSS 53 #define LED_PIN 13
#define LED_PIN 13 #define FAN_PIN 7
#define FAN_PIN 7 #define PS_ON_PIN 12
#define PS_ON_PIN 12 #define KILL_PIN -1
#define KILL_PIN -1
#ifdef ULTRA_LCD
#ifdef ULTRA_LCD
#ifdef NEWPANEL
#ifdef NEWPANEL //arduino pin witch triggers an piezzo beeper
//arduino pin witch triggers an piezzo beeper #define BEEPER 18
#define BEEPER 18
#define LCD_PINS_RS 20
#define LCD_PINS_RS 20 #define LCD_PINS_ENABLE 17
#define LCD_PINS_ENABLE 17 #define LCD_PINS_D4 16
#define LCD_PINS_D4 16 #define LCD_PINS_D5 21
#define LCD_PINS_D5 21 #define LCD_PINS_D6 5
#define LCD_PINS_D6 5 #define LCD_PINS_D7 6
#define LCD_PINS_D7 6
//buttons are directly attached
//buttons are directly attached #define BTN_EN1 40
#define BTN_EN1 40 #define BTN_EN2 42
#define BTN_EN2 42 #define BTN_ENC 19 //the click
#define BTN_ENC 19 //the click
#define BLEN_C 2
#define BLEN_C 2 #define BLEN_B 1
#define BLEN_B 1 #define BLEN_A 0
#define BLEN_A 0
#define SDCARDDETECT 38
#define SDCARDDETECT 38
//encoder rotation values
//encoder rotation values #define encrot0 0
#define encrot0 0 #define encrot1 2
#define encrot1 2 #define encrot2 3
#define encrot2 3 #define encrot3 1
#define encrot3 1 #else //old style panel with shift register
#else //old style panel with shift register //arduino pin witch triggers an piezzo beeper
//arduino pin witch triggers an piezzo beeper #define BEEPER 18
#define BEEPER 18
//buttons are attached to a shift register
//buttons are attached to a shift register #define SHIFT_CLK 38
#define SHIFT_CLK 38 #define SHIFT_LD 42
#define SHIFT_LD 42 #define SHIFT_OUT 40
#define SHIFT_OUT 40 #define SHIFT_EN 17
#define SHIFT_EN 17
#define LCD_PINS_RS 16
#define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 5
#define LCD_PINS_ENABLE 5 #define LCD_PINS_D4 6
#define LCD_PINS_D4 6 #define LCD_PINS_D5 21
#define LCD_PINS_D5 21 #define LCD_PINS_D6 20
#define LCD_PINS_D6 20 #define LCD_PINS_D7 19
#define LCD_PINS_D7 19
//encoder rotation values
//encoder rotation values #define encrot0 0
#define encrot0 0 #define encrot1 2
#define encrot1 2 #define encrot2 3
#define encrot2 3 #define encrot3 1
#define encrot3 1
//bits in the shift register that carry the buttons for:
//bits in the shift register that carry the buttons for: // left up center down right red
// left up center down right red #define BL_LE 7
#define BL_LE 7 #define BL_UP 6
#define BL_UP 6 #define BL_MI 5
#define BL_MI 5 #define BL_DW 4
#define BL_DW 4 #define BL_RI 3
#define BL_RI 3 #define BL_ST 2
#define BL_ST 2
#define BLEN_B 1
#define BLEN_B 1 #define BLEN_A 0
#define BLEN_A 0 #endif
#endif #endif //ULTRA_LCD
#endif //ULTRA_LCD
#endif
#endif
/****************************************************************************************
/**************************************************************************************** * Teensylu 0.7 pin assingments (ATMEGA90USB)
* Teensylu 0.7 pin assingments (ATMEGA90USB) * Requires the Teensyduino software with Teensy2.0++ selected in arduino IDE!
* Requires the Teensyduino software with Teensy2.0++ selected in arduino IDE! ****************************************************************************************/
****************************************************************************************/ #if MOTHERBOARD == 8
#if MOTHERBOARD == 8 #define MOTHERBOARD 8
#define MOTHERBOARD 8 #define KNOWN_BOARD 1
#define KNOWN_BOARD 1
#define X_STEP_PIN 0
#define X_STEP_PIN 0 #define X_DIR_PIN 1
#define X_DIR_PIN 1 #define X_ENABLE_PIN 39
#define X_ENABLE_PIN 39 #define X_MIN_PIN 13
#define X_MIN_PIN 13 #define X_MAX_PIN -1
#define X_MAX_PIN -1
#define Y_STEP_PIN 2
#define Y_STEP_PIN 2 #define Y_DIR_PIN 3
#define Y_DIR_PIN 3 #define Y_ENABLE_PIN 38
#define Y_ENABLE_PIN 38 #define Y_MIN_PIN 14
#define Y_MIN_PIN 14 #define Y_MAX_PIN -1
#define Y_MAX_PIN -1
#define Z_STEP_PIN 4
#define Z_STEP_PIN 4 #define Z_DIR_PIN 5
#define Z_DIR_PIN 5 #define Z_ENABLE_PIN 23
#define Z_ENABLE_PIN 23 #define Z_MIN_PIN 15
#define Z_MIN_PIN 15 #define Z_MAX_PIN -1
#define Z_MAX_PIN -1
#define E0_STEP_PIN 6
#define E0_STEP_PIN 6 #define E0_DIR_PIN 7
#define E0_DIR_PIN 7 #define E0_ENABLE_PIN 19
#define E0_ENABLE_PIN 19
#define HEATER_0_PIN 21 // Extruder
#define HEATER_0_PIN 21 // Extruder #define HEATER_1_PIN -1
#define HEATER_1_PIN -1 #define HEATER_2_PIN -1
#define HEATER_2_PIN -1 #define HEATER_BED_PIN 20 // Bed
#define HEATER_BED_PIN 20 // Bed #define FAN_PIN 22 // Fan
#define FAN_PIN 22 // Fan
#define TEMP_0_PIN 7 // Extruder
#define TEMP_0_PIN 7 // Extruder #define TEMP_1_PIN -1
#define TEMP_1_PIN -1 #define TEMP_2_PIN -1
#define TEMP_2_PIN -1 #define TEMP_BED_PIN 6 // Bed
#define TEMP_BED_PIN 6 // Bed
#define SDPOWER -1
#define SDPOWER -1 #define SDSS 8
#define SDSS 8 #define LED_PIN -1
#define LED_PIN -1 #define PS_ON_PIN -1
#define PS_ON_PIN -1 #define KILL_PIN -1
#define KILL_PIN -1 #define ALARM_PIN -1
#define ALARM_PIN -1
#ifndef SDSUPPORT
#ifndef SDSUPPORT // these pins are defined in the SD library if building with SD support
// these pins are defined in the SD library if building with SD support #define SCK_PIN 9
#define SCK_PIN 9 #define MISO_PIN 11
#define MISO_PIN 11 #define MOSI_PIN 10
#define MOSI_PIN 10 #endif
#endif #endif
#endif
#ifndef KNOWN_BOARD
#ifndef KNOWN_BOARD #error Unknown MOTHERBOARD value in configuration.h
#error Unknown MOTHERBOARD value in configuration.h #endif
#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!
//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
#define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN #if EXTRUDERS == 3
#if EXTRUDERS == 3 #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN
#define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN #define _E2_PINS E2_STEP_PIN, E2_DIR_PIN, E2_ENABLE_PIN
#define _E2_PINS E2_STEP_PIN, E2_DIR_PIN, E2_ENABLE_PIN #elif EXTRUDERS == 2
#elif EXTRUDERS == 2 #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN
#define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN #define _E2_PINS -1
#define _E2_PINS -1 #elif EXTRUDERS == 1
#elif EXTRUDERS == 1 #define _E1_PINS -1
#define _E1_PINS -1 #define _E2_PINS -1
#define _E2_PINS -1 #else
#else #error Unsupported number of extruders
#error Unsupported number of extruders #endif
#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, \
#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_0_PIN, HEATER_1_PIN, HEATER_2_PIN, \ HEATER_BED_PIN, FAN_PIN, \
HEATER_BED_PIN, FAN_PIN, \ _E0_PINS, _E1_PINS, _E2_PINS, \
_E0_PINS, _E1_PINS, _E2_PINS, \ TEMP_0_PIN, TEMP_1_PIN, TEMP_2_PIN, TEMP_BED_PIN }
TEMP_0_PIN, TEMP_1_PIN, TEMP_2_PIN, TEMP_BED_PIN }
#endif #endif

View file

@ -191,8 +191,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;

View file

@ -57,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;
@ -266,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;
@ -303,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 {
@ -418,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
NORM_E_DIR(); REV_E_DIR();
count_direction[E_AXIS]=-1; count_direction[E_AXIS]=-1;
} }
else { // +direction else { // +direction
REV_E_DIR(); NORM_E_DIR();
count_direction[E_AXIS]=-1; count_direction[E_AXIS]=-1;
} }
#endif //!ADVANCE #endif //!ADVANCE
@ -437,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
@ -503,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
@ -532,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
} }
@ -557,20 +557,50 @@ 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(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(INVERT_E_DIR); e_steps[0]++;
e_steps++; WRITE(E0_STEP_PIN, HIGH);
WRITE_E_STEP(HIGH); }
} else if (e_steps[0] > 0) {
else if (e_steps > 0) { WRITE(E0_DIR_PIN, !INVERT_E0_DIR);
WRITE_E_DIR(!INVERT_E_DIR); e_steps[0]--;
e_steps--; WRITE(E0_STEP_PIN, HIGH);
WRITE_E_STEP(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
@ -712,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

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>
@ -82,6 +81,7 @@ static unsigned long previous_millis_bed_heater;
// static float pid_output[EXTRUDERS]; // static float pid_output[EXTRUDERS];
static bool pid_reset[EXTRUDERS]; 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_raw[EXTRUDERS] = { -1000 }; // the first value used for all
@ -140,6 +140,10 @@ void updatePID()
#endif #endif
} }
int getHeaterPower(int heater) {
return soft_pwm[heater];
}
void manage_heater() void manage_heater()
{ {
#ifdef USE_WATCHDOG #ifdef USE_WATCHDOG
@ -198,15 +202,16 @@ void manage_heater()
} }
#endif #endif
// Check if temperature is within the correct range // Check if temperature is within the correct range
if((current_raw[e] > minttemp[e]) && (current_raw[e] < maxttemp[e])) if((current_raw[e] > minttemp[e]) && (current_raw[e] < maxttemp[e]))
{ {
analogWrite(heater_pin_map[e], pid_output); //analogWrite(heater_pin_map[e], pid_output);
} soft_pwm[e] = (int)pid_output >> 1;
else { }
analogWrite(heater_pin_map[e], 0); else {
} //analogWrite(heater_pin_map[e], 0);
soft_pwm[e] = 0;
}
} // End extruder for loop } // End extruder for loop
if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL) if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
@ -418,7 +423,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)
@ -426,7 +430,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)
@ -434,7 +437,6 @@ 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
#endif #endif
#if (TEMP_BED_PIN > -1) #if (TEMP_BED_PIN > -1)
@ -442,7 +444,6 @@ void tp_init()
DIDR0 |= 1<<TEMP_BED_PIN; DIDR0 |= 1<<TEMP_BED_PIN;
#else #else
DIDR2 |= 1<<(TEMP_BED_PIN - 8); DIDR2 |= 1<<(TEMP_BED_PIN - 8);
ADCSRB = 1<<MUX5;
#endif #endif
#endif #endif
@ -506,6 +507,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
@ -513,6 +515,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
@ -520,6 +523,7 @@ 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
@ -533,6 +537,26 @@ void disable_heater()
#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
ISR(TIMER0_COMPB_vect) ISR(TIMER0_COMPB_vect)
{ {
@ -543,6 +567,33 @@ ISR(TIMER0_COMPB_vect)
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 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
@ -628,10 +679,10 @@ ISR(TIMER0_COMPB_vect)
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) // 8 ms * 16 = 128ms. if(temp_count >= 16) // 8 ms * 16 = 128ms.
@ -671,21 +722,15 @@ ISR(TIMER0_COMPB_vect)
raw_temp_2_value = 0; raw_temp_2_value = 0;
raw_temp_bed_value = 0; raw_temp_bed_value = 0;
for(int e = 0; e < EXTRUDERS; e++) { for(unsigned char e = 0; e < EXTRUDERS; e++) {
if(current_raw[e] >= maxttemp[e]) { if(current_raw[e] >= maxttemp[e]) {
target_raw[e] = 0; target_raw[e] = 0;
digitalWrite(heater_pin_map[e], 0); max_temp_error(e);
SERIAL_ERROR_START; kill();;
SERIAL_ERRORLN((int)e);
SERIAL_ERRORLNPGM(": Extruder switched off. MAXTEMP triggered !");
kill();
} }
if(current_raw[e] <= minttemp[e]) { if(current_raw[e] <= minttemp[e]) {
target_raw[e] = 0; target_raw[e] = 0;
digitalWrite(heater_pin_map[e], 0); min_temp_error(e);
SERIAL_ERROR_START;
SERIAL_ERRORLN(e);
SERIAL_ERRORLNPGM(": Extruder switched off. MINTEMP triggered !");
kill(); kill();
} }
} }
@ -693,9 +738,7 @@ ISR(TIMER0_COMPB_vect)
#if defined(BED_MAXTEMP) && (HEATER_BED_PIN > -1) #if defined(BED_MAXTEMP) && (HEATER_BED_PIN > -1)
if(current_raw_bed >= bed_maxttemp) { if(current_raw_bed >= bed_maxttemp) {
target_raw_bed = 0; target_raw_bed = 0;
digitalWrite(HEATER_BED_PIN, 0); bed_max_temp_error();
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !!");
kill(); kill();
} }
#endif #endif

View file

@ -1,143 +1,144 @@
/* /*
temperature.h - temperature controller temperature.h - temperature controller
Part of Marlin Part of Marlin
Copyright (c) 2011 Erik van der Zalm Copyright (c) 2011 Erik van der Zalm
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (at your option) any later version.
Grbl is distributed in the hope that it will be useful, Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
#ifndef temperature_h #ifndef temperature_h
#define temperature_h #define temperature_h
#include "Marlin.h" #include "Marlin.h"
#include "fastio.h" #include "fastio.h"
#ifdef PID_ADD_EXTRUSION_RATE #ifdef PID_ADD_EXTRUSION_RATE
#include "stepper.h" #include "stepper.h"
#endif #endif
// public functions // public functions
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.
//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, uint8_t e); int temp2analog(int celsius, uint8_t e);
int temp2analogBed(int celsius); int temp2analogBed(int celsius);
float analog2temp(int raw, uint8_t e); float analog2temp(int raw, uint8_t e);
float analog2tempBed(int raw); float analog2tempBed(int raw);
extern int target_raw[EXTRUDERS]; extern int target_raw[EXTRUDERS];
extern int heatingtarget_raw[EXTRUDERS]; extern int heatingtarget_raw[EXTRUDERS];
extern int current_raw[EXTRUDERS]; extern int current_raw[EXTRUDERS];
extern int target_raw_bed; extern int target_raw_bed;
extern int current_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[EXTRUDERS]; extern float pid_setpoint[EXTRUDERS];
#endif #endif
#ifdef WATCHPERIOD #ifdef WATCHPERIOD
extern int watch_raw[EXTRUDERS] ; 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 degHotend(uint8_t extruder) { FORCE_INLINE float degHotend(uint8_t extruder) {
return analog2temp(current_raw[extruder], extruder); return analog2temp(current_raw[extruder], extruder);
}; };
FORCE_INLINE float degBed() { FORCE_INLINE float degBed() {
return analog2tempBed(current_raw_bed); return analog2tempBed(current_raw_bed);
}; };
FORCE_INLINE float degTargetHotend(uint8_t extruder) { FORCE_INLINE float degTargetHotend(uint8_t extruder) {
return analog2temp(target_raw[extruder], extruder); return analog2temp(target_raw[extruder], extruder);
}; };
FORCE_INLINE float degTargetBed() { FORCE_INLINE float degTargetBed() {
return analog2tempBed(target_raw_bed); return analog2tempBed(target_raw_bed);
}; };
FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) { FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) {
target_raw[extruder] = temp2analog(celsius, extruder); target_raw[extruder] = temp2analog(celsius, extruder);
#ifdef PIDTEMP #ifdef PIDTEMP
pid_setpoint[extruder] = celsius; pid_setpoint[extruder] = celsius;
#endif //PIDTEMP #endif //PIDTEMP
}; };
FORCE_INLINE void setTargetBed(const float &celsius) { FORCE_INLINE void setTargetBed(const float &celsius) {
target_raw_bed = temp2analogBed(celsius); target_raw_bed = temp2analogBed(celsius);
}; };
FORCE_INLINE bool isHeatingHotend(uint8_t extruder){ FORCE_INLINE bool isHeatingHotend(uint8_t extruder){
return target_raw[extruder] > current_raw[extruder]; return target_raw[extruder] > current_raw[extruder];
}; };
FORCE_INLINE bool isHeatingBed() { FORCE_INLINE bool isHeatingBed() {
return target_raw_bed > current_raw_bed; return target_raw_bed > current_raw_bed;
}; };
FORCE_INLINE bool isCoolingHotend(uint8_t extruder) { FORCE_INLINE bool isCoolingHotend(uint8_t extruder) {
return target_raw[extruder] < current_raw[extruder]; return target_raw[extruder] < current_raw[extruder];
}; };
FORCE_INLINE bool isCoolingBed() { FORCE_INLINE bool isCoolingBed() {
return target_raw_bed < current_raw_bed; return target_raw_bed < current_raw_bed;
}; };
#define degHotend0() degHotend(0) #define degHotend0() degHotend(0)
#define degTargetHotend0() degTargetHotend(0) #define degTargetHotend0() degTargetHotend(0)
#define setTargetHotend0(_celsius) setTargetHotend((_celsius), 0) #define setTargetHotend0(_celsius) setTargetHotend((_celsius), 0)
#define isHeatingHotend0() isHeatingHotend(0) #define isHeatingHotend0() isHeatingHotend(0)
#define isCoolingHotend0() isCoolingHotend(0) #define isCoolingHotend0() isCoolingHotend(0)
#if EXTRUDERS > 1 #if EXTRUDERS > 1
#define degHotend1() degHotend(1) #define degHotend1() degHotend(1)
#define degTargetHotend1() degTargetHotend(1) #define degTargetHotend1() degTargetHotend(1)
#define setTargetHotend1(_celsius) setTargetHotend((_celsius), 1) #define setTargetHotend1(_celsius) setTargetHotend((_celsius), 1)
#define isHeatingHotend1() isHeatingHotend(1) #define isHeatingHotend1() isHeatingHotend(1)
#define isCoolingHotend1() isCoolingHotend(1) #define isCoolingHotend1() isCoolingHotend(1)
#endif #endif
#if EXTRUDERS > 2 #if EXTRUDERS > 2
#define degHotend2() degHotend(2) #define degHotend2() degHotend(2)
#define degTargetHotend2() degTargetHotend(2) #define degTargetHotend2() degTargetHotend(2)
#define setTargetHotend2(_celsius) setTargetHotend((_celsius), 2) #define setTargetHotend2(_celsius) setTargetHotend((_celsius), 2)
#define isHeatingHotend2() isHeatingHotend(2) #define isHeatingHotend2() isHeatingHotend(2)
#define isCoolingHotend2() isCoolingHotend(2) #define isCoolingHotend2() isCoolingHotend(2)
#endif #endif
#if EXTRUDERS > 3 #if EXTRUDERS > 3
#error Invalid number of extruders #error Invalid number of extruders
#endif #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(degTargetHotend(ACTIVE_EXTRUDER)>autotemp_min) if(degTargetHotend(ACTIVE_EXTRUDER)>autotemp_min)
setTargetHotend(0,ACTIVE_EXTRUDER); setTargetHotend(0,ACTIVE_EXTRUDER);
} }
#endif #endif
} }
void disable_heater(); int getHeaterPower(int heater);
void setWatch(); void disable_heater();
void updatePID(); void setWatch();
void updatePID();
#endif
#endif

View file

@ -1,1839 +1,1843 @@
#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_home, ItemP_origin, ItemP_preheat, ItemP_extrude, ItemP_disstep}; #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_home, ItemP_origin, ItemP_preheat, ItemP_extrude, ItemP_disstep};
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_home: {
MENUITEM( lcdprintPGM(" Auto Home") , BLOCK;enquecommand("G28 X-105 Y-105 Z0");beepshort(); ) ; case ItemP_exit:
break; MENUITEM( lcdprintPGM(" Main \003") , BLOCK;status=Main_Menu;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(); ) ;
case ItemP_disstep: break;
MENUITEM( lcdprintPGM(" Disable Steppers") , BLOCK;enquecommand("M84");beepshort(); ) ; case ItemP_extrude:
break; MENUITEM( lcdprintPGM(" Extrude") , BLOCK;enquecommand("G92 E0");enquecommand("G1 F700 E50");beepshort(); ) ;
default: break;
break; case ItemP_disstep:
} MENUITEM( lcdprintPGM(" Disable Steppers") , BLOCK;enquecommand("M84");beepshort(); ) ;
line++; break;
} default:
updateActiveLines(ItemP_disstep,encoderpos); break;
} }
line++;
enum {ItemT_exit,ItemT_speed,ItemT_flow,ItemT_nozzle,ItemT_fan}; }
updateActiveLines(ItemP_disstep,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