Repository: kliment/Sprinter Branch: master Commit: b6820141eae6 Files: 26 Total size: 450.9 KB Directory structure: gitextract_tpti9gwz/ ├── README └── Sprinter/ ├── Configuration.h ├── FatStructs.h ├── Makefile ├── Sd2Card.cpp ├── Sd2Card.h ├── Sd2PinMap.h ├── SdFat.h ├── SdFatUtil.h ├── SdFatmainpage.h ├── SdFile.cpp ├── SdInfo.h ├── SdVolume.cpp ├── Sprinter.h ├── Sprinter.pde ├── arc_func.cpp ├── arc_func.h ├── createTemperatureLookup.py ├── fastio.h ├── heater.cpp ├── heater.h ├── pins.h ├── speed_lookuptable.h ├── store_eeprom.cpp ├── store_eeprom.h └── thermistortables.h ================================================ FILE CONTENTS ================================================ ================================================ FILE: README ================================================ The leading developers of Sprinter are currently Kliment, caru and midopple, though many others contribute with their patches. This is a firmware for RAMPS and other reprap single-processor electronics setups. It supports printing from SD card, active heatbed control, and ATmega internal pullups. This work is licensed under the GNU GPL v3 or (at the user's discretion) any later version. It is based on Tonokips's firmware, which was licensed under GPL v2 or later. WARNING: This version (April 19th, 2011) fixes a bug that caused speeds to be lower than what set in GCODE. So before attempting any print, you will have to check all your axis max speed, including the extruder retract speed. Not following this guidelines can seriously damage your printer. The configuration file now has an option to set the wanted temperature table file. If you copy and paste a temperature file from older versions, make sure that the configuration is pointing to it. For example: #include "ThermistorTable.h" In addition, you can optionally use a different thermistor table for hot-end and bed. To do so, comment out the following lines in configuration.h: #define BNUMTEMPS NUMPTEMPS #define bedtemptable temptable Then add a line pointing to your second thermistor table, for example: #include "BedThermistorTable.h" Finally, make sure that the nozzle thermistor table, inside ThermistorTable.h in this case, is defined as "temptable" and that the bed thermistor table is defined as "bedtemptable", and that the number of temps is defined as NUMTEMPS for the heater and BNUMTEMPS for the bed. There are examples of all these configurations in the configuration.h file. Please look at them before you change anything. Complete beginners guide ======================= From a fresh Ubuntu install how to update the firmware of your Prusa Mendel ? (the specifics are for the Prusa Mendel built at the Bath RepRap masterclass. This version uses the http://reprap.org/wiki/Sanguinololu. Some details may not fit your hardware, be sure to check what you are doing) Steps 3,10,11 are hardware-specific to the Sanguinololu and Bath Prusa and should be skipped or modified accordingly for other hardware such as the Arduino Mega 2560 Software installation ---------------------- 1. Install the required packages (gcc-avr, avr-libc, etc.) sudo apt-get install arduino-core 2. Get the arduino software version 0023, uncompress it in a directory. Arduino software v1 has not been tested much, but is known to work with some boards. http://www.arduino.cc/en/Main/Software 3. Get the sanguino software, version 0023 http://sanguino.cc/softwareforlinux follow the sanguino's readme so that your arduino hardware folder looks like arduino-0023/hardware/arduino arduino-0023/hardware/sanguino arduino-0023/hardware/tools 4. Clone the Sprinter git repository. git clone https://github.com/kliment/Sprinter.git Optionally, switch to the desired branch git branch -a git checkout THE_BRANCH_YOU_WANT Firmware compilation and upload ------------------------------- 5. Edit INSTALL_DIR inside Sprinter/Makefile (do not mind the default reference to arduino 0022) 6. Run make. If everything goes well Sprinter/applet/Sprinter.cpp should have been created. You can safely ignore the error message mentioning arduino-0023/hardware/arduino/cores/arduino/WString.o 7. Connect your Sanguinololu to your computer http://reprap.org/wiki/Sanguinololu 8. Launch arduino-0023/arduino, open Sprinter/Sprinter.pde 9. Go to Tools -> Serial Port, and select the relevant option 10. Go to Tools -> Board, select Sanguino 11. Go to the Configuration.h file and edit the following lines: #define MOTHERBOARD 62 62 indicates Sanguino 1.2 or superior float axis_steps_per_unit[] set values that match your hardware. For the special cast gears of the Bath Masterclass Prusa Mendel, these values are float axis_steps_per_unit[] = {91.42857, 91.42857, 3200/1.25,700}; also for the mentioned hardware setup const bool ENDSTOPS_INVERTING = false; //set to true to invert the logic of the endstops // false because the switch SIG signal is linked to the ground // "no touch == closed circuit == SIG connects to GND" // see http://reprap.org/wiki/Sanguinololu#Endstops 12. Click on the "play" button to compile. If everything goes well you should see a "Binary sketch size: " message. 13. Click on "the arrow going to the right" button to upload (you had done steps 7,8,9 before, right ?). If everything goes well you should see the message "Done uploading". if GEN7 with 20 Mhz is in use set the Fuses for Bootloader to lfuse= 0xF7 hfuse = 0xD4 efuse = FD Brownout must be 2,7 V Congratulations, you have just upgraded the firmware of your RepRap ! You can use pronterface.py to do some manual verifications by moving the printer's tip along the axes and verifying that the physical displacements match the ones indicated on the interface. ================================================ FILE: Sprinter/Configuration.h ================================================ #ifndef CONFIGURATION_H #define CONFIGURATION_H // BASIC SETTINGS: select your board type, thermistor type, axis scaling, and endstop configuration //// The following define selects which electronics board you have. Please choose the one that matches your setup // MEGA/RAMPS up to 1.2 = 3, // RAMPS 1.3/1.4 = 33 // Gen6 = 5, // Gen6 deluxe = 51 // Sanguinololu up to 1.1 = 6 // Sanguinololu 1.2 and above = 62 // Gen 7 @ 16MHZ only= 7 // Gen 7 @ 20MHZ only= 71 // Teensylu (at90usb) = 8 // Printrboard Rev. B (ATMEGA90USB1286) = 9 // Gen 3 Plus = 21 // gen 3 Monolithic Electronics = 22 // Gen3 PLUS for TechZone Gen3 Remix Motherboard = 23 #define MOTHERBOARD 33 //// Thermistor settings: // 1 is 100k thermistor // 2 is 200k thermistor // 3 is mendel-parts thermistor // 4 is 10k thermistor // 5 is ParCan supplied 104GT-2 100K // 6 is EPCOS 100k // 7 is 100k Honeywell thermistor 135-104LAG-J01 #define THERMISTORHEATER 1 #define THERMISTORBED 1 //// Calibration variables // X, Y, Z, E steps per unit - Metric Prusa Mendel with Wade extruder: #define _AXIS_STEP_PER_UNIT {80, 80, 3200/1.25,700} // Metric Prusa Mendel with Makergear geared stepper extruder: //#define _AXIS_STEP_PER_UNIT {80,80,3200/1.25,1380} // MakerGear Hybrid Prusa Mendel: // Z axis value is for .9 stepper(if you have 1.8 steppers for Z, you need to use 2272.7272) //#define _AXIS_STEP_PER_UNIT {104.987, 104.987, 4545.4544, 1487} //// Endstop Settings #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. //If your axes are only moving in one direction, make sure the endstops are connected properly. //If your axes move in one direction ONLY when the endstops are triggered, set [XYZ]_ENDSTOP_INVERT to true here: const bool X_ENDSTOP_INVERT = false; const bool Y_ENDSTOP_INVERT = false; const bool Z_ENDSTOP_INVERT = false; // This determines the communication speed of the printer #define BAUDRATE 115200 //#define BAUDRATE 250000 // Comment out (using // at the start of the line) to disable SD support: #define SDSUPPORT // Uncomment to make run init.g from SD on boot //#define SDINITFILE //Only work with Atmega1284 you need +1 kb ram //#define SD_FAST_XFER_AKTIV //----------------------------------------------------------------------- //// STORE SETTINGS TO EEPROM //----------------------------------------------------------------------- // the microcontroller can store settings in the EEPROM // M500 - stores paramters in EEPROM // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. // M503 - Print settings // define this to enable eeprom support //#define USE_EEPROM_SETTINGS // to disable EEPROM Serial responses and decrease program space by ~1000 byte: comment this out: // please keep turned on if you can. //#define PRINT_EEPROM_SETTING //----------------------------------------------------------------------- //// ARC Function (G2/G3 Command) //----------------------------------------------------------------------- //Uncomment to aktivate the arc (circle) function (G2/G3 Command) //Without SD function an ARC function the used Flash is smaller 31 kb #define USE_ARC_FUNCTION //----------------------------------------------------------------------- //// ADVANCED SETTINGS - to tweak parameters //----------------------------------------------------------------------- #ifdef SDSUPPORT #ifdef SD_FAST_XFER_AKTIV //Fast transfer chunk size (> 1024 is unstable, change at your own risk). #define SD_FAST_XFER_CHUNK_SIZE 1024 #endif #endif //----------------------------------------------------------------------- // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 //----------------------------------------------------------------------- #define X_ENABLE_ON 0 #define Y_ENABLE_ON 0 #define Z_ENABLE_ON 0 #define E_ENABLE_ON 0 //Uncomment if you have problems with a stepper driver enabeling too late, this will also set how many microseconds delay there will be after enabeling the driver //#define DELAY_ENABLE 15 //----------------------------------------------------------------------- // Disables axis when it's not being used. //----------------------------------------------------------------------- const bool DISABLE_X = false; const bool DISABLE_Y = false; const bool DISABLE_Z = true; const bool DISABLE_E = false; //----------------------------------------------------------------------- // Inverting axis direction //----------------------------------------------------------------------- const bool INVERT_X_DIR = false; const bool INVERT_Y_DIR = false; const bool INVERT_Z_DIR = true; const bool INVERT_E_DIR = false; //----------------------------------------------------------------------- //// ENDSTOP SETTINGS: //----------------------------------------------------------------------- // Sets direction of endstops when homing; 1=MAX, -1=MIN #define X_HOME_DIR -1 #define Y_HOME_DIR -1 #define Z_HOME_DIR -1 //#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing const bool min_software_endstops = false; //If true, axis won't move to coordinates less than zero. const bool max_software_endstops = true; //If true, axis won't move to coordinates greater than the defined lengths below. //----------------------------------------------------------------------- //Max Length for Prusa Mendel, check the ways of your axis and set this Values //----------------------------------------------------------------------- const int X_MAX_LENGTH = 200; const int Y_MAX_LENGTH = 200; const int Z_MAX_LENGTH = 100; //----------------------------------------------------------------------- //// MOVEMENT SETTINGS //----------------------------------------------------------------------- const int NUM_AXIS = 4; // The axis order in all axis related arrays is X, Y, Z, E #define _MAX_FEEDRATE {400, 400, 2, 45} // (mm/sec) #define _HOMING_FEEDRATE {1500,1500,120} // (mm/min) !! #define _AXIS_RELATIVE_MODES {false, false, false, false} #define MAX_STEP_FREQUENCY 30000 // Max step frequency //For the retract (negative Extruder) move this maxiumum Limit of Feedrate is used //The next positive Extruder move use also this Limit, //then for the next (second after retract) move the original Maximum (_MAX_FEEDRATE) Limit is used #define MAX_RETRACT_FEEDRATE 100 //mm/sec //----------------------------------------------------------------------- //// Not used at the Moment //----------------------------------------------------------------------- // Min step delay in microseconds. If you are experiencing missing steps, try to raise the delay microseconds, but be aware this // If you enable this, make sure STEP_DELAY_RATIO is disabled. //#define STEP_DELAY_MICROS 1 // Step delay over interval ratio. If you are still experiencing missing steps, try to uncomment the following line, but be aware this // If you enable this, make sure STEP_DELAY_MICROS is disabled. (except for Gen6: both need to be enabled.) //#define STEP_DELAY_RATIO 0.25 ///Oscillation reduction. Forces x,y,or z axis to be stationary for ## ms before allowing axis to switch direcitons. Alternative method to prevent skipping steps. Uncomment the line below to activate. // At this Version with Planner this Function ist not used //#define RAPID_OSCILLATION_REDUCTION #ifdef RAPID_OSCILLATION_REDUCTION const long min_time_before_dir_change = 30; //milliseconds #endif //----------------------------------------------------------------------- //// Acceleration settings //----------------------------------------------------------------------- // 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 _ACCELERATION 1000 // Axis Normal acceleration mm/s^2 #define _RETRACT_ACCELERATION 2000 // Extruder Normal acceleration mm/s^2 #define _MAX_XY_JERK 20.0 #define _MAX_Z_JERK 0.4 #define _MAX_E_JERK 5.0 // (mm/sec) //#define _MAX_START_SPEED_UNITS_PER_SECOND {25.0,25.0,0.2,10.0} #define _MAX_ACCELERATION_UNITS_PER_SQ_SECOND {5000,5000,50,5000} // X, Y, Z and E max acceleration in mm/s^2 for printing moves or retracts // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. #define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 #define _MIN_SEG_TIME 20000 // If defined the movements slow down when the look ahead buffer is only half full #define SLOWDOWN const int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement //----------------------------------------------------------------------- // Machine UUID //----------------------------------------------------------------------- // This may be useful if you have multiple machines and wish to identify them by using the M115 command. // By default we set it to zeros. #define _DEF_CHAR_UUID "00000000-0000-0000-0000-000000000000" //----------------------------------------------------------------------- //// Planner buffer Size //----------------------------------------------------------------------- // The number of linear motions that can be in the plan at any give time // if the SD Card need to much memory reduce the Values for Plannerpuffer (base of 2) #ifdef SDSUPPORT #define BLOCK_BUFFER_SIZE 16 #define BLOCK_BUFFER_MASK 0x0f #else #define BLOCK_BUFFER_SIZE 16 #define BLOCK_BUFFER_MASK 0x0f #endif //----------------------------------------------------------------------- //// SETTINGS FOR ARC FUNCTION (Command G2/G2) //----------------------------------------------------------------------- // Arc interpretation settings: //Step to split a cirrcle in small Lines #define MM_PER_ARC_SEGMENT 1 //After this count of steps a new SIN / COS caluclation is startet to correct the circle interpolation #define N_ARC_CORRECTION 25 //----------------------------------------------------------------------- //// FANCONTROL WITH SOFT PWM //----------------------------------------------------------------------- //With this option its possible to drive the fan with SOFT PWM (500hz) and use //every Digital output for it, main usage for Sanguinololu #define FAN_SOFT_PWM //----------------------------------------------------------------------- //// MINIMUM START SPEED FOR FAN //----------------------------------------------------------------------- //Minimum start speed for FAN when the last speed was zero //Set to 0 to deaktivate //If value is set the fan will drive with this minimum speed for MINIMUM_FAN_START_TIME #define MINIMUM_FAN_START_SPEED 0 //This is the time how long the minimum FAN speed is set #define MINIMUM_FAN_START_TIME 6000 //6sec //----------------------------------------------------------------------- //// HEATERCONTROL AND PID PARAMETERS //----------------------------------------------------------------------- //Testfunction to adjust the Hotend temperatur in case of Printingspeed //If the Printer print slow the Temp is going to AUTO_TEMP_MIN //At the moment this Value dont change the targettemp from the Hotend //The result of this function is only send with the Temperaturerequest to the host //#define AUTOTEMP #ifdef AUTOTEMP #define AUTO_TEMP_MAX 240 #define AUTO_TEMP_MIN 205 #define AUTO_TEMP_FACTOR 0.025 #define AUTOTEMP_OLDWEIGHT 0.98 #endif //// AD595 THERMOCOUPLE SUPPORT UNTESTED... USE WITH CAUTION!!!! //// PID settings: // Uncomment the following line to enable PID support. This is untested and could be disastrous. Be careful. #define PIDTEMP 1 #ifdef PIDTEMP //Sanguinololu 1.2 and above, the PWM Output Hotend Timer 1 is used for the Hardware PWM //but in this Software use Timer1 for the Stepperfunction so it is not possible to use the "analogWrite" function. //This Soft PWM use Timer 2 with 400 Hz to drive the PWM for the hotend #define PID_SOFT_PWM //Measure the MIN/MAX Value of the Hotend Temp and show it with //Command M601 / Command M602 Reset the MIN/MAX Value //#define DEBUG_HEATER_TEMP // M303 - PID relay autotune S sets the target temperature. // (default target temperature = 150C) #define PID_AUTOTUNE //PID Controler Settings #define PID_INTEGRAL_DRIVE_MAX 80 // too big, and heater will lag after changing temperature, too small and it might not compensate enough for long-term errors #define PID_PGAIN 2560 //256 is 1.0 // value of X means that error of 1 degree is changing PWM duty by X, probably no need to go over 25 #define PID_IGAIN 64 //256 is 1.0 // value of X (e.g 0.25) means that each degree error over 1 sec (2 measurements) changes duty cycle by 2X (=0.5) units (verify?) #define PID_DGAIN 4096 //256 is 1.0 // value of X means that around reached setpoint, each degree change over one measurement (half second) adjusts PWM by X units to compensate // magic formula 1, to get approximate "zero error" PWM duty. Take few measurements with low PWM duty and make linear fit to get the formula // for my makergear hot-end: linear fit {50,10},{60,20},{80,30},{105,50},{176,100},{128,64},{208,128} #define HEATER_DUTY_FOR_SETPOINT(setpoint) ((int)((187L*(long)setpoint)>>8)-27) // magic formula 2, to make led brightness approximately linear #define LED_PWM_FOR_BRIGHTNESS(brightness) ((64*brightness-1384)/(300-brightness)) #endif // Change this value (range 30-255) to limit the current to the nozzle #define HEATER_CURRENT 255 // How often should the heater check for new temp readings, in milliseconds #define HEATER_CHECK_INTERVAL 500 #define BED_CHECK_INTERVAL 5000 // Comment the following line to enable heat management during acceleration #define DISABLE_CHECK_DURING_ACC #ifndef DISABLE_CHECK_DURING_ACC // Uncomment the following line to disable heat management during moves //#define DISABLE_CHECK_DURING_MOVE #endif // Uncomment the following line to disable heat management during travel moves (and extruder-only moves, eg: retracts), strongly recommended if you are missing steps mid print. // Probably this should remain commented if are using PID. // It also defines the max milliseconds interval after which a travel move is not considered so for the sake of this feature. #define DISABLE_CHECK_DURING_TRAVEL 1000 //// Temperature smoothing - only uncomment this if your temp readings are noisy (Gen6 without EvdZ's 5V hack) //#define SMOOTHING //#define SMOOTHFACTOR 16 //best to use a power of two here - determines how many values are averaged together by the smoothing algorithm //// Experimental watchdog and minimal temp // The watchdog waits for the watchperiod in milliseconds whenever an M104 or M109 increases the target temperature // If the temperature has not increased at the end of that period, the target temperature is set to zero. It can be reset with another M104/M109 //#define WATCHPERIOD 5000 //5 seconds // Actual temperature must be close to target for this long before M109 returns success //#define TEMP_RESIDENCY_TIME 20 // (seconds) //#define TEMP_HYSTERESIS 5 // (C°) range of +/- temperatures considered "close" to the target one //// The minimal temperature defines the temperature below which the heater will not be enabled #define MINTEMP 5 //// Experimental max temp // When temperature exceeds max temp, your heater will be switched off. // This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure! // You should use MINTEMP for thermistor short/failure protection. #define MAXTEMP 275 // Select one of these only to define how the nozzle temp is read. #define HEATER_USES_THERMISTOR //#define HEATER_USES_AD595 //#define HEATER_USES_MAX6675 // Select one of these only to define how the bed temp is read. #define BED_USES_THERMISTOR //#define BED_USES_AD595 //This is for controlling a fan to cool down the stepper drivers //it will turn on when any driver is enabled //and turn off after the set amount of seconds from last driver being disabled again //#define CONTROLLERFAN_PIN 23 //Pin used for the fan to cool controller, comment out to disable this function #define CONTROLLERFAN_SEC 60 //How many seconds, after all motors were disabled, the fan should run //This is for controlling a fan that will keep the extruder cool. //#define EXTRUDERFAN_PIN 66 //Pin used to control the fan, comment out to disable this function #define EXTRUDERFAN_DEC 50 //Hotend temperature from where the fan will be turned on //#define CHAIN_OF_COMMAND 1 //Finish buffered moves before executing M42, fan speed, heater target, and so... //----------------------------------------------------------------------- // DEBUGING //----------------------------------------------------------------------- //Uncomment this to see on the host if a wrong or unknown Command is recived //Only for Testing !!! //#define SEND_WRONG_CMD_INFO // Uncomment the following line to enable debugging. You can better control debugging below the following line //#define DEBUG #ifdef DEBUG //#define DEBUG_PREPARE_MOVE //Enable this to debug prepare_move() function //#define DEBUG_MOVE_TIME //Enable this to time each move and print the result //#define DEBUG_HEAT_MGMT //Enable this to debug heat management. WARNING, this will cause axes to jitter! //#define DEBUG_DISABLE_CHECK_DURING_TRAVEL //Debug the namesake feature, see above in this file #endif #endif ================================================ FILE: Sprinter/FatStructs.h ================================================ /* Arduino SdFat Library * Copyright (C) 2009 by William Greiman * * This file is part of the Arduino SdFat Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with the Arduino SdFat Library. If not, see * . */ #ifndef FatStructs_h #define FatStructs_h /** * \file * FAT file structures */ /* * mostly from Microsoft document fatgen103.doc * http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx */ //------------------------------------------------------------------------------ /** Value for byte 510 of boot block or MBR */ uint8_t const BOOTSIG0 = 0X55; /** Value for byte 511 of boot block or MBR */ uint8_t const BOOTSIG1 = 0XAA; //------------------------------------------------------------------------------ /** * \struct partitionTable * \brief MBR partition table entry * * A partition table entry for a MBR formatted storage device. * The MBR partition table has four entries. */ struct partitionTable { /** * Boot Indicator . Indicates whether the volume is the active * partition. Legal values include: 0X00. Do not use for booting. * 0X80 Active partition. */ uint8_t boot; /** * Head part of Cylinder-head-sector address of the first block in * the partition. Legal values are 0-255. Only used in old PC BIOS. */ uint8_t beginHead; /** * Sector part of Cylinder-head-sector address of the first block in * the partition. Legal values are 1-63. Only used in old PC BIOS. */ unsigned beginSector : 6; /** High bits cylinder for first block in partition. */ unsigned beginCylinderHigh : 2; /** * Combine beginCylinderLow with beginCylinderHigh. Legal values * are 0-1023. Only used in old PC BIOS. */ uint8_t beginCylinderLow; /** * Partition type. See defines that begin with PART_TYPE_ for * some Microsoft partition types. */ uint8_t type; /** * head part of cylinder-head-sector address of the last sector in the * partition. Legal values are 0-255. Only used in old PC BIOS. */ uint8_t endHead; /** * Sector part of cylinder-head-sector address of the last sector in * the partition. Legal values are 1-63. Only used in old PC BIOS. */ unsigned endSector : 6; /** High bits of end cylinder */ unsigned endCylinderHigh : 2; /** * Combine endCylinderLow with endCylinderHigh. Legal values * are 0-1023. Only used in old PC BIOS. */ uint8_t endCylinderLow; /** Logical block address of the first block in the partition. */ uint32_t firstSector; /** Length of the partition, in blocks. */ uint32_t totalSectors; }; /** Type name for partitionTable */ typedef struct partitionTable part_t; //------------------------------------------------------------------------------ /** * \struct masterBootRecord * * \brief Master Boot Record * * The first block of a storage device that is formatted with a MBR. */ struct masterBootRecord { /** Code Area for master boot program. */ uint8_t codeArea[440]; /** Optional WindowsNT disk signature. May contain more boot code. */ uint32_t diskSignature; /** Usually zero but may be more boot code. */ uint16_t usuallyZero; /** Partition tables. */ part_t part[4]; /** First MBR signature byte. Must be 0X55 */ uint8_t mbrSig0; /** Second MBR signature byte. Must be 0XAA */ uint8_t mbrSig1; }; /** Type name for masterBootRecord */ typedef struct masterBootRecord mbr_t; //------------------------------------------------------------------------------ /** * \struct biosParmBlock * * \brief BIOS parameter block * * The BIOS parameter block describes the physical layout of a FAT volume. */ struct biosParmBlock { /** * Count of bytes per sector. This value may take on only the * following values: 512, 1024, 2048 or 4096 */ uint16_t bytesPerSector; /** * Number of sectors per allocation unit. This value must be a * power of 2 that is greater than 0. The legal values are * 1, 2, 4, 8, 16, 32, 64, and 128. */ uint8_t sectorsPerCluster; /** * Number of sectors before the first FAT. * This value must not be zero. */ uint16_t reservedSectorCount; /** The count of FAT data structures on the volume. This field should * always contain the value 2 for any FAT volume of any type. */ uint8_t fatCount; /** * For FAT12 and FAT16 volumes, this field contains the count of * 32-byte directory entries in the root directory. For FAT32 volumes, * this field must be set to 0. For FAT12 and FAT16 volumes, this * value should always specify a count that when multiplied by 32 * results in a multiple of bytesPerSector. FAT16 volumes should * use the value 512. */ uint16_t rootDirEntryCount; /** * This field is the old 16-bit total count of sectors on the volume. * This count includes the count of all sectors in all four regions * of the volume. This field can be 0; if it is 0, then totalSectors32 * must be non-zero. For FAT32 volumes, this field must be 0. For * FAT12 and FAT16 volumes, this field contains the sector count, and * totalSectors32 is 0 if the total sector count fits * (is less than 0x10000). */ uint16_t totalSectors16; /** * This dates back to the old MS-DOS 1.x media determination and is * no longer usually used for anything. 0xF8 is the standard value * for fixed (non-removable) media. For removable media, 0xF0 is * frequently used. Legal values are 0xF0 or 0xF8-0xFF. */ uint8_t mediaType; /** * Count of sectors occupied by one FAT on FAT12/FAT16 volumes. * On FAT32 volumes this field must be 0, and sectorsPerFat32 * contains the FAT size count. */ uint16_t sectorsPerFat16; /** Sectors per track for interrupt 0x13. Not used otherwise. */ uint16_t sectorsPerTrtack; /** Number of heads for interrupt 0x13. Not used otherwise. */ uint16_t headCount; /** * Count of hidden sectors preceding the partition that contains this * FAT volume. This field is generally only relevant for media * visible on interrupt 0x13. */ uint32_t hidddenSectors; /** * This field is the new 32-bit total count of sectors on the volume. * This count includes the count of all sectors in all four regions * of the volume. This field can be 0; if it is 0, then * totalSectors16 must be non-zero. */ uint32_t totalSectors32; /** * Count of sectors occupied by one FAT on FAT32 volumes. */ uint32_t sectorsPerFat32; /** * This field is only defined for FAT32 media and does not exist on * FAT12 and FAT16 media. * Bits 0-3 -- Zero-based number of active FAT. * Only valid if mirroring is disabled. * Bits 4-6 -- Reserved. * Bit 7 -- 0 means the FAT is mirrored at runtime into all FATs. * -- 1 means only one FAT is active; it is the one referenced in bits 0-3. * Bits 8-15 -- Reserved. */ uint16_t fat32Flags; /** * FAT32 version. High byte is major revision number. * Low byte is minor revision number. Only 0.0 define. */ uint16_t fat32Version; /** * Cluster number of the first cluster of the root directory for FAT32. * This usually 2 but not required to be 2. */ uint32_t fat32RootCluster; /** * Sector number of FSINFO structure in the reserved area of the * FAT32 volume. Usually 1. */ uint16_t fat32FSInfo; /** * If non-zero, indicates the sector number in the reserved area * of the volume of a copy of the boot record. Usually 6. * No value other than 6 is recommended. */ uint16_t fat32BackBootBlock; /** * Reserved for future expansion. Code that formats FAT32 volumes * should always set all of the bytes of this field to 0. */ uint8_t fat32Reserved[12]; }; /** Type name for biosParmBlock */ typedef struct biosParmBlock bpb_t; //------------------------------------------------------------------------------ /** * \struct fat32BootSector * * \brief Boot sector for a FAT16 or FAT32 volume. * */ struct fat32BootSector { /** X86 jmp to boot program */ uint8_t jmpToBootCode[3]; /** informational only - don't depend on it */ char oemName[8]; /** BIOS Parameter Block */ bpb_t bpb; /** for int0x13 use value 0X80 for hard drive */ uint8_t driveNumber; /** used by Windows NT - should be zero for FAT */ uint8_t reserved1; /** 0X29 if next three fields are valid */ uint8_t bootSignature; /** usually generated by combining date and time */ uint32_t volumeSerialNumber; /** should match volume label in root dir */ char volumeLabel[11]; /** informational only - don't depend on it */ char fileSystemType[8]; /** X86 boot code */ uint8_t bootCode[420]; /** must be 0X55 */ uint8_t bootSectorSig0; /** must be 0XAA */ uint8_t bootSectorSig1; }; //------------------------------------------------------------------------------ // End Of Chain values for FAT entries /** FAT16 end of chain value used by Microsoft. */ uint16_t const FAT16EOC = 0XFFFF; /** Minimum value for FAT16 EOC. Use to test for EOC. */ uint16_t const FAT16EOC_MIN = 0XFFF8; /** FAT32 end of chain value used by Microsoft. */ uint32_t const FAT32EOC = 0X0FFFFFFF; /** Minimum value for FAT32 EOC. Use to test for EOC. */ uint32_t const FAT32EOC_MIN = 0X0FFFFFF8; /** Mask a for FAT32 entry. Entries are 28 bits. */ uint32_t const FAT32MASK = 0X0FFFFFFF; /** Type name for fat32BootSector */ typedef struct fat32BootSector fbs_t; //------------------------------------------------------------------------------ /** * \struct directoryEntry * \brief FAT short directory entry * * Short means short 8.3 name, not the entry size. * * Date Format. A FAT directory entry date stamp is a 16-bit field that is * basically a date relative to the MS-DOS epoch of 01/01/1980. Here is the * format (bit 0 is the LSB of the 16-bit word, bit 15 is the MSB of the * 16-bit word): * * Bits 9-15: Count of years from 1980, valid value range 0-127 * inclusive (1980-2107). * * Bits 5-8: Month of year, 1 = January, valid value range 1-12 inclusive. * * Bits 0-4: Day of month, valid value range 1-31 inclusive. * * Time Format. A FAT directory entry time stamp is a 16-bit field that has * a granularity of 2 seconds. Here is the format (bit 0 is the LSB of the * 16-bit word, bit 15 is the MSB of the 16-bit word). * * Bits 11-15: Hours, valid value range 0-23 inclusive. * * Bits 5-10: Minutes, valid value range 0-59 inclusive. * * Bits 0-4: 2-second count, valid value range 0-29 inclusive (0 - 58 seconds). * * The valid time range is from Midnight 00:00:00 to 23:59:58. */ struct directoryEntry { /** * Short 8.3 name. * The first eight bytes contain the file name with blank fill. * The last three bytes contain the file extension with blank fill. */ uint8_t name[11]; /** Entry attributes. * * The upper two bits of the attribute byte are reserved and should * always be set to 0 when a file is created and never modified or * looked at after that. See defines that begin with DIR_ATT_. */ uint8_t attributes; /** * Reserved for use by Windows NT. Set value to 0 when a file is * created and never modify or look at it after that. */ uint8_t reservedNT; /** * The granularity of the seconds part of creationTime is 2 seconds * so this field is a count of tenths of a second and its valid * value range is 0-199 inclusive. (WHG note - seems to be hundredths) */ uint8_t creationTimeTenths; /** Time file was created. */ uint16_t creationTime; /** Date file was created. */ uint16_t creationDate; /** * Last access date. Note that there is no last access time, only * a date. This is the date of last read or write. In the case of * a write, this should be set to the same date as lastWriteDate. */ uint16_t lastAccessDate; /** * High word of this entry's first cluster number (always 0 for a * FAT12 or FAT16 volume). */ uint16_t firstClusterHigh; /** Time of last write. File creation is considered a write. */ uint16_t lastWriteTime; /** Date of last write. File creation is considered a write. */ uint16_t lastWriteDate; /** Low word of this entry's first cluster number. */ uint16_t firstClusterLow; /** 32-bit unsigned holding this file's size in bytes. */ uint32_t fileSize; }; //------------------------------------------------------------------------------ // Definitions for directory entries // /** Type name for directoryEntry */ typedef struct directoryEntry dir_t; /** escape for name[0] = 0XE5 */ uint8_t const DIR_NAME_0XE5 = 0X05; /** name[0] value for entry that is free after being "deleted" */ uint8_t const DIR_NAME_DELETED = 0XE5; /** name[0] value for entry that is free and no allocated entries follow */ uint8_t const DIR_NAME_FREE = 0X00; /** file is read-only */ uint8_t const DIR_ATT_READ_ONLY = 0X01; /** File should hidden in directory listings */ uint8_t const DIR_ATT_HIDDEN = 0X02; /** Entry is for a system file */ uint8_t const DIR_ATT_SYSTEM = 0X04; /** Directory entry contains the volume label */ uint8_t const DIR_ATT_VOLUME_ID = 0X08; /** Entry is for a directory */ uint8_t const DIR_ATT_DIRECTORY = 0X10; /** Old DOS archive bit for backup support */ uint8_t const DIR_ATT_ARCHIVE = 0X20; /** Test value for long name entry. Test is (d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME. */ uint8_t const DIR_ATT_LONG_NAME = 0X0F; /** Test mask for long name entry */ uint8_t const DIR_ATT_LONG_NAME_MASK = 0X3F; /** defined attribute bits */ uint8_t const DIR_ATT_DEFINED_BITS = 0X3F; /** Directory entry is part of a long name */ static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) { return (dir->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME; } /** Mask for file/subdirectory tests */ uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY); /** Directory entry is for a file */ static inline uint8_t DIR_IS_FILE(const dir_t* dir) { return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0; } /** Directory entry is for a subdirectory */ static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) { return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY; } /** Directory entry is for a file or subdirectory */ static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) { return (dir->attributes & DIR_ATT_VOLUME_ID) == 0; } #endif // FatStructs_h ================================================ FILE: Sprinter/Makefile ================================================ # Sprinter Arduino Project Makefile # # Makefile Based on: # Arduino 0011 Makefile # Arduino adaptation by mellis, eighthave, oli.keller # # This has been tested with Arduino 0022. # # This makefile allows you to build sketches from the command line # without the Arduino environment (or Java). # # Detailed instructions for using the makefile: # # 1. Modify the line containg "INSTALL_DIR" to point to the directory that # contains the Arduino installation (for example, under Mac OS X, this # might be /Applications/arduino-0012). # # 2. Modify the line containing "PORT" to refer to the filename # representing the USB or serial connection to your Arduino board # (e.g. PORT = /dev/tty.USB0). If the exact name of this file # changes, you can use * as a wildcard (e.g. PORT = /dev/tty.usb*). # # 3. Set the line containing "MCU" to match your board's processor. # Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth # or Diecimila have the atmega168. If you're using a LilyPad Arduino, # change F_CPU to 8000000. # # 4. Type "make" and press enter to compile/verify your program. # # 5. Type "make upload", reset your Arduino board, and press enter to # upload your program to the Arduino board. # # $Id$ TARGET = $(notdir $(CURDIR)) INSTALL_DIR = ../../arduino22/arduino-0022/ UPLOAD_RATE = 38400 AVRDUDE_PROGRAMMER = stk500v1 PORT = /dev/ttyUSB0 MCU = atmega2560 #For "old" Arduino Mega #MCU = atmega1280 #For Sanguinololu #MCU = atmega644p F_CPU = 16000000 ############################################################################ # Below here nothing should be changed... ARDUINO = $(INSTALL_DIR)/hardware/arduino/cores/arduino AVR_TOOLS_PATH = /usr/bin SRC = $(ARDUINO)/pins_arduino.c $(ARDUINO)/wiring.c \ $(ARDUINO)/wiring_analog.c $(ARDUINO)/wiring_digital.c \ $(ARDUINO)/wiring_pulse.c \ $(ARDUINO)/wiring_shift.c $(ARDUINO)/WInterrupts.c CXXSRC = $(ARDUINO)/HardwareSerial.cpp $(ARDUINO)/WMath.cpp $(ARDUINO)/WString.cpp\ $(ARDUINO)/Print.cpp ./SdFile.cpp ./SdVolume.cpp ./Sd2Card.cpp ./heater.cpp ./arc_func.cpp ./store_eeprom.cpp FORMAT = ihex # Name of this Makefile (used for "make depend"). MAKEFILE = Makefile # Debugging format. # Native formats for AVR-GCC's -g are stabs [default], or dwarf-2. # AVR (extended) COFF requires stabs, plus an avr-objcopy run. DEBUG = stabs OPT = s # Place -D or -U options here CDEFS = -DF_CPU=$(F_CPU) CXXDEFS = -DF_CPU=$(F_CPU) # Place -I options here CINCS = -I$(ARDUINO) CXXINCS = -I$(ARDUINO) # Compiler flag to set the C Standard level. # c89 - "ANSI" C # gnu89 - c89 plus GCC extensions # c99 - ISO C99 standard (not yet fully implemented) # gnu99 - c99 plus GCC extensions #CSTANDARD = -std=gnu99 CDEBUG = -g$(DEBUG) CWARN = -Wall -Wstrict-prototypes CTUNING = -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -w -ffunction-sections -fdata-sections -DARDUINO=22 #CEXTRA = -Wa,-adhlns=$(<:.c=.lst) CFLAGS = $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CEXTRA) $(CTUNING) CXXFLAGS = $(CDEFS) $(CINCS) -O$(OPT) -Wall $(CEXTRA) $(CTUNING) #ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs LDFLAGS = -lm # Programming support using avrdude. Settings and variables. AVRDUDE_PORT = $(PORT) AVRDUDE_WRITE_FLASH = -U flash:w:applet/$(TARGET).hex:i AVRDUDE_FLAGS = -D -C $(INSTALL_DIR)/hardware/tools/avrdude.conf \ -p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) \ -b $(UPLOAD_RATE) # Program settings CC = $(AVR_TOOLS_PATH)/avr-gcc CXX = $(AVR_TOOLS_PATH)/avr-g++ OBJCOPY = $(AVR_TOOLS_PATH)/avr-objcopy OBJDUMP = $(AVR_TOOLS_PATH)/avr-objdump AR = $(AVR_TOOLS_PATH)/avr-ar SIZE = $(AVR_TOOLS_PATH)/avr-size NM = $(AVR_TOOLS_PATH)/avr-nm AVRDUDE = $(INSTALL_DIR)/hardware/tools/avrdude REMOVE = rm -f MV = mv -f # Define all object files. OBJ = $(SRC:.c=.o) $(CXXSRC:.cpp=.o) $(ASRC:.S=.o) # Define all listing files. LST = $(ASRC:.S=.lst) $(CXXSRC:.cpp=.lst) $(SRC:.c=.lst) # Combine all necessary flags and optional flags. # Add target processor to flags. ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS) ALL_CXXFLAGS = -mmcu=$(MCU) -I. $(CXXFLAGS) ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS) # Default target. all: build sizeafter build: elf hex applet/$(TARGET).cpp: $(TARGET).pde # Here is the "preprocessing". # It creates a .cpp file based with the same name as the .pde file. # On top of the new .cpp file comes the WProgram.h header. # At the end there is a generic main() function attached. # Then the .cpp file will be compiled. Errors during compile will # refer to this new, automatically generated, file. # Not the original .pde file you actually edit... test -d applet || mkdir applet echo '#include "WProgram.h"' > applet/$(TARGET).cpp cat $(TARGET).pde >> applet/$(TARGET).cpp cat $(ARDUINO)/main.cpp >> applet/$(TARGET).cpp elf: applet/$(TARGET).elf hex: applet/$(TARGET).hex eep: applet/$(TARGET).eep lss: applet/$(TARGET).lss sym: applet/$(TARGET).sym # Program the device. upload: applet/$(TARGET).hex $(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH) # Display size of file. HEXSIZE = $(SIZE) --target=$(FORMAT) applet/$(TARGET).hex ELFSIZE = $(SIZE) applet/$(TARGET).elf sizebefore: @if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(HEXSIZE); echo; fi sizeafter: @if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(HEXSIZE); echo; fi # Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB. COFFCONVERT=$(OBJCOPY) --debugging \ --change-section-address .data-0x800000 \ --change-section-address .bss-0x800000 \ --change-section-address .noinit-0x800000 \ --change-section-address .eeprom-0x810000 coff: applet/$(TARGET).elf $(COFFCONVERT) -O coff-avr applet/$(TARGET).elf $(TARGET).cof extcoff: $(TARGET).elf $(COFFCONVERT) -O coff-ext-avr applet/$(TARGET).elf $(TARGET).cof .SUFFIXES: .elf .hex .eep .lss .sym .elf.hex: $(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@ .elf.eep: -$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \ --change-section-lma .eeprom=0 -O $(FORMAT) $< $@ # Create extended listing file from ELF output file. .elf.lss: $(OBJDUMP) -h -S $< > $@ # Create a symbol table from ELF output file. .elf.sym: $(NM) -n $< > $@ # Link: create ELF output file from library. applet/$(TARGET).elf: applet/$(TARGET).cpp applet/core.a $(CC) $(ALL_CFLAGS) -Wl,--gc-sections -o $@ applet/$(TARGET).cpp -L. applet/core.a $(LDFLAGS) applet/core.a: $(OBJ) @for i in $(OBJ); do echo $(AR) rcs applet/core.a $$i; $(AR) rcs applet/core.a $$i; done # Compile: create object files from C++ source files. .cpp.o: $(CXX) -c $(ALL_CXXFLAGS) $< -o $@ # Compile: create object files from C source files. .c.o: $(CC) -c $(ALL_CFLAGS) $< -o $@ # Compile: create assembler files from C source files. .c.s: $(CC) -S $(ALL_CFLAGS) $< -o $@ # Assemble: create object files from assembler source files. .S.o: $(CC) -c $(ALL_ASFLAGS) $< -o $@ # Target: clean project. clean: $(REMOVE) applet/$(TARGET).hex applet/$(TARGET).eep applet/$(TARGET).cof applet/$(TARGET).elf \ applet/$(TARGET).map applet/$(TARGET).sym applet/$(TARGET).lss applet/core.a \ $(OBJ) $(LST) $(SRC:.c=.s) $(SRC:.c=.d) $(CXXSRC:.cpp=.s) $(CXXSRC:.cpp=.d) depend: if grep '^# DO NOT DELETE' $(MAKEFILE) >/dev/null; \ then \ sed -e '/^# DO NOT DELETE/,$$d' $(MAKEFILE) > \ $(MAKEFILE).$$$$ && \ $(MV) $(MAKEFILE).$$$$ $(MAKEFILE); \ fi echo '# DO NOT DELETE THIS LINE -- make depend depends on it.' \ >> $(MAKEFILE); \ $(CC) -M -mmcu=$(MCU) $(CDEFS) $(CINCS) $(SRC) $(ASRC) >> $(MAKEFILE) .PHONY: all build elf hex eep lss sym program coff extcoff clean depend sizebefore sizeafter ================================================ FILE: Sprinter/Sd2Card.cpp ================================================ /* Arduino Sd2Card Library * Copyright (C) 2009 by William Greiman * * This file is part of the Arduino Sd2Card Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with the Arduino Sd2Card Library. If not, see * . */ #if defined(ARDUINO) && ARDUINO >= 100 #include #else #include #endif #include "Sd2Card.h" //------------------------------------------------------------------------------ #ifndef SOFTWARE_SPI // functions for hardware SPI /** Send a byte to the card */ static void spiSend(uint8_t b) { SPDR = b; while (!(SPSR & (1 << SPIF))); } /** Receive a byte from the card */ static uint8_t spiRec(void) { spiSend(0XFF); return SPDR; } #else // SOFTWARE_SPI //------------------------------------------------------------------------------ /** nop to tune soft SPI timing */ #define nop asm volatile ("nop\n\t") //------------------------------------------------------------------------------ /** Soft SPI receive */ uint8_t spiRec(void) { uint8_t data = 0; // no interrupts during byte receive - about 8 us cli(); // output pin high - like sending 0XFF fastDigitalWrite(SPI_MOSI_PIN, HIGH); for (uint8_t i = 0; i < 8; i++) { fastDigitalWrite(SPI_SCK_PIN, HIGH); // adjust so SCK is nice nop; nop; data <<= 1; if (fastDigitalRead(SPI_MISO_PIN)) data |= 1; fastDigitalWrite(SPI_SCK_PIN, LOW); } // enable interrupts sei(); return data; } //------------------------------------------------------------------------------ /** Soft SPI send */ void spiSend(uint8_t data) { // no interrupts during byte send - about 8 us cli(); for (uint8_t i = 0; i < 8; i++) { fastDigitalWrite(SPI_SCK_PIN, LOW); fastDigitalWrite(SPI_MOSI_PIN, data & 0X80); data <<= 1; fastDigitalWrite(SPI_SCK_PIN, HIGH); } // hold SCK high for a few ns nop; nop; nop; nop; fastDigitalWrite(SPI_SCK_PIN, LOW); // enable interrupts sei(); } #endif // SOFTWARE_SPI //------------------------------------------------------------------------------ // send command and return error code. Return zero for OK uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) { // end read if in partialBlockRead mode readEnd(); // select card chipSelectLow(); // wait up to 300 ms if busy waitNotBusy(300); // send command spiSend(cmd | 0x40); // send argument for (int8_t s = 24; s >= 0; s -= 8) spiSend(arg >> s); // send CRC uint8_t crc = 0XFF; if (cmd == CMD0) crc = 0X95; // correct crc for CMD0 with arg 0 if (cmd == CMD8) crc = 0X87; // correct crc for CMD8 with arg 0X1AA spiSend(crc); // wait for response for (uint8_t i = 0; ((status_ = spiRec()) & 0X80) && i != 0XFF; i++); return status_; } //------------------------------------------------------------------------------ /** * Determine the size of an SD flash memory card. * * \return The number of 512 byte data blocks in the card * or zero if an error occurs. */ uint32_t Sd2Card::cardSize(void) { csd_t csd; if (!readCSD(&csd)) return 0; if (csd.v1.csd_ver == 0) { uint8_t read_bl_len = csd.v1.read_bl_len; uint16_t c_size = (csd.v1.c_size_high << 10) | (csd.v1.c_size_mid << 2) | csd.v1.c_size_low; uint8_t c_size_mult = (csd.v1.c_size_mult_high << 1) | csd.v1.c_size_mult_low; return (uint32_t)(c_size + 1) << (c_size_mult + read_bl_len - 7); } else if (csd.v2.csd_ver == 1) { uint32_t c_size = ((uint32_t)csd.v2.c_size_high << 16) | (csd.v2.c_size_mid << 8) | csd.v2.c_size_low; return (c_size + 1) << 10; } else { error(SD_CARD_ERROR_BAD_CSD); return 0; } } //------------------------------------------------------------------------------ void Sd2Card::chipSelectHigh(void) { digitalWrite(chipSelectPin_, HIGH); } //------------------------------------------------------------------------------ void Sd2Card::chipSelectLow(void) { digitalWrite(chipSelectPin_, LOW); } //------------------------------------------------------------------------------ /** Erase a range of blocks. * * \param[in] firstBlock The address of the first block in the range. * \param[in] lastBlock The address of the last block in the range. * * \note This function requests the SD card to do a flash erase for a * range of blocks. The data on the card after an erase operation is * either 0 or 1, depends on the card vendor. The card must support * single block erase. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) { if (!eraseSingleBlockEnable()) { error(SD_CARD_ERROR_ERASE_SINGLE_BLOCK); goto fail; } if (type_ != SD_CARD_TYPE_SDHC) { firstBlock <<= 9; lastBlock <<= 9; } if (cardCommand(CMD32, firstBlock) || cardCommand(CMD33, lastBlock) || cardCommand(CMD38, 0)) { error(SD_CARD_ERROR_ERASE); goto fail; } if (!waitNotBusy(SD_ERASE_TIMEOUT)) { error(SD_CARD_ERROR_ERASE_TIMEOUT); goto fail; } chipSelectHigh(); return true; fail: chipSelectHigh(); return false; } //------------------------------------------------------------------------------ /** Determine if card supports single block erase. * * \return The value one, true, is returned if single block erase is supported. * The value zero, false, is returned if single block erase is not supported. */ uint8_t Sd2Card::eraseSingleBlockEnable(void) { csd_t csd; return readCSD(&csd) ? csd.v1.erase_blk_en : 0; } //------------------------------------------------------------------------------ /** * Initialize an SD flash memory card. * * \param[in] sckRateID SPI clock rate selector. See setSckRate(). * \param[in] chipSelectPin SD chip select pin number. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. The reason for failure * can be determined by calling errorCode() and errorData(). */ uint8_t Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { errorCode_ = inBlock_ = partialBlockRead_ = type_ = 0; chipSelectPin_ = chipSelectPin; // 16-bit init start time allows over a minute uint16_t t0 = (uint16_t)millis(); uint32_t arg; // set pin modes pinMode(chipSelectPin_, OUTPUT); chipSelectHigh(); pinMode(SPI_MISO_PIN, INPUT); pinMode(SPI_MOSI_PIN, OUTPUT); pinMode(SPI_SCK_PIN, OUTPUT); #ifndef SOFTWARE_SPI // SS must be in output mode even it is not chip select pinMode(SS_PIN, OUTPUT); // Enable SPI, Master, clock rate f_osc/128 SPCR = (1 << SPE) | (1 << MSTR) | (1 << SPR1) | (1 << SPR0); // clear double speed SPSR &= ~(1 << SPI2X); #endif // SOFTWARE_SPI // must supply min of 74 clock cycles with CS high. for (uint8_t i = 0; i < 10; i++) spiSend(0XFF); chipSelectLow(); // command to go idle in SPI mode while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) { if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) { error(SD_CARD_ERROR_CMD0); goto fail; } } // check SD version if ((cardCommand(CMD8, 0x1AA) & R1_ILLEGAL_COMMAND)) { type(SD_CARD_TYPE_SD1); } else { // only need last byte of r7 response for (uint8_t i = 0; i < 4; i++) status_ = spiRec(); if (status_ != 0XAA) { error(SD_CARD_ERROR_CMD8); goto fail; } type(SD_CARD_TYPE_SD2); } // initialize card and send host supports SDHC if SD2 arg = type() == SD_CARD_TYPE_SD2 ? 0X40000000 : 0; while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) { // check for timeout if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) { error(SD_CARD_ERROR_ACMD41); goto fail; } } // if SD2 read OCR register to check for SDHC card if (type() == SD_CARD_TYPE_SD2) { if (cardCommand(CMD58, 0)) { error(SD_CARD_ERROR_CMD58); goto fail; } if ((spiRec() & 0XC0) == 0XC0) type(SD_CARD_TYPE_SDHC); // discard rest of ocr - contains allowed voltage range for (uint8_t i = 0; i < 3; i++) spiRec(); } chipSelectHigh(); #ifndef SOFTWARE_SPI return setSckRate(sckRateID); #else // SOFTWARE_SPI return true; #endif // SOFTWARE_SPI fail: chipSelectHigh(); return false; } //------------------------------------------------------------------------------ /** * Enable or disable partial block reads. * * Enabling partial block reads improves performance by allowing a block * to be read over the SPI bus as several sub-blocks. Errors may occur * if the time between reads is too long since the SD card may timeout. * The SPI SS line will be held low until the entire block is read or * readEnd() is called. * * Use this for applications like the Adafruit Wave Shield. * * \param[in] value The value TRUE (non-zero) or FALSE (zero).) */ void Sd2Card::partialBlockRead(uint8_t value) { readEnd(); partialBlockRead_ = value; } //------------------------------------------------------------------------------ /** * Read a 512 byte block from an SD card device. * * \param[in] block Logical block to be read. * \param[out] dst Pointer to the location that will receive the data. * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t Sd2Card::readBlock(uint32_t block, uint8_t* dst) { return readData(block, 0, 512, dst); } //------------------------------------------------------------------------------ /** * Read part of a 512 byte block from an SD card. * * \param[in] block Logical block to be read. * \param[in] offset Number of bytes to skip at start of block * \param[out] dst Pointer to the location that will receive the data. * \param[in] count Number of bytes to read * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t Sd2Card::readData(uint32_t block, uint16_t offset, uint16_t count, uint8_t* dst) { uint16_t n; if (count == 0) return true; if ((count + offset) > 512) { goto fail; } if (!inBlock_ || block != block_ || offset < offset_) { block_ = block; // use address if not SDHC card if (type()!= SD_CARD_TYPE_SDHC) block <<= 9; if (cardCommand(CMD17, block)) { error(SD_CARD_ERROR_CMD17); goto fail; } if (!waitStartBlock()) { goto fail; } offset_ = 0; inBlock_ = 1; } #ifdef OPTIMIZE_HARDWARE_SPI // start first spi transfer SPDR = 0XFF; // skip data before offset for (;offset_ < offset; offset_++) { while (!(SPSR & (1 << SPIF))); SPDR = 0XFF; } // transfer data n = count - 1; for (uint16_t i = 0; i < n; i++) { while (!(SPSR & (1 << SPIF))); dst[i] = SPDR; SPDR = 0XFF; } // wait for last byte while (!(SPSR & (1 << SPIF))); dst[n] = SPDR; #else // OPTIMIZE_HARDWARE_SPI // skip data before offset for (;offset_ < offset; offset_++) { spiRec(); } // transfer data for (uint16_t i = 0; i < count; i++) { dst[i] = spiRec(); } #endif // OPTIMIZE_HARDWARE_SPI offset_ += count; if (!partialBlockRead_ || offset_ >= 512) { // read rest of data, checksum and set chip select high readEnd(); } return true; fail: chipSelectHigh(); return false; } //------------------------------------------------------------------------------ /** Skip remaining data in a block when in partial block read mode. */ void Sd2Card::readEnd(void) { if (inBlock_) { // skip data and crc #ifdef OPTIMIZE_HARDWARE_SPI // optimize skip for hardware SPDR = 0XFF; while (offset_++ < 513) { while (!(SPSR & (1 << SPIF))); SPDR = 0XFF; } // wait for last crc byte while (!(SPSR & (1 << SPIF))); #else // OPTIMIZE_HARDWARE_SPI while (offset_++ < 514) spiRec(); #endif // OPTIMIZE_HARDWARE_SPI chipSelectHigh(); inBlock_ = 0; } } //------------------------------------------------------------------------------ /** read CID or CSR register */ uint8_t Sd2Card::readRegister(uint8_t cmd, void* buf) { uint8_t* dst = reinterpret_cast(buf); if (cardCommand(cmd, 0)) { error(SD_CARD_ERROR_READ_REG); goto fail; } if (!waitStartBlock()) goto fail; // transfer data for (uint16_t i = 0; i < 16; i++) dst[i] = spiRec(); spiRec(); // get first crc byte spiRec(); // get second crc byte chipSelectHigh(); return true; fail: chipSelectHigh(); return false; } //------------------------------------------------------------------------------ /** * Set the SPI clock rate. * * \param[in] sckRateID A value in the range [0, 6]. * * The SPI clock will be set to F_CPU/pow(2, 1 + sckRateID). The maximum * SPI rate is F_CPU/2 for \a sckRateID = 0 and the minimum rate is F_CPU/128 * for \a scsRateID = 6. * * \return The value one, true, is returned for success and the value zero, * false, is returned for an invalid value of \a sckRateID. */ uint8_t Sd2Card::setSckRate(uint8_t sckRateID) { if (sckRateID > 6) { error(SD_CARD_ERROR_SCK_RATE); return false; } // see avr processor datasheet for SPI register bit definitions if ((sckRateID & 1) || sckRateID == 6) { SPSR &= ~(1 << SPI2X); } else { SPSR |= (1 << SPI2X); } SPCR &= ~((1 < SD_READ_TIMEOUT) { error(SD_CARD_ERROR_READ_TIMEOUT); goto fail; } } if (status_ != DATA_START_BLOCK) { error(SD_CARD_ERROR_READ); goto fail; } return true; fail: chipSelectHigh(); return false; } //------------------------------------------------------------------------------ /** * Writes a 512 byte block to an SD card. * * \param[in] blockNumber Logical block to be written. * \param[in] src Pointer to the location of the data to be written. * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) { #if SD_PROTECT_BLOCK_ZERO // don't allow write to first block if (blockNumber == 0) { error(SD_CARD_ERROR_WRITE_BLOCK_ZERO); goto fail; } #endif // SD_PROTECT_BLOCK_ZERO // use address if not SDHC card if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; if (cardCommand(CMD24, blockNumber)) { error(SD_CARD_ERROR_CMD24); goto fail; } if (!writeData(DATA_START_BLOCK, src)) goto fail; // wait for flash programming to complete if (!waitNotBusy(SD_WRITE_TIMEOUT)) { error(SD_CARD_ERROR_WRITE_TIMEOUT); goto fail; } // response is r2 so get and check two bytes for nonzero if (cardCommand(CMD13, 0) || spiRec()) { error(SD_CARD_ERROR_WRITE_PROGRAMMING); goto fail; } chipSelectHigh(); return true; fail: chipSelectHigh(); return false; } //------------------------------------------------------------------------------ /** Write one data block in a multiple block write sequence */ uint8_t Sd2Card::writeData(const uint8_t* src) { // wait for previous write to finish if (!waitNotBusy(SD_WRITE_TIMEOUT)) { error(SD_CARD_ERROR_WRITE_MULTIPLE); chipSelectHigh(); return false; } return writeData(WRITE_MULTIPLE_TOKEN, src); } //------------------------------------------------------------------------------ // send one block of data for write block or write multiple blocks uint8_t Sd2Card::writeData(uint8_t token, const uint8_t* src) { #ifdef OPTIMIZE_HARDWARE_SPI // send data - optimized loop SPDR = token; // send two byte per iteration for (uint16_t i = 0; i < 512; i += 2) { while (!(SPSR & (1 << SPIF))); SPDR = src[i]; while (!(SPSR & (1 << SPIF))); SPDR = src[i+1]; } // wait for last data byte while (!(SPSR & (1 << SPIF))); #else // OPTIMIZE_HARDWARE_SPI spiSend(token); for (uint16_t i = 0; i < 512; i++) { spiSend(src[i]); } #endif // OPTIMIZE_HARDWARE_SPI spiSend(0xff); // dummy crc spiSend(0xff); // dummy crc status_ = spiRec(); if ((status_ & DATA_RES_MASK) != DATA_RES_ACCEPTED) { error(SD_CARD_ERROR_WRITE); chipSelectHigh(); return false; } return true; } //------------------------------------------------------------------------------ /** Start a write multiple blocks sequence. * * \param[in] blockNumber Address of first block in sequence. * \param[in] eraseCount The number of blocks to be pre-erased. * * \note This function is used with writeData() and writeStop() * for optimized multiple block writes. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) { #if SD_PROTECT_BLOCK_ZERO // don't allow write to first block if (blockNumber == 0) { error(SD_CARD_ERROR_WRITE_BLOCK_ZERO); goto fail; } #endif // SD_PROTECT_BLOCK_ZERO // send pre-erase count if (cardAcmd(ACMD23, eraseCount)) { error(SD_CARD_ERROR_ACMD23); goto fail; } // use address if not SDHC card if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; if (cardCommand(CMD25, blockNumber)) { error(SD_CARD_ERROR_CMD25); goto fail; } return true; fail: chipSelectHigh(); return false; } //------------------------------------------------------------------------------ /** End a write multiple blocks sequence. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t Sd2Card::writeStop(void) { if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail; spiSend(STOP_TRAN_TOKEN); if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail; chipSelectHigh(); return true; fail: error(SD_CARD_ERROR_STOP_TRAN); chipSelectHigh(); return false; } ================================================ FILE: Sprinter/Sd2Card.h ================================================ /* Arduino Sd2Card Library * Copyright (C) 2009 by William Greiman * * This file is part of the Arduino Sd2Card Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with the Arduino Sd2Card Library. If not, see * . */ #ifndef Sd2Card_h #define Sd2Card_h /** * \file * Sd2Card class */ #include "Sd2PinMap.h" #include "SdInfo.h" /** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */ uint8_t const SPI_FULL_SPEED = 0; /** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */ uint8_t const SPI_HALF_SPEED = 1; /** Set SCK rate to F_CPU/8. Sd2Card::setSckRate(). */ uint8_t const SPI_QUARTER_SPEED = 2; /** * Define MEGA_SOFT_SPI non-zero to use software SPI on Mega Arduinos. * Pins used are SS 10, MOSI 11, MISO 12, and SCK 13. * * MEGA_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used * on Mega Arduinos. Software SPI works well with GPS Shield V1.1 * but many SD cards will fail with GPS Shield V1.0. */ #define MEGA_SOFT_SPI 0 //------------------------------------------------------------------------------ #if MEGA_SOFT_SPI && (defined(__AVR_ATmega1280__)||defined(__AVR_ATmega2560__)) #define SOFTWARE_SPI #endif // MEGA_SOFT_SPI //------------------------------------------------------------------------------ // SPI pin definitions // #ifndef SOFTWARE_SPI // hardware pin defs /** * SD Chip Select pin * * Warning if this pin is redefined the hardware SS will pin will be enabled * as an output by init(). An avr processor will not function as an SPI * master unless SS is set to output mode. */ /** The default chip select pin for the SD card is SS. */ uint8_t const SD_CHIP_SELECT_PIN = SS_PIN; // The following three pins must not be redefined for hardware SPI. /** SPI Master Out Slave In pin */ uint8_t const SPI_MOSI_PIN = MOSI_PIN; /** SPI Master In Slave Out pin */ uint8_t const SPI_MISO_PIN = MISO_PIN; /** SPI Clock pin */ uint8_t const SPI_SCK_PIN = SCK_PIN; /** optimize loops for hardware SPI */ #define OPTIMIZE_HARDWARE_SPI #else // SOFTWARE_SPI // define software SPI pins so Mega can use unmodified GPS Shield /** SPI chip select pin */ uint8_t const SD_CHIP_SELECT_PIN = 10; /** SPI Master Out Slave In pin */ uint8_t const SPI_MOSI_PIN = 11; /** SPI Master In Slave Out pin */ uint8_t const SPI_MISO_PIN = 12; /** SPI Clock pin */ uint8_t const SPI_SCK_PIN = 13; #endif // SOFTWARE_SPI //------------------------------------------------------------------------------ /** Protect block zero from write if nonzero */ #define SD_PROTECT_BLOCK_ZERO 1 /** init timeout ms */ uint16_t const SD_INIT_TIMEOUT = 2000; /** erase timeout ms */ uint16_t const SD_ERASE_TIMEOUT = 10000; /** read timeout ms */ uint16_t const SD_READ_TIMEOUT = 300; /** write time out ms */ uint16_t const SD_WRITE_TIMEOUT = 600; //------------------------------------------------------------------------------ // SD card errors /** timeout error for command CMD0 */ uint8_t const SD_CARD_ERROR_CMD0 = 0X1; /** CMD8 was not accepted - not a valid SD card*/ uint8_t const SD_CARD_ERROR_CMD8 = 0X2; /** card returned an error response for CMD17 (read block) */ uint8_t const SD_CARD_ERROR_CMD17 = 0X3; /** card returned an error response for CMD24 (write block) */ uint8_t const SD_CARD_ERROR_CMD24 = 0X4; /** WRITE_MULTIPLE_BLOCKS command failed */ uint8_t const SD_CARD_ERROR_CMD25 = 0X05; /** card returned an error response for CMD58 (read OCR) */ uint8_t const SD_CARD_ERROR_CMD58 = 0X06; /** SET_WR_BLK_ERASE_COUNT failed */ uint8_t const SD_CARD_ERROR_ACMD23 = 0X07; /** card's ACMD41 initialization process timeout */ uint8_t const SD_CARD_ERROR_ACMD41 = 0X08; /** card returned a bad CSR version field */ uint8_t const SD_CARD_ERROR_BAD_CSD = 0X09; /** erase block group command failed */ uint8_t const SD_CARD_ERROR_ERASE = 0X0A; /** card not capable of single block erase */ uint8_t const SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0X0B; /** Erase sequence timed out */ uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0X0C; /** card returned an error token instead of read data */ uint8_t const SD_CARD_ERROR_READ = 0X0D; /** read CID or CSD failed */ uint8_t const SD_CARD_ERROR_READ_REG = 0X0E; /** timeout while waiting for start of read data */ uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0X0F; /** card did not accept STOP_TRAN_TOKEN */ uint8_t const SD_CARD_ERROR_STOP_TRAN = 0X10; /** card returned an error token as a response to a write operation */ uint8_t const SD_CARD_ERROR_WRITE = 0X11; /** attempt to write protected block zero */ uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0X12; /** card did not go ready for a multiple block write */ uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0X13; /** card returned an error to a CMD13 status check after a write */ uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0X14; /** timeout occurred during write programming */ uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0X15; /** incorrect rate selected */ uint8_t const SD_CARD_ERROR_SCK_RATE = 0X16; //------------------------------------------------------------------------------ // card types /** Standard capacity V1 SD card */ uint8_t const SD_CARD_TYPE_SD1 = 1; /** Standard capacity V2 SD card */ uint8_t const SD_CARD_TYPE_SD2 = 2; /** High Capacity SD card */ uint8_t const SD_CARD_TYPE_SDHC = 3; //------------------------------------------------------------------------------ /** * \class Sd2Card * \brief Raw access to SD and SDHC flash memory cards. */ class Sd2Card { public: /** Construct an instance of Sd2Card. */ Sd2Card(void) : errorCode_(0), inBlock_(0), partialBlockRead_(0), type_(0) {} uint32_t cardSize(void); uint8_t erase(uint32_t firstBlock, uint32_t lastBlock); uint8_t eraseSingleBlockEnable(void); /** * \return error code for last error. See Sd2Card.h for a list of error codes. */ uint8_t errorCode(void) const {return errorCode_;} /** \return error data for last error. */ uint8_t errorData(void) const {return status_;} /** * Initialize an SD flash memory card with default clock rate and chip * select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin). */ uint8_t init(void) { return init(SPI_FULL_SPEED, SD_CHIP_SELECT_PIN); } /** * Initialize an SD flash memory card with the selected SPI clock rate * and the default SD chip select pin. * See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin). */ uint8_t init(uint8_t sckRateID) { return init(sckRateID, SD_CHIP_SELECT_PIN); } uint8_t init(uint8_t sckRateID, uint8_t chipSelectPin); void partialBlockRead(uint8_t value); /** Returns the current value, true or false, for partial block read. */ uint8_t partialBlockRead(void) const {return partialBlockRead_;} uint8_t readBlock(uint32_t block, uint8_t* dst); uint8_t readData(uint32_t block, uint16_t offset, uint16_t count, uint8_t* dst); /** * Read a cards CID register. The CID contains card identification * information such as Manufacturer ID, Product name, Product serial * number and Manufacturing date. */ uint8_t readCID(cid_t* cid) { return readRegister(CMD10, cid); } /** * Read a cards CSD register. The CSD contains Card-Specific Data that * provides information regarding access to the card's contents. */ uint8_t readCSD(csd_t* csd) { return readRegister(CMD9, csd); } void readEnd(void); uint8_t setSckRate(uint8_t sckRateID); /** Return the card type: SD V1, SD V2 or SDHC */ uint8_t type(void) const {return type_;} uint8_t writeBlock(uint32_t blockNumber, const uint8_t* src); uint8_t writeData(const uint8_t* src); uint8_t writeStart(uint32_t blockNumber, uint32_t eraseCount); uint8_t writeStop(void); private: uint32_t block_; uint8_t chipSelectPin_; uint8_t errorCode_; uint8_t inBlock_; uint16_t offset_; uint8_t partialBlockRead_; uint8_t status_; uint8_t type_; // private functions uint8_t cardAcmd(uint8_t cmd, uint32_t arg) { cardCommand(CMD55, 0); return cardCommand(cmd, arg); } uint8_t cardCommand(uint8_t cmd, uint32_t arg); void error(uint8_t code) {errorCode_ = code;} uint8_t readRegister(uint8_t cmd, void* buf); uint8_t sendWriteCommand(uint32_t blockNumber, uint32_t eraseCount); void chipSelectHigh(void); void chipSelectLow(void); void type(uint8_t value) {type_ = value;} uint8_t waitNotBusy(uint16_t timeoutMillis); uint8_t writeData(uint8_t token, const uint8_t* src); uint8_t waitStartBlock(void); }; #endif // Sd2Card_h ================================================ FILE: Sprinter/Sd2PinMap.h ================================================ /* Arduino SdFat Library * Copyright (C) 2010 by William Greiman * * This file is part of the Arduino SdFat Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with the Arduino SdFat Library. If not, see * . */ // Warning this file was generated by a program. #ifndef Sd2PinMap_h #define Sd2PinMap_h #include //------------------------------------------------------------------------------ /** struct for mapping digital pins */ struct pin_map_t { volatile uint8_t* ddr; volatile uint8_t* pin; volatile uint8_t* port; uint8_t bit; }; //------------------------------------------------------------------------------ #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) // Mega // Two Wire (aka I2C) ports uint8_t const SDA_PIN = 20; uint8_t const SCL_PIN = 21; // SPI port uint8_t const SS_PIN = 53; uint8_t const MOSI_PIN = 51; uint8_t const MISO_PIN = 50; uint8_t const SCK_PIN = 52; static const pin_map_t digitalPinMap[] = { {&DDRE, &PINE, &PORTE, 0}, // E0 0 {&DDRE, &PINE, &PORTE, 1}, // E1 1 {&DDRE, &PINE, &PORTE, 4}, // E4 2 {&DDRE, &PINE, &PORTE, 5}, // E5 3 {&DDRG, &PING, &PORTG, 5}, // G5 4 {&DDRE, &PINE, &PORTE, 3}, // E3 5 {&DDRH, &PINH, &PORTH, 3}, // H3 6 {&DDRH, &PINH, &PORTH, 4}, // H4 7 {&DDRH, &PINH, &PORTH, 5}, // H5 8 {&DDRH, &PINH, &PORTH, 6}, // H6 9 {&DDRB, &PINB, &PORTB, 4}, // B4 10 {&DDRB, &PINB, &PORTB, 5}, // B5 11 {&DDRB, &PINB, &PORTB, 6}, // B6 12 {&DDRB, &PINB, &PORTB, 7}, // B7 13 {&DDRJ, &PINJ, &PORTJ, 1}, // J1 14 {&DDRJ, &PINJ, &PORTJ, 0}, // J0 15 {&DDRH, &PINH, &PORTH, 1}, // H1 16 {&DDRH, &PINH, &PORTH, 0}, // H0 17 {&DDRD, &PIND, &PORTD, 3}, // D3 18 {&DDRD, &PIND, &PORTD, 2}, // D2 19 {&DDRD, &PIND, &PORTD, 1}, // D1 20 {&DDRD, &PIND, &PORTD, 0}, // D0 21 {&DDRA, &PINA, &PORTA, 0}, // A0 22 {&DDRA, &PINA, &PORTA, 1}, // A1 23 {&DDRA, &PINA, &PORTA, 2}, // A2 24 {&DDRA, &PINA, &PORTA, 3}, // A3 25 {&DDRA, &PINA, &PORTA, 4}, // A4 26 {&DDRA, &PINA, &PORTA, 5}, // A5 27 {&DDRA, &PINA, &PORTA, 6}, // A6 28 {&DDRA, &PINA, &PORTA, 7}, // A7 29 {&DDRC, &PINC, &PORTC, 7}, // C7 30 {&DDRC, &PINC, &PORTC, 6}, // C6 31 {&DDRC, &PINC, &PORTC, 5}, // C5 32 {&DDRC, &PINC, &PORTC, 4}, // C4 33 {&DDRC, &PINC, &PORTC, 3}, // C3 34 {&DDRC, &PINC, &PORTC, 2}, // C2 35 {&DDRC, &PINC, &PORTC, 1}, // C1 36 {&DDRC, &PINC, &PORTC, 0}, // C0 37 {&DDRD, &PIND, &PORTD, 7}, // D7 38 {&DDRG, &PING, &PORTG, 2}, // G2 39 {&DDRG, &PING, &PORTG, 1}, // G1 40 {&DDRG, &PING, &PORTG, 0}, // G0 41 {&DDRL, &PINL, &PORTL, 7}, // L7 42 {&DDRL, &PINL, &PORTL, 6}, // L6 43 {&DDRL, &PINL, &PORTL, 5}, // L5 44 {&DDRL, &PINL, &PORTL, 4}, // L4 45 {&DDRL, &PINL, &PORTL, 3}, // L3 46 {&DDRL, &PINL, &PORTL, 2}, // L2 47 {&DDRL, &PINL, &PORTL, 1}, // L1 48 {&DDRL, &PINL, &PORTL, 0}, // L0 49 {&DDRB, &PINB, &PORTB, 3}, // B3 50 {&DDRB, &PINB, &PORTB, 2}, // B2 51 {&DDRB, &PINB, &PORTB, 1}, // B1 52 {&DDRB, &PINB, &PORTB, 0}, // B0 53 {&DDRF, &PINF, &PORTF, 0}, // F0 54 {&DDRF, &PINF, &PORTF, 1}, // F1 55 {&DDRF, &PINF, &PORTF, 2}, // F2 56 {&DDRF, &PINF, &PORTF, 3}, // F3 57 {&DDRF, &PINF, &PORTF, 4}, // F4 58 {&DDRF, &PINF, &PORTF, 5}, // F5 59 {&DDRF, &PINF, &PORTF, 6}, // F6 60 {&DDRF, &PINF, &PORTF, 7}, // F7 61 {&DDRK, &PINK, &PORTK, 0}, // K0 62 {&DDRK, &PINK, &PORTK, 1}, // K1 63 {&DDRK, &PINK, &PORTK, 2}, // K2 64 {&DDRK, &PINK, &PORTK, 3}, // K3 65 {&DDRK, &PINK, &PORTK, 4}, // K4 66 {&DDRK, &PINK, &PORTK, 5}, // K5 67 {&DDRK, &PINK, &PORTK, 6}, // K6 68 {&DDRK, &PINK, &PORTK, 7} // K7 69 }; //------------------------------------------------------------------------------ #elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega1284P__) // Sanguino // Two Wire (aka I2C) ports uint8_t const SDA_PIN = 17; uint8_t const SCL_PIN = 18; // SPI port uint8_t const SS_PIN = 4; uint8_t const MOSI_PIN = 5; uint8_t const MISO_PIN = 6; uint8_t const SCK_PIN = 7; static const pin_map_t digitalPinMap[] = { {&DDRB, &PINB, &PORTB, 0}, // B0 0 {&DDRB, &PINB, &PORTB, 1}, // B1 1 {&DDRB, &PINB, &PORTB, 2}, // B2 2 {&DDRB, &PINB, &PORTB, 3}, // B3 3 {&DDRB, &PINB, &PORTB, 4}, // B4 4 {&DDRB, &PINB, &PORTB, 5}, // B5 5 {&DDRB, &PINB, &PORTB, 6}, // B6 6 {&DDRB, &PINB, &PORTB, 7}, // B7 7 {&DDRD, &PIND, &PORTD, 0}, // D0 8 {&DDRD, &PIND, &PORTD, 1}, // D1 9 {&DDRD, &PIND, &PORTD, 2}, // D2 10 {&DDRD, &PIND, &PORTD, 3}, // D3 11 {&DDRD, &PIND, &PORTD, 4}, // D4 12 {&DDRD, &PIND, &PORTD, 5}, // D5 13 {&DDRD, &PIND, &PORTD, 6}, // D6 14 {&DDRD, &PIND, &PORTD, 7}, // D7 15 {&DDRC, &PINC, &PORTC, 0}, // C0 16 {&DDRC, &PINC, &PORTC, 1}, // C1 17 {&DDRC, &PINC, &PORTC, 2}, // C2 18 {&DDRC, &PINC, &PORTC, 3}, // C3 19 {&DDRC, &PINC, &PORTC, 4}, // C4 20 {&DDRC, &PINC, &PORTC, 5}, // C5 21 {&DDRC, &PINC, &PORTC, 6}, // C6 22 {&DDRC, &PINC, &PORTC, 7}, // C7 23 {&DDRA, &PINA, &PORTA, 7}, // A7 24 {&DDRA, &PINA, &PORTA, 6}, // A6 25 {&DDRA, &PINA, &PORTA, 5}, // A5 26 {&DDRA, &PINA, &PORTA, 4}, // A4 27 {&DDRA, &PINA, &PORTA, 3}, // A3 28 {&DDRA, &PINA, &PORTA, 2}, // A2 29 {&DDRA, &PINA, &PORTA, 1}, // A1 30 {&DDRA, &PINA, &PORTA, 0} // A0 31 }; //------------------------------------------------------------------------------ #elif defined(__AVR_ATmega32U4__) // Teensy 2.0 // Two Wire (aka I2C) ports uint8_t const SDA_PIN = 6; uint8_t const SCL_PIN = 5; // SPI port uint8_t const SS_PIN = 0; uint8_t const MOSI_PIN = 2; uint8_t const MISO_PIN = 3; uint8_t const SCK_PIN = 1; static const pin_map_t digitalPinMap[] = { {&DDRB, &PINB, &PORTB, 0}, // B0 0 {&DDRB, &PINB, &PORTB, 1}, // B1 1 {&DDRB, &PINB, &PORTB, 2}, // B2 2 {&DDRB, &PINB, &PORTB, 3}, // B3 3 {&DDRB, &PINB, &PORTB, 7}, // B7 4 {&DDRD, &PIND, &PORTD, 0}, // D0 5 {&DDRD, &PIND, &PORTD, 1}, // D1 6 {&DDRD, &PIND, &PORTD, 2}, // D2 7 {&DDRD, &PIND, &PORTD, 3}, // D3 8 {&DDRC, &PINC, &PORTC, 6}, // C6 9 {&DDRC, &PINC, &PORTC, 7}, // C7 10 {&DDRD, &PIND, &PORTD, 6}, // D6 11 {&DDRD, &PIND, &PORTD, 7}, // D7 12 {&DDRB, &PINB, &PORTB, 4}, // B4 13 {&DDRB, &PINB, &PORTB, 5}, // B5 14 {&DDRB, &PINB, &PORTB, 6}, // B6 15 {&DDRF, &PINF, &PORTF, 7}, // F7 16 {&DDRF, &PINF, &PORTF, 6}, // F6 17 {&DDRF, &PINF, &PORTF, 5}, // F5 18 {&DDRF, &PINF, &PORTF, 4}, // F4 19 {&DDRF, &PINF, &PORTF, 1}, // F1 20 {&DDRF, &PINF, &PORTF, 0}, // F0 21 {&DDRD, &PIND, &PORTD, 4}, // D4 22 {&DDRD, &PIND, &PORTD, 5}, // D5 23 {&DDRE, &PINE, &PORTE, 6} // E6 24 }; //------------------------------------------------------------------------------ #elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__) // Teensy++ 1.0 & 2.0 // Two Wire (aka I2C) ports uint8_t const SDA_PIN = 1; uint8_t const SCL_PIN = 0; // SPI port uint8_t const SS_PIN = 20; uint8_t const MOSI_PIN = 22; uint8_t const MISO_PIN = 23; uint8_t const SCK_PIN = 21; static const pin_map_t digitalPinMap[] = { {&DDRD, &PIND, &PORTD, 0}, // D0 0 {&DDRD, &PIND, &PORTD, 1}, // D1 1 {&DDRD, &PIND, &PORTD, 2}, // D2 2 {&DDRD, &PIND, &PORTD, 3}, // D3 3 {&DDRD, &PIND, &PORTD, 4}, // D4 4 {&DDRD, &PIND, &PORTD, 5}, // D5 5 {&DDRD, &PIND, &PORTD, 6}, // D6 6 {&DDRD, &PIND, &PORTD, 7}, // D7 7 {&DDRE, &PINE, &PORTE, 0}, // E0 8 {&DDRE, &PINE, &PORTE, 1}, // E1 9 {&DDRC, &PINC, &PORTC, 0}, // C0 10 {&DDRC, &PINC, &PORTC, 1}, // C1 11 {&DDRC, &PINC, &PORTC, 2}, // C2 12 {&DDRC, &PINC, &PORTC, 3}, // C3 13 {&DDRC, &PINC, &PORTC, 4}, // C4 14 {&DDRC, &PINC, &PORTC, 5}, // C5 15 {&DDRC, &PINC, &PORTC, 6}, // C6 16 {&DDRC, &PINC, &PORTC, 7}, // C7 17 {&DDRE, &PINE, &PORTE, 6}, // E6 18 {&DDRE, &PINE, &PORTE, 7}, // E7 19 {&DDRB, &PINB, &PORTB, 0}, // B0 20 {&DDRB, &PINB, &PORTB, 1}, // B1 21 {&DDRB, &PINB, &PORTB, 2}, // B2 22 {&DDRB, &PINB, &PORTB, 3}, // B3 23 {&DDRB, &PINB, &PORTB, 4}, // B4 24 {&DDRB, &PINB, &PORTB, 5}, // B5 25 {&DDRB, &PINB, &PORTB, 6}, // B6 26 {&DDRB, &PINB, &PORTB, 7}, // B7 27 {&DDRA, &PINA, &PORTA, 0}, // A0 28 {&DDRA, &PINA, &PORTA, 1}, // A1 29 {&DDRA, &PINA, &PORTA, 2}, // A2 30 {&DDRA, &PINA, &PORTA, 3}, // A3 31 {&DDRA, &PINA, &PORTA, 4}, // A4 32 {&DDRA, &PINA, &PORTA, 5}, // A5 33 {&DDRA, &PINA, &PORTA, 6}, // A6 34 {&DDRA, &PINA, &PORTA, 7}, // A7 35 {&DDRE, &PINE, &PORTE, 4}, // E4 36 {&DDRE, &PINE, &PORTE, 5}, // E5 37 {&DDRF, &PINF, &PORTF, 0}, // F0 38 {&DDRF, &PINF, &PORTF, 1}, // F1 39 {&DDRF, &PINF, &PORTF, 2}, // F2 40 {&DDRF, &PINF, &PORTF, 3}, // F3 41 {&DDRF, &PINF, &PORTF, 4}, // F4 42 {&DDRF, &PINF, &PORTF, 5}, // F5 43 {&DDRF, &PINF, &PORTF, 6}, // F6 44 {&DDRF, &PINF, &PORTF, 7} // F7 45 }; //------------------------------------------------------------------------------ #else // defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) // 168 and 328 Arduinos // Two Wire (aka I2C) ports uint8_t const SDA_PIN = 18; uint8_t const SCL_PIN = 19; // SPI port uint8_t const SS_PIN = 10; uint8_t const MOSI_PIN = 11; uint8_t const MISO_PIN = 12; uint8_t const SCK_PIN = 13; static const pin_map_t digitalPinMap[] = { {&DDRD, &PIND, &PORTD, 0}, // D0 0 {&DDRD, &PIND, &PORTD, 1}, // D1 1 {&DDRD, &PIND, &PORTD, 2}, // D2 2 {&DDRD, &PIND, &PORTD, 3}, // D3 3 {&DDRD, &PIND, &PORTD, 4}, // D4 4 {&DDRD, &PIND, &PORTD, 5}, // D5 5 {&DDRD, &PIND, &PORTD, 6}, // D6 6 {&DDRD, &PIND, &PORTD, 7}, // D7 7 {&DDRB, &PINB, &PORTB, 0}, // B0 8 {&DDRB, &PINB, &PORTB, 1}, // B1 9 {&DDRB, &PINB, &PORTB, 2}, // B2 10 {&DDRB, &PINB, &PORTB, 3}, // B3 11 {&DDRB, &PINB, &PORTB, 4}, // B4 12 {&DDRB, &PINB, &PORTB, 5}, // B5 13 {&DDRC, &PINC, &PORTC, 0}, // C0 14 {&DDRC, &PINC, &PORTC, 1}, // C1 15 {&DDRC, &PINC, &PORTC, 2}, // C2 16 {&DDRC, &PINC, &PORTC, 3}, // C3 17 {&DDRC, &PINC, &PORTC, 4}, // C4 18 {&DDRC, &PINC, &PORTC, 5} // C5 19 }; #endif // defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //------------------------------------------------------------------------------ static const uint8_t digitalPinCount = sizeof(digitalPinMap)/sizeof(pin_map_t); uint8_t badPinNumber(void) __attribute__((error("Pin number is too large or not a constant"))); static inline __attribute__((always_inline)) uint8_t getPinMode(uint8_t pin) { if (__builtin_constant_p(pin) && pin < digitalPinCount) { return (*digitalPinMap[pin].ddr >> digitalPinMap[pin].bit) & 1; } else { return badPinNumber(); } } static inline __attribute__((always_inline)) void setPinMode(uint8_t pin, uint8_t mode) { if (__builtin_constant_p(pin) && pin < digitalPinCount) { if (mode) { *digitalPinMap[pin].ddr |= 1 << digitalPinMap[pin].bit; } else { *digitalPinMap[pin].ddr &= ~(1 << digitalPinMap[pin].bit); } } else { badPinNumber(); } } static inline __attribute__((always_inline)) uint8_t fastDigitalRead(uint8_t pin) { if (__builtin_constant_p(pin) && pin < digitalPinCount) { return (*digitalPinMap[pin].pin >> digitalPinMap[pin].bit) & 1; } else { return badPinNumber(); } } static inline __attribute__((always_inline)) void fastDigitalWrite(uint8_t pin, uint8_t value) { if (__builtin_constant_p(pin) && pin < digitalPinCount) { if (value) { *digitalPinMap[pin].port |= 1 << digitalPinMap[pin].bit; } else { *digitalPinMap[pin].port &= ~(1 << digitalPinMap[pin].bit); } } else { badPinNumber(); } } #endif // Sd2PinMap_h ================================================ FILE: Sprinter/SdFat.h ================================================ /* Arduino SdFat Library * Copyright (C) 2009 by William Greiman * * This file is part of the Arduino SdFat Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with the Arduino SdFat Library. If not, see * . */ #ifndef SdFat_h #define SdFat_h /** * \file * SdFile and SdVolume classes */ #include #include "Sd2Card.h" #include "FatStructs.h" #include "Print.h" //------------------------------------------------------------------------------ /** * Allow use of deprecated functions if non-zero */ #define ALLOW_DEPRECATED_FUNCTIONS 1 //------------------------------------------------------------------------------ // forward declaration since SdVolume is used in SdFile class SdVolume; //============================================================================== // SdFile class // flags for ls() /** ls() flag to print modify date */ uint8_t const LS_DATE = 1; /** ls() flag to print file size */ uint8_t const LS_SIZE = 2; /** ls() flag for recursive list of subdirectories */ uint8_t const LS_R = 4; // use the gnu style oflag in open() /** open() oflag for reading */ uint8_t const O_READ = 0X01; /** open() oflag - same as O_READ */ uint8_t const O_RDONLY = O_READ; /** open() oflag for write */ uint8_t const O_WRITE = 0X02; /** open() oflag - same as O_WRITE */ uint8_t const O_WRONLY = O_WRITE; /** open() oflag for reading and writing */ uint8_t const O_RDWR = (O_READ | O_WRITE); /** open() oflag mask for access modes */ uint8_t const O_ACCMODE = (O_READ | O_WRITE); /** The file offset shall be set to the end of the file prior to each write. */ uint8_t const O_APPEND = 0X04; /** synchronous writes - call sync() after each write */ uint8_t const O_SYNC = 0X08; /** create the file if nonexistent */ uint8_t const O_CREAT = 0X10; /** If O_CREAT and O_EXCL are set, open() shall fail if the file exists */ uint8_t const O_EXCL = 0X20; /** truncate the file to zero length */ uint8_t const O_TRUNC = 0X40; // flags for timestamp /** set the file's last access date */ uint8_t const T_ACCESS = 1; /** set the file's creation date and time */ uint8_t const T_CREATE = 2; /** Set the file's write date and time */ uint8_t const T_WRITE = 4; // values for type_ /** This SdFile has not been opened. */ uint8_t const FAT_FILE_TYPE_CLOSED = 0; /** SdFile for a file */ uint8_t const FAT_FILE_TYPE_NORMAL = 1; /** SdFile for a FAT16 root directory */ uint8_t const FAT_FILE_TYPE_ROOT16 = 2; /** SdFile for a FAT32 root directory */ uint8_t const FAT_FILE_TYPE_ROOT32 = 3; /** SdFile for a subdirectory */ uint8_t const FAT_FILE_TYPE_SUBDIR = 4; /** Test value for directory type */ uint8_t const FAT_FILE_TYPE_MIN_DIR = FAT_FILE_TYPE_ROOT16; /** date field for FAT directory entry */ static inline uint16_t FAT_DATE(uint16_t year, uint8_t month, uint8_t day) { return (year - 1980) << 9 | month << 5 | day; } /** year part of FAT directory date field */ static inline uint16_t FAT_YEAR(uint16_t fatDate) { return 1980 + (fatDate >> 9); } /** month part of FAT directory date field */ static inline uint8_t FAT_MONTH(uint16_t fatDate) { return (fatDate >> 5) & 0XF; } /** day part of FAT directory date field */ static inline uint8_t FAT_DAY(uint16_t fatDate) { return fatDate & 0X1F; } /** time field for FAT directory entry */ static inline uint16_t FAT_TIME(uint8_t hour, uint8_t minute, uint8_t second) { return hour << 11 | minute << 5 | second >> 1; } /** hour part of FAT directory time field */ static inline uint8_t FAT_HOUR(uint16_t fatTime) { return fatTime >> 11; } /** minute part of FAT directory time field */ static inline uint8_t FAT_MINUTE(uint16_t fatTime) { return(fatTime >> 5) & 0X3F; } /** second part of FAT directory time field */ static inline uint8_t FAT_SECOND(uint16_t fatTime) { return 2*(fatTime & 0X1F); } /** Default date for file timestamps is 1 Jan 2000 */ uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1; /** Default time for file timestamp is 1 am */ uint16_t const FAT_DEFAULT_TIME = (1 << 11); //------------------------------------------------------------------------------ /** * \class SdFile * \brief Access FAT16 and FAT32 files on SD and SDHC cards. */ class SdFile : public Print { public: /** Create an instance of SdFile. */ SdFile(void) : type_(FAT_FILE_TYPE_CLOSED) {} /** * writeError is set to true if an error occurs during a write(). * Set writeError to false before calling print() and/or write() and check * for true after calls to print() and/or write(). */ bool writeError; /** * Cancel unbuffered reads for this file. * See setUnbufferedRead() */ void clearUnbufferedRead(void) { flags_ &= ~F_FILE_UNBUFFERED_READ; } uint8_t close(void); uint8_t contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock); uint8_t createContiguous(SdFile* dirFile, const char* fileName, uint32_t size); /** \return The current cluster number for a file or directory. */ uint32_t curCluster(void) const {return curCluster_;} /** \return The current position for a file or directory. */ uint32_t curPosition(void) const {return curPosition_;} /** * Set the date/time callback function * * \param[in] dateTime The user's call back function. The callback * function is of the form: * * \code * void dateTime(uint16_t* date, uint16_t* time) { * uint16_t year; * uint8_t month, day, hour, minute, second; * * // User gets date and time from GPS or real-time clock here * * // return date using FAT_DATE macro to format fields * *date = FAT_DATE(year, month, day); * * // return time using FAT_TIME macro to format fields * *time = FAT_TIME(hour, minute, second); * } * \endcode * * Sets the function that is called when a file is created or when * a file's directory entry is modified by sync(). All timestamps, * access, creation, and modify, are set when a file is created. * sync() maintains the last access date and last modify date/time. * * See the timestamp() function. */ static void dateTimeCallback( void (*dateTime)(uint16_t* date, uint16_t* time)) { dateTime_ = dateTime; } /** * Cancel the date/time callback function. */ static void dateTimeCallbackCancel(void) { // use explicit zero since NULL is not defined for Sanguino dateTime_ = 0; } /** \return Address of the block that contains this file's directory. */ uint32_t dirBlock(void) const {return dirBlock_;} uint8_t dirEntry(dir_t* dir); /** \return Index of this file's directory in the block dirBlock. */ uint8_t dirIndex(void) const {return dirIndex_;} static void dirName(const dir_t& dir, char* name); /** \return The total number of bytes in a file or directory. */ uint32_t fileSize(void) const {return fileSize_;} /** \return The first cluster number for a file or directory. */ uint32_t firstCluster(void) const {return firstCluster_;} /** \return True if this is a SdFile for a directory else false. */ uint8_t isDir(void) const {return type_ >= FAT_FILE_TYPE_MIN_DIR;} /** \return True if this is a SdFile for a file else false. */ uint8_t isFile(void) const {return type_ == FAT_FILE_TYPE_NORMAL;} /** \return True if this is a SdFile for an open file/directory else false. */ uint8_t isOpen(void) const {return type_ != FAT_FILE_TYPE_CLOSED;} /** \return True if this is a SdFile for a subdirectory else false. */ uint8_t isSubDir(void) const {return type_ == FAT_FILE_TYPE_SUBDIR;} /** \return True if this is a SdFile for the root directory. */ uint8_t isRoot(void) const { return type_ == FAT_FILE_TYPE_ROOT16 || type_ == FAT_FILE_TYPE_ROOT32; } void ls(uint8_t flags = 0, uint8_t indent = 0); uint8_t makeDir(SdFile* dir, const char* dirName); uint8_t open(SdFile* dirFile, uint16_t index, uint8_t oflag); uint8_t open(SdFile* dirFile, const char* fileName, uint8_t oflag); uint8_t openRoot(SdVolume* vol); static void printDirName(const dir_t& dir, uint8_t width); static void printFatDate(uint16_t fatDate); static void printFatTime(uint16_t fatTime); static void printTwoDigits(uint8_t v); /** * Read the next byte from a file. * * \return For success read returns the next byte in the file as an int. * If an error occurs or end of file is reached -1 is returned. */ int16_t read(void) { uint8_t b; return read(&b, 1) == 1 ? b : -1; } int16_t read(void* buf, uint16_t nbyte); int8_t readDir(dir_t* dir); static uint8_t remove(SdFile* dirFile, const char* fileName); uint8_t remove(void); /** Set the file's current position to zero. */ void rewind(void) { curPosition_ = curCluster_ = 0; } uint8_t rmDir(void); uint8_t rmRfStar(void); /** Set the files position to current position + \a pos. See seekSet(). */ uint8_t seekCur(uint32_t pos) { return seekSet(curPosition_ + pos); } /** * Set the files current position to end of file. Useful to position * a file for append. See seekSet(). */ uint8_t seekEnd(void) {return seekSet(fileSize_);} uint8_t seekSet(uint32_t pos); /** * Use unbuffered reads to access this file. Used with Wave * Shield ISR. Used with Sd2Card::partialBlockRead() in WaveRP. * * Not recommended for normal applications. */ void setUnbufferedRead(void) { if (isFile()) flags_ |= F_FILE_UNBUFFERED_READ; } uint8_t timestamp(uint8_t flag, uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t minute, uint8_t second); uint8_t sync(void); /** Type of this SdFile. You should use isFile() or isDir() instead of type() * if possible. * * \return The file or directory type. */ uint8_t type(void) const {return type_;} uint8_t truncate(uint32_t size); /** \return Unbuffered read flag. */ uint8_t unbufferedRead(void) const { return flags_ & F_FILE_UNBUFFERED_READ; } /** \return SdVolume that contains this file. */ SdVolume* volume(void) const {return vol_;} #if ARDUINO >= 100 size_t write(uint8_t b); #else void write(uint8_t b); #endif int16_t write(const void* buf, uint16_t nbyte); void write(const char* str); void write_P(PGM_P str); void writeln_P(PGM_P str); //------------------------------------------------------------------------------ #if ALLOW_DEPRECATED_FUNCTIONS // Deprecated functions - suppress cpplint warnings with NOLINT comment /** \deprecated Use: * uint8_t SdFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock); */ uint8_t contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) { // NOLINT return contiguousRange(&bgnBlock, &endBlock); } /** \deprecated Use: * uint8_t SdFile::createContiguous(SdFile* dirFile, * const char* fileName, uint32_t size) */ uint8_t createContiguous(SdFile& dirFile, // NOLINT const char* fileName, uint32_t size) { return createContiguous(&dirFile, fileName, size); } /** * \deprecated Use: * static void SdFile::dateTimeCallback( * void (*dateTime)(uint16_t* date, uint16_t* time)); */ static void dateTimeCallback( void (*dateTime)(uint16_t& date, uint16_t& time)) { // NOLINT oldDateTime_ = dateTime; dateTime_ = dateTime ? oldToNew : 0; } /** \deprecated Use: uint8_t SdFile::dirEntry(dir_t* dir); */ uint8_t dirEntry(dir_t& dir) {return dirEntry(&dir);} // NOLINT /** \deprecated Use: * uint8_t SdFile::makeDir(SdFile* dir, const char* dirName); */ uint8_t makeDir(SdFile& dir, const char* dirName) { // NOLINT return makeDir(&dir, dirName); } /** \deprecated Use: * uint8_t SdFile::open(SdFile* dirFile, const char* fileName, uint8_t oflag); */ uint8_t open(SdFile& dirFile, // NOLINT const char* fileName, uint8_t oflag) { return open(&dirFile, fileName, oflag); } /** \deprecated Do not use in new apps */ uint8_t open(SdFile& dirFile, const char* fileName) { // NOLINT return open(dirFile, fileName, O_RDWR); } /** \deprecated Use: * uint8_t SdFile::open(SdFile* dirFile, uint16_t index, uint8_t oflag); */ uint8_t open(SdFile& dirFile, uint16_t index, uint8_t oflag) { // NOLINT return open(&dirFile, index, oflag); } /** \deprecated Use: uint8_t SdFile::openRoot(SdVolume* vol); */ uint8_t openRoot(SdVolume& vol) {return openRoot(&vol);} // NOLINT /** \deprecated Use: int8_t SdFile::readDir(dir_t* dir); */ int8_t readDir(dir_t& dir) {return readDir(&dir);} // NOLINT /** \deprecated Use: * static uint8_t SdFile::remove(SdFile* dirFile, const char* fileName); */ static uint8_t remove(SdFile& dirFile, const char* fileName) { // NOLINT return remove(&dirFile, fileName); } //------------------------------------------------------------------------------ // rest are private private: static void (*oldDateTime_)(uint16_t& date, uint16_t& time); // NOLINT static void oldToNew(uint16_t* date, uint16_t* time) { uint16_t d; uint16_t t; oldDateTime_(d, t); *date = d; *time = t; } #endif // ALLOW_DEPRECATED_FUNCTIONS private: // bits defined in flags_ // should be 0XF static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC); // available bits static uint8_t const F_UNUSED = 0X30; // use unbuffered SD read static uint8_t const F_FILE_UNBUFFERED_READ = 0X40; // sync of directory entry required static uint8_t const F_FILE_DIR_DIRTY = 0X80; // make sure F_OFLAG is ok #if ((F_UNUSED | F_FILE_UNBUFFERED_READ | F_FILE_DIR_DIRTY) & F_OFLAG) #error flags_ bits conflict #endif // flags_ bits // private data uint8_t flags_; // See above for definition of flags_ bits uint8_t type_; // type of file see above for values uint32_t curCluster_; // cluster for current file position uint32_t curPosition_; // current file position in bytes from beginning uint32_t dirBlock_; // SD block that contains directory entry for file uint8_t dirIndex_; // index of entry in dirBlock 0 <= dirIndex_ <= 0XF uint32_t fileSize_; // file size in bytes uint32_t firstCluster_; // first cluster of file SdVolume* vol_; // volume where file is located // private functions uint8_t addCluster(void); uint8_t addDirCluster(void); dir_t* cacheDirEntry(uint8_t action); static void (*dateTime_)(uint16_t* date, uint16_t* time); static uint8_t make83Name(const char* str, uint8_t* name); uint8_t openCachedEntry(uint8_t cacheIndex, uint8_t oflags); dir_t* readDirCache(void); }; //============================================================================== // SdVolume class /** * \brief Cache for an SD data block */ union cache_t { /** Used to access cached file data blocks. */ uint8_t data[512]; /** Used to access cached FAT16 entries. */ uint16_t fat16[256]; /** Used to access cached FAT32 entries. */ uint32_t fat32[128]; /** Used to access cached directory entries. */ dir_t dir[16]; /** Used to access a cached MasterBoot Record. */ mbr_t mbr; /** Used to access to a cached FAT boot sector. */ fbs_t fbs; }; //------------------------------------------------------------------------------ /** * \class SdVolume * \brief Access FAT16 and FAT32 volumes on SD and SDHC cards. */ class SdVolume { public: /** Create an instance of SdVolume */ SdVolume(void) :allocSearchStart_(2), fatType_(0) {} /** Clear the cache and returns a pointer to the cache. Used by the WaveRP * recorder to do raw write to the SD card. Not for normal apps. */ static uint8_t* cacheClear(void) { cacheFlush(); cacheBlockNumber_ = 0XFFFFFFFF; return cacheBuffer_.data; } /** * Initialize a FAT volume. Try partition one first then try super * floppy format. * * \param[in] dev The Sd2Card where the volume is located. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. Reasons for * failure include not finding a valid partition, not finding a valid * FAT file system or an I/O error. */ uint8_t init(Sd2Card* dev) { return init(dev, 1) ? true : init(dev, 0);} uint8_t init(Sd2Card* dev, uint8_t part); // inline functions that return volume info /** \return The volume's cluster size in blocks. */ uint8_t blocksPerCluster(void) const {return blocksPerCluster_;} /** \return The number of blocks in one FAT. */ uint32_t blocksPerFat(void) const {return blocksPerFat_;} /** \return The total number of clusters in the volume. */ uint32_t clusterCount(void) const {return clusterCount_;} /** \return The shift count required to multiply by blocksPerCluster. */ uint8_t clusterSizeShift(void) const {return clusterSizeShift_;} /** \return The logical block number for the start of file data. */ uint32_t dataStartBlock(void) const {return dataStartBlock_;} /** \return The number of FAT structures on the volume. */ uint8_t fatCount(void) const {return fatCount_;} /** \return The logical block number for the start of the first FAT. */ uint32_t fatStartBlock(void) const {return fatStartBlock_;} /** \return The FAT type of the volume. Values are 12, 16 or 32. */ uint8_t fatType(void) const {return fatType_;} /** \return The number of entries in the root directory for FAT16 volumes. */ uint32_t rootDirEntryCount(void) const {return rootDirEntryCount_;} /** \return The logical block number for the start of the root directory on FAT16 volumes or the first cluster number on FAT32 volumes. */ uint32_t rootDirStart(void) const {return rootDirStart_;} /** return a pointer to the Sd2Card object for this volume */ static Sd2Card* sdCard(void) {return sdCard_;} //------------------------------------------------------------------------------ #if ALLOW_DEPRECATED_FUNCTIONS // Deprecated functions - suppress cpplint warnings with NOLINT comment /** \deprecated Use: uint8_t SdVolume::init(Sd2Card* dev); */ uint8_t init(Sd2Card& dev) {return init(&dev);} // NOLINT /** \deprecated Use: uint8_t SdVolume::init(Sd2Card* dev, uint8_t vol); */ uint8_t init(Sd2Card& dev, uint8_t part) { // NOLINT return init(&dev, part); } #endif // ALLOW_DEPRECATED_FUNCTIONS //------------------------------------------------------------------------------ private: // Allow SdFile access to SdVolume private data. friend class SdFile; // value for action argument in cacheRawBlock to indicate read from cache static uint8_t const CACHE_FOR_READ = 0; // value for action argument in cacheRawBlock to indicate cache dirty static uint8_t const CACHE_FOR_WRITE = 1; static cache_t cacheBuffer_; // 512 byte cache for device blocks static uint32_t cacheBlockNumber_; // Logical number of block in the cache static Sd2Card* sdCard_; // Sd2Card object for cache static uint8_t cacheDirty_; // cacheFlush() will write block if true static uint32_t cacheMirrorBlock_; // block number for mirror FAT // uint32_t allocSearchStart_; // start cluster for alloc search uint8_t blocksPerCluster_; // cluster size in blocks uint32_t blocksPerFat_; // FAT size in blocks uint32_t clusterCount_; // clusters in one FAT uint8_t clusterSizeShift_; // shift to convert cluster count to block count uint32_t dataStartBlock_; // first data block number uint8_t fatCount_; // number of FATs on volume uint32_t fatStartBlock_; // start block for first FAT uint8_t fatType_; // volume type (12, 16, OR 32) uint16_t rootDirEntryCount_; // number of entries in FAT16 root dir uint32_t rootDirStart_; // root start block for FAT16, cluster for FAT32 //---------------------------------------------------------------------------- uint8_t allocContiguous(uint32_t count, uint32_t* curCluster); uint8_t blockOfCluster(uint32_t position) const { return (position >> 9) & (blocksPerCluster_ - 1);} uint32_t clusterStartBlock(uint32_t cluster) const { return dataStartBlock_ + ((cluster - 2) << clusterSizeShift_);} uint32_t blockNumber(uint32_t cluster, uint32_t position) const { return clusterStartBlock(cluster) + blockOfCluster(position);} static uint8_t cacheFlush(void); static uint8_t cacheRawBlock(uint32_t blockNumber, uint8_t action); static void cacheSetDirty(void) {cacheDirty_ |= CACHE_FOR_WRITE;} static uint8_t cacheZeroBlock(uint32_t blockNumber); uint8_t chainSize(uint32_t beginCluster, uint32_t* size) const; uint8_t fatGet(uint32_t cluster, uint32_t* value) const; uint8_t fatPut(uint32_t cluster, uint32_t value); uint8_t fatPutEOC(uint32_t cluster) { return fatPut(cluster, 0x0FFFFFFF); } uint8_t freeChain(uint32_t cluster); uint8_t isEOC(uint32_t cluster) const { return cluster >= (fatType_ == 16 ? FAT16EOC_MIN : FAT32EOC_MIN); } uint8_t readBlock(uint32_t block, uint8_t* dst) { return sdCard_->readBlock(block, dst);} uint8_t readData(uint32_t block, uint16_t offset, uint16_t count, uint8_t* dst) { return sdCard_->readData(block, offset, count, dst); } uint8_t writeBlock(uint32_t block, const uint8_t* dst) { return sdCard_->writeBlock(block, dst); } }; #endif // SdFat_h ================================================ FILE: Sprinter/SdFatUtil.h ================================================ /* Arduino SdFat Library * Copyright (C) 2008 by William Greiman * * This file is part of the Arduino SdFat Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * You should have received a copy of the GNU General Public License * along with the Arduino SdFat Library. If not, see * . */ #ifndef SdFatUtil_h #define SdFatUtil_h /** * \file * Useful utility functions. */ #if defined(ARDUINO) && ARDUINO >= 100 #include #else #include #endif #include /** Store and print a string in flash memory.*/ #define PgmPrint(x) SerialPrint_P(PSTR(x)) /** Store and print a string in flash memory followed by a CR/LF.*/ #define PgmPrintln(x) SerialPrintln_P(PSTR(x)) /** Defined so doxygen works for function definitions. */ #define NOINLINE __attribute__((noinline)) //------------------------------------------------------------------------------ /** Return the number of bytes currently free in RAM. */ static int FreeRam(void) { extern int __bss_end; extern int* __brkval; int free_memory; if (reinterpret_cast(__brkval) == 0) { // if no heap use from end of bss section free_memory = reinterpret_cast(&free_memory) - reinterpret_cast(&__bss_end); } else { // use from top of stack to heap free_memory = reinterpret_cast(&free_memory) - reinterpret_cast(__brkval); } return free_memory; } //------------------------------------------------------------------------------ /** * %Print a string in flash memory to the serial port. * * \param[in] str Pointer to string stored in flash memory. */ static NOINLINE void SerialPrint_P(PGM_P str) { for (uint8_t c; (c = pgm_read_byte(str)); str++) Serial.print(char(c)); } //------------------------------------------------------------------------------ /** * %Print a string in flash memory followed by a CR/LF. * * \param[in] str Pointer to string stored in flash memory. */ static NOINLINE void SerialPrintln_P(PGM_P str) { SerialPrint_P(str); Serial.println(); } #endif // #define SdFatUtil_h ================================================ FILE: Sprinter/SdFatmainpage.h ================================================ /* Arduino SdFat Library * Copyright (C) 2009 by William Greiman * * This file is part of the Arduino SdFat Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with the Arduino SdFat Library. If not, see * . */ /** \mainpage Arduino SdFat Library
Copyright © 2009 by William Greiman
\section Intro Introduction The Arduino SdFat Library is a minimal implementation of FAT16 and FAT32 file systems on SD flash memory cards. Standard SD and high capacity SDHC cards are supported. The SdFat only supports short 8.3 names. The main classes in SdFat are Sd2Card, SdVolume, and SdFile. The Sd2Card class supports access to standard SD cards and SDHC cards. Most applications will only need to call the Sd2Card::init() member function. The SdVolume class supports FAT16 and FAT32 partitions. Most applications will only need to call the SdVolume::init() member function. The SdFile class provides file access functions such as open(), read(), remove(), write(), close() and sync(). This class supports access to the root directory and subdirectories. A number of example are provided in the SdFat/examples folder. These were developed to test SdFat and illustrate its use. SdFat was developed for high speed data recording. SdFat was used to implement an audio record/play class, WaveRP, for the Adafruit Wave Shield. This application uses special Sd2Card calls to write to contiguous files in raw mode. These functions reduce write latency so that audio can be recorded with the small amount of RAM in the Arduino. \section SDcard SD\SDHC Cards Arduinos access SD cards using the cards SPI protocol. PCs, Macs, and most consumer devices use the 4-bit parallel SD protocol. A card that functions well on A PC or Mac may not work well on the Arduino. Most cards have good SPI read performance but cards vary widely in SPI write performance. Write performance is limited by how efficiently the card manages internal erase/remapping operations. The Arduino cannot optimize writes to reduce erase operations because of its limit RAM. SanDisk cards generally have good write performance. They seem to have more internal RAM buffering than other cards and therefore can limit the number of flash erase operations that the Arduino forces due to its limited RAM. \section Hardware Hardware Configuration SdFat was developed using an Adafruit Industries Wave Shield. The hardware interface to the SD card should not use a resistor based level shifter. SdFat sets the SPI bus frequency to 8 MHz which results in signal rise times that are too slow for the edge detectors in many newer SD card controllers when resistor voltage dividers are used. The 5 to 3.3 V level shifter for 5 V Arduinos should be IC based like the 74HC4050N based circuit shown in the file SdLevel.png. The Adafruit Wave Shield uses a 74AHC125N. Gravitech sells SD and MicroSD Card Adapters based on the 74LCX245. If you are using a resistor based level shifter and are having problems try setting the SPI bus frequency to 4 MHz. This can be done by using card.init(SPI_HALF_SPEED) to initialize the SD card. \section comment Bugs and Comments If you wish to report bugs or have comments, send email to fat16lib@sbcglobal.net. \section SdFatClass SdFat Usage SdFat uses a slightly restricted form of short names. Only printable ASCII characters are supported. No characters with code point values greater than 127 are allowed. Space is not allowed even though space was allowed in the API of early versions of DOS. Short names are limited to 8 characters followed by an optional period (.) and extension of up to 3 characters. The characters may be any combination of letters and digits. The following special characters are also allowed: $ % ' - _ @ ~ ` ! ( ) { } ^ # & Short names are always converted to upper case and their original case value is lost. \note The Arduino Print class uses character at a time writes so it was necessary to use a \link SdFile::sync() sync() \endlink function to control when data is written to the SD card. \par An application which writes to a file using \link Print::print() print()\endlink, \link Print::println() println() \endlink or \link SdFile::write write() \endlink must call \link SdFile::sync() sync() \endlink at the appropriate time to force data and directory information to be written to the SD Card. Data and directory information are also written to the SD card when \link SdFile::close() close() \endlink is called. \par Applications must use care calling \link SdFile::sync() sync() \endlink since 2048 bytes of I/O is required to update file and directory information. This includes writing the current data block, reading the block that contains the directory entry for update, writing the directory block back and reading back the current data block. It is possible to open a file with two or more instances of SdFile. A file may be corrupted if data is written to the file by more than one instance of SdFile. \section HowTo How to format SD Cards as FAT Volumes You should use a freshly formatted SD card for best performance. FAT file systems become slower if many files have been created and deleted. This is because the directory entry for a deleted file is marked as deleted, but is not deleted. When a new file is created, these entries must be scanned before creating the file, a flaw in the FAT design. Also files can become fragmented which causes reads and writes to be slower. Microsoft operating systems support removable media formatted with a Master Boot Record, MBR, or formatted as a super floppy with a FAT Boot Sector in block zero. Microsoft operating systems expect MBR formatted removable media to have only one partition. The first partition should be used. Microsoft operating systems do not support partitioning SD flash cards. If you erase an SD card with a program like KillDisk, Most versions of Windows will format the card as a super floppy. The best way to restore an SD card's format is to use SDFormatter which can be downloaded from: http://www.sdcard.org/consumers/formatter/ SDFormatter aligns flash erase boundaries with file system structures which reduces write latency and file system overhead. SDFormatter does not have an option for FAT type so it may format small cards as FAT12. After the MBR is restored by SDFormatter you may need to reformat small cards that have been formatted FAT12 to force the volume type to be FAT16. If you reformat the SD card with an OS utility, choose a cluster size that will result in: 4084 < CountOfClusters && CountOfClusters < 65525 The volume will then be FAT16. If you are formatting an SD card on OS X or Linux, be sure to use the first partition. Format this partition with a cluster count in above range. \section References References Adafruit Industries: http://www.adafruit.com/ http://www.ladyada.net/make/waveshield/ The Arduino site: http://www.arduino.cc/ For more information about FAT file systems see: http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx For information about using SD cards as SPI devices see: http://www.sdcard.org/developers/tech/sdcard/pls/Simplified_Physical_Layer_Spec.pdf The ATmega328 datasheet: http://www.atmel.com/dyn/resources/prod_documents/doc8161.pdf */ ================================================ FILE: Sprinter/SdFile.cpp ================================================ /* Arduino SdFat Library * Copyright (C) 2009 by William Greiman * * This file is part of the Arduino SdFat Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with the Arduino SdFat Library. If not, see * . */ #include "SdFat.h" #include #if defined(ARDUINO) && ARDUINO >= 100 #include #else #include #endif //------------------------------------------------------------------------------ // callback function for date/time void (*SdFile::dateTime_)(uint16_t* date, uint16_t* time) = NULL; #if ALLOW_DEPRECATED_FUNCTIONS // suppress cpplint warnings with NOLINT comment void (*SdFile::oldDateTime_)(uint16_t& date, uint16_t& time) = NULL; // NOLINT #endif // ALLOW_DEPRECATED_FUNCTIONS //------------------------------------------------------------------------------ // add a cluster to a file uint8_t SdFile::addCluster() { if (!vol_->allocContiguous(1, &curCluster_)) return false; // if first cluster of file link to directory entry if (firstCluster_ == 0) { firstCluster_ = curCluster_; flags_ |= F_FILE_DIR_DIRTY; } return true; } //------------------------------------------------------------------------------ // Add a cluster to a directory file and zero the cluster. // return with first block of cluster in the cache uint8_t SdFile::addDirCluster(void) { if (!addCluster()) return false; // zero data in cluster insure first cluster is in cache uint32_t block = vol_->clusterStartBlock(curCluster_); for (uint8_t i = vol_->blocksPerCluster_; i != 0; i--) { if (!SdVolume::cacheZeroBlock(block + i - 1)) return false; } // Increase directory file size by cluster size fileSize_ += 512UL << vol_->clusterSizeShift_; return true; } //------------------------------------------------------------------------------ // cache a file's directory entry // return pointer to cached entry or null for failure dir_t* SdFile::cacheDirEntry(uint8_t action) { if (!SdVolume::cacheRawBlock(dirBlock_, action)) return NULL; return SdVolume::cacheBuffer_.dir + dirIndex_; } //------------------------------------------------------------------------------ /** * Close a file and force cached data and directory information * to be written to the storage device. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include no file is open or an I/O error. */ uint8_t SdFile::close(void) { if (!sync())return false; type_ = FAT_FILE_TYPE_CLOSED; return true; } //------------------------------------------------------------------------------ /** * Check for contiguous file and return its raw block range. * * \param[out] bgnBlock the first block address for the file. * \param[out] endBlock the last block address for the file. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include file is not contiguous, file has zero length * or an I/O error occurred. */ uint8_t SdFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock) { // error if no blocks if (firstCluster_ == 0) return false; for (uint32_t c = firstCluster_; ; c++) { uint32_t next; if (!vol_->fatGet(c, &next)) return false; // check for contiguous if (next != (c + 1)) { // error if not end of chain if (!vol_->isEOC(next)) return false; *bgnBlock = vol_->clusterStartBlock(firstCluster_); *endBlock = vol_->clusterStartBlock(c) + vol_->blocksPerCluster_ - 1; return true; } } } //------------------------------------------------------------------------------ /** * Create and open a new contiguous file of a specified size. * * \note This function only supports short DOS 8.3 names. * See open() for more information. * * \param[in] dirFile The directory where the file will be created. * \param[in] fileName A valid DOS 8.3 file name. * \param[in] size The desired file size. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include \a fileName contains * an invalid DOS 8.3 file name, the FAT volume has not been initialized, * a file is already open, the file already exists, the root * directory is full or an I/O error. * */ uint8_t SdFile::createContiguous(SdFile* dirFile, const char* fileName, uint32_t size) { // don't allow zero length file if (size == 0) return false; if (!open(dirFile, fileName, O_CREAT | O_EXCL | O_RDWR)) return false; // calculate number of clusters needed uint32_t count = ((size - 1) >> (vol_->clusterSizeShift_ + 9)) + 1; // allocate clusters if (!vol_->allocContiguous(count, &firstCluster_)) { remove(); return false; } fileSize_ = size; // insure sync() will update dir entry flags_ |= F_FILE_DIR_DIRTY; return sync(); } //------------------------------------------------------------------------------ /** * Return a files directory entry * * \param[out] dir Location for return of the files directory entry. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t SdFile::dirEntry(dir_t* dir) { // make sure fields on SD are correct if (!sync()) return false; // read entry dir_t* p = cacheDirEntry(SdVolume::CACHE_FOR_READ); if (!p) return false; // copy to caller's struct memcpy(dir, p, sizeof(dir_t)); return true; } //------------------------------------------------------------------------------ /** * Format the name field of \a dir into the 13 byte array * \a name in standard 8.3 short name format. * * \param[in] dir The directory structure containing the name. * \param[out] name A 13 byte char array for the formatted name. */ void SdFile::dirName(const dir_t& dir, char* name) { uint8_t j = 0; for (uint8_t i = 0; i < 11; i++) { if (dir.name[i] == ' ')continue; if (i == 8) name[j++] = '.'; name[j++] = dir.name[i]; } name[j] = 0; } //------------------------------------------------------------------------------ /** List directory contents to Serial. * * \param[in] flags The inclusive OR of * * LS_DATE - %Print file modification date * * LS_SIZE - %Print file size. * * LS_R - Recursive list of subdirectories. * * \param[in] indent Amount of space before file name. Used for recursive * list to indicate subdirectory level. */ void SdFile::ls(uint8_t flags, uint8_t indent) { dir_t* p; rewind(); while ((p = readDirCache())) { // done if past last used entry if (p->name[0] == DIR_NAME_FREE) break; // skip deleted entry and entries for . and .. if (p->name[0] == DIR_NAME_DELETED || p->name[0] == '.') continue; // only list subdirectories and files if (!DIR_IS_FILE_OR_SUBDIR(p)) continue; // print any indent spaces for (int8_t i = 0; i < indent; i++) Serial.print(char(' ')); // print file name with possible blank fill printDirName(*p, flags & (LS_DATE | LS_SIZE) ? 14 : 0); // print modify date/time if requested if (flags & LS_DATE) { printFatDate(p->lastWriteDate); Serial.print(char(' ')); printFatTime(p->lastWriteTime); } // print size if requested if (!DIR_IS_SUBDIR(p) && (flags & LS_SIZE)) { Serial.print(char(' ')); Serial.print(p->fileSize); } Serial.println(); // list subdirectory content if requested if ((flags & LS_R) && DIR_IS_SUBDIR(p)) { uint16_t index = curPosition()/32 - 1; SdFile s; if (s.open(this, index, O_READ)) s.ls(flags, indent + 2); seekSet(32 * (index + 1)); } } } //------------------------------------------------------------------------------ // format directory name field from a 8.3 name string uint8_t SdFile::make83Name(const char* str, uint8_t* name) { uint8_t c; uint8_t n = 7; // max index for part before dot uint8_t i = 0; // blank fill name and extension while (i < 11) name[i++] = ' '; i = 0; while ((c = *str++) != '\0') { if (c == '.') { if (n == 10) return false; // only one dot allowed n = 10; // max index for full 8.3 name i = 8; // place for extension } else { // illegal FAT characters PGM_P p = PSTR("|<>^+=?/[];,*\"\\"); uint8_t b; while ((b = pgm_read_byte(p++))) if (b == c) return false; // check size and only allow ASCII printable characters if (i > n || c < 0X21 || c > 0X7E)return false; // only upper case allowed in 8.3 names - convert lower to upper name[i++] = c < 'a' || c > 'z' ? c : c + ('A' - 'a'); } } // must have a file name, extension is optional return name[0] != ' '; } //------------------------------------------------------------------------------ /** Make a new directory. * * \param[in] dir An open SdFat instance for the directory that will containing * the new directory. * * \param[in] dirName A valid 8.3 DOS name for the new directory. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include this SdFile is already open, \a dir is not a * directory, \a dirName is invalid or already exists in \a dir. */ uint8_t SdFile::makeDir(SdFile* dir, const char* dirName) { dir_t d; // create a normal file if (!open(dir, dirName, O_CREAT | O_EXCL | O_RDWR)) return false; // convert SdFile to directory flags_ = O_READ; type_ = FAT_FILE_TYPE_SUBDIR; // allocate and zero first cluster if (!addDirCluster())return false; // force entry to SD if (!sync()) return false; // cache entry - should already be in cache due to sync() call dir_t* p = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!p) return false; // change directory entry attribute p->attributes = DIR_ATT_DIRECTORY; // make entry for '.' memcpy(&d, p, sizeof(d)); for (uint8_t i = 1; i < 11; i++) d.name[i] = ' '; d.name[0] = '.'; // cache block for '.' and '..' uint32_t block = vol_->clusterStartBlock(firstCluster_); if (!SdVolume::cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) return false; // copy '.' to block memcpy(&SdVolume::cacheBuffer_.dir[0], &d, sizeof(d)); // make entry for '..' d.name[1] = '.'; if (dir->isRoot()) { d.firstClusterLow = 0; d.firstClusterHigh = 0; } else { d.firstClusterLow = dir->firstCluster_ & 0XFFFF; d.firstClusterHigh = dir->firstCluster_ >> 16; } // copy '..' to block memcpy(&SdVolume::cacheBuffer_.dir[1], &d, sizeof(d)); // set position after '..' curPosition_ = 2 * sizeof(d); // write first block return SdVolume::cacheFlush(); } //------------------------------------------------------------------------------ /** * Open a file or directory by name. * * \param[in] dirFile An open SdFat instance for the directory containing the * file to be opened. * * \param[in] fileName A valid 8.3 DOS name for a file to be opened. * * \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive * OR of flags from the following list * * O_READ - Open for reading. * * O_RDONLY - Same as O_READ. * * O_WRITE - Open for writing. * * O_WRONLY - Same as O_WRITE. * * O_RDWR - Open for reading and writing. * * O_APPEND - If set, the file offset shall be set to the end of the * file prior to each write. * * O_CREAT - If the file exists, this flag has no effect except as noted * under O_EXCL below. Otherwise, the file shall be created * * O_EXCL - If O_CREAT and O_EXCL are set, open() shall fail if the file exists. * * O_SYNC - Call sync() after each write. This flag should not be used with * write(uint8_t), write_P(PGM_P), writeln_P(PGM_P), or the Arduino Print class. * These functions do character at a time writes so sync() will be called * after each byte. * * O_TRUNC - If the file exists and is a regular file, and the file is * successfully opened and is not read only, its length shall be truncated to 0. * * \note Directory files must be opened read only. Write and truncation is * not allowed for directory files. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include this SdFile is already open, \a difFile is not * a directory, \a fileName is invalid, the file does not exist * or can't be opened in the access mode specified by oflag. */ uint8_t SdFile::open(SdFile* dirFile, const char* fileName, uint8_t oflag) { uint8_t dname[11]; dir_t* p; // error if already open if (isOpen())return false; if (!make83Name(fileName, dname)) return false; vol_ = dirFile->vol_; dirFile->rewind(); // bool for empty entry found uint8_t emptyFound = false; // search for file while (dirFile->curPosition_ < dirFile->fileSize_) { uint8_t index = 0XF & (dirFile->curPosition_ >> 5); p = dirFile->readDirCache(); if (p == NULL) return false; if (p->name[0] == DIR_NAME_FREE || p->name[0] == DIR_NAME_DELETED) { // remember first empty slot if (!emptyFound) { emptyFound = true; dirIndex_ = index; dirBlock_ = SdVolume::cacheBlockNumber_; } // done if no entries follow if (p->name[0] == DIR_NAME_FREE) break; } else if (!memcmp(dname, p->name, 11)) { // don't open existing file if O_CREAT and O_EXCL if ((oflag & (O_CREAT | O_EXCL)) == (O_CREAT | O_EXCL)) return false; // open found file return openCachedEntry(0XF & index, oflag); } } // only create file if O_CREAT and O_WRITE if ((oflag & (O_CREAT | O_WRITE)) != (O_CREAT | O_WRITE)) return false; // cache found slot or add cluster if end of file if (emptyFound) { p = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!p) return false; } else { if (dirFile->type_ == FAT_FILE_TYPE_ROOT16) return false; // add and zero cluster for dirFile - first cluster is in cache for write if (!dirFile->addDirCluster()) return false; // use first entry in cluster dirIndex_ = 0; p = SdVolume::cacheBuffer_.dir; } // initialize as empty file memset(p, 0, sizeof(dir_t)); memcpy(p->name, dname, 11); // set timestamps if (dateTime_) { // call user function dateTime_(&p->creationDate, &p->creationTime); } else { // use default date/time p->creationDate = FAT_DEFAULT_DATE; p->creationTime = FAT_DEFAULT_TIME; } p->lastAccessDate = p->creationDate; p->lastWriteDate = p->creationDate; p->lastWriteTime = p->creationTime; // force write of entry to SD if (!SdVolume::cacheFlush()) return false; // open entry in cache return openCachedEntry(dirIndex_, oflag); } //------------------------------------------------------------------------------ /** * Open a file by index. * * \param[in] dirFile An open SdFat instance for the directory. * * \param[in] index The \a index of the directory entry for the file to be * opened. The value for \a index is (directory file position)/32. * * \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive * OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC. * * See open() by fileName for definition of flags and return values. * */ uint8_t SdFile::open(SdFile* dirFile, uint16_t index, uint8_t oflag) { // error if already open if (isOpen())return false; // don't open existing file if O_CREAT and O_EXCL - user call error if ((oflag & (O_CREAT | O_EXCL)) == (O_CREAT | O_EXCL)) return false; vol_ = dirFile->vol_; // seek to location of entry if (!dirFile->seekSet(32 * index)) return false; // read entry into cache dir_t* p = dirFile->readDirCache(); if (p == NULL) return false; // error if empty slot or '.' or '..' if (p->name[0] == DIR_NAME_FREE || p->name[0] == DIR_NAME_DELETED || p->name[0] == '.') { return false; } // open cached entry return openCachedEntry(index & 0XF, oflag); } //------------------------------------------------------------------------------ // open a cached directory entry. Assumes vol_ is initializes uint8_t SdFile::openCachedEntry(uint8_t dirIndex, uint8_t oflag) { // location of entry in cache dir_t* p = SdVolume::cacheBuffer_.dir + dirIndex; // write or truncate is an error for a directory or read-only file if (p->attributes & (DIR_ATT_READ_ONLY | DIR_ATT_DIRECTORY)) { if (oflag & (O_WRITE | O_TRUNC)) return false; } // remember location of directory entry on SD dirIndex_ = dirIndex; dirBlock_ = SdVolume::cacheBlockNumber_; // copy first cluster number for directory fields firstCluster_ = (uint32_t)p->firstClusterHigh << 16; firstCluster_ |= p->firstClusterLow; // make sure it is a normal file or subdirectory if (DIR_IS_FILE(p)) { fileSize_ = p->fileSize; type_ = FAT_FILE_TYPE_NORMAL; } else if (DIR_IS_SUBDIR(p)) { if (!vol_->chainSize(firstCluster_, &fileSize_)) return false; type_ = FAT_FILE_TYPE_SUBDIR; } else { return false; } // save open flags for read/write flags_ = oflag & (O_ACCMODE | O_SYNC | O_APPEND); // set to start of file curCluster_ = 0; curPosition_ = 0; // truncate file to zero length if requested if (oflag & O_TRUNC) return truncate(0); return true; } //------------------------------------------------------------------------------ /** * Open a volume's root directory. * * \param[in] vol The FAT volume containing the root directory to be opened. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include the FAT volume has not been initialized * or it a FAT12 volume. */ uint8_t SdFile::openRoot(SdVolume* vol) { // error if file is already open if (isOpen()) return false; if (vol->fatType() == 16) { type_ = FAT_FILE_TYPE_ROOT16; firstCluster_ = 0; fileSize_ = 32 * vol->rootDirEntryCount(); } else if (vol->fatType() == 32) { type_ = FAT_FILE_TYPE_ROOT32; firstCluster_ = vol->rootDirStart(); if (!vol->chainSize(firstCluster_, &fileSize_)) return false; } else { // volume is not initialized or FAT12 return false; } vol_ = vol; // read only flags_ = O_READ; // set to start of file curCluster_ = 0; curPosition_ = 0; // root has no directory entry dirBlock_ = 0; dirIndex_ = 0; return true; } //------------------------------------------------------------------------------ /** %Print the name field of a directory entry in 8.3 format to Serial. * * \param[in] dir The directory structure containing the name. * \param[in] width Blank fill name if length is less than \a width. */ void SdFile::printDirName(const dir_t& dir, uint8_t width) { uint8_t w = 0; for (uint8_t i = 0; i < 11; i++) { if (dir.name[i] == ' ')continue; if (i == 8) { Serial.print(char('.')); w++; } Serial.print(char(dir.name[i])); w++; } if (DIR_IS_SUBDIR(&dir)) { Serial.print(char('/')); w++; } while (w < width) { Serial.print(char(' ')); w++; } } //------------------------------------------------------------------------------ /** %Print a directory date field to Serial. * * Format is yyyy-mm-dd. * * \param[in] fatDate The date field from a directory entry. */ void SdFile::printFatDate(uint16_t fatDate) { Serial.print(FAT_YEAR(fatDate)); Serial.print(char('-')); printTwoDigits(FAT_MONTH(fatDate)); Serial.print(char('-')); printTwoDigits(FAT_DAY(fatDate)); } //------------------------------------------------------------------------------ /** %Print a directory time field to Serial. * * Format is hh:mm:ss. * * \param[in] fatTime The time field from a directory entry. */ void SdFile::printFatTime(uint16_t fatTime) { printTwoDigits(FAT_HOUR(fatTime)); Serial.print(char(':')); printTwoDigits(FAT_MINUTE(fatTime)); Serial.print(char(':')); printTwoDigits(FAT_SECOND(fatTime)); } //------------------------------------------------------------------------------ /** %Print a value as two digits to Serial. * * \param[in] v Value to be printed, 0 <= \a v <= 99 */ void SdFile::printTwoDigits(uint8_t v) { char str[3]; str[0] = '0' + v/10; str[1] = '0' + v % 10; str[2] = 0; Serial.print(str); } //------------------------------------------------------------------------------ /** * Read data from a file starting at the current position. * * \param[out] buf Pointer to the location that will receive the data. * * \param[in] nbyte Maximum number of bytes to read. * * \return For success read() returns the number of bytes read. * A value less than \a nbyte, including zero, will be returned * if end of file is reached. * If an error occurs, read() returns -1. Possible errors include * read() called before a file has been opened, corrupt file system * or an I/O error occurred. */ int16_t SdFile::read(void* buf, uint16_t nbyte) { uint8_t* dst = reinterpret_cast(buf); // error if not open or write only if (!isOpen() || !(flags_ & O_READ)) return -1; // max bytes left in file if (nbyte > (fileSize_ - curPosition_)) nbyte = fileSize_ - curPosition_; // amount left to read uint16_t toRead = nbyte; while (toRead > 0) { uint32_t block; // raw device block number uint16_t offset = curPosition_ & 0X1FF; // offset in block if (type_ == FAT_FILE_TYPE_ROOT16) { block = vol_->rootDirStart() + (curPosition_ >> 9); } else { uint8_t blockOfCluster = vol_->blockOfCluster(curPosition_); if (offset == 0 && blockOfCluster == 0) { // start of new cluster if (curPosition_ == 0) { // use first cluster in file curCluster_ = firstCluster_; } else { // get next cluster from FAT if (!vol_->fatGet(curCluster_, &curCluster_)) return -1; } } block = vol_->clusterStartBlock(curCluster_) + blockOfCluster; } uint16_t n = toRead; // amount to be read from current block if (n > (512 - offset)) n = 512 - offset; // no buffering needed if n == 512 or user requests no buffering if ((unbufferedRead() || n == 512) && block != SdVolume::cacheBlockNumber_) { if (!vol_->readData(block, offset, n, dst)) return -1; dst += n; } else { // read block to cache and copy data to caller if (!SdVolume::cacheRawBlock(block, SdVolume::CACHE_FOR_READ)) return -1; uint8_t* src = SdVolume::cacheBuffer_.data + offset; uint8_t* end = src + n; while (src != end) *dst++ = *src++; } curPosition_ += n; toRead -= n; } return nbyte; } //------------------------------------------------------------------------------ /** * Read the next directory entry from a directory file. * * \param[out] dir The dir_t struct that will receive the data. * * \return For success readDir() returns the number of bytes read. * A value of zero will be returned if end of file is reached. * If an error occurs, readDir() returns -1. Possible errors include * readDir() called before a directory has been opened, this is not * a directory file or an I/O error occurred. */ int8_t SdFile::readDir(dir_t* dir) { int8_t n; // if not a directory file or miss-positioned return an error if (!isDir() || (0X1F & curPosition_)) return -1; while ((n = read(dir, sizeof(dir_t))) == sizeof(dir_t)) { // last entry if DIR_NAME_FREE if (dir->name[0] == DIR_NAME_FREE) break; // skip empty entries and entry for . and .. if (dir->name[0] == DIR_NAME_DELETED || dir->name[0] == '.') continue; // return if normal file or subdirectory if (DIR_IS_FILE_OR_SUBDIR(dir)) return n; } // error, end of file, or past last entry return n < 0 ? -1 : 0; } //------------------------------------------------------------------------------ // Read next directory entry into the cache // Assumes file is correctly positioned dir_t* SdFile::readDirCache(void) { // error if not directory if (!isDir()) return NULL; // index of entry in cache uint8_t i = (curPosition_ >> 5) & 0XF; // use read to locate and cache block if (read() < 0) return NULL; // advance to next entry curPosition_ += 31; // return pointer to entry return (SdVolume::cacheBuffer_.dir + i); } //------------------------------------------------------------------------------ /** * Remove a file. * * The directory entry and all data for the file are deleted. * * \note This function should not be used to delete the 8.3 version of a * file that has a long name. For example if a file has the long name * "New Text Document.txt" you should not delete the 8.3 name "NEWTEX~1.TXT". * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include the file read-only, is a directory, * or an I/O error occurred. */ uint8_t SdFile::remove(void) { // free any clusters - will fail if read-only or directory if (!truncate(0)) return false; // cache directory entry dir_t* d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!d) return false; // mark entry deleted d->name[0] = DIR_NAME_DELETED; // set this SdFile closed type_ = FAT_FILE_TYPE_CLOSED; // write entry to SD return SdVolume::cacheFlush(); } //------------------------------------------------------------------------------ /** * Remove a file. * * The directory entry and all data for the file are deleted. * * \param[in] dirFile The directory that contains the file. * \param[in] fileName The name of the file to be removed. * * \note This function should not be used to delete the 8.3 version of a * file that has a long name. For example if a file has the long name * "New Text Document.txt" you should not delete the 8.3 name "NEWTEX~1.TXT". * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include the file is a directory, is read only, * \a dirFile is not a directory, \a fileName is not found * or an I/O error occurred. */ uint8_t SdFile::remove(SdFile* dirFile, const char* fileName) { SdFile file; if (!file.open(dirFile, fileName, O_WRITE)) return false; return file.remove(); } //------------------------------------------------------------------------------ /** Remove a directory file. * * The directory file will be removed only if it is empty and is not the * root directory. rmDir() follows DOS and Windows and ignores the * read-only attribute for the directory. * * \note This function should not be used to delete the 8.3 version of a * directory that has a long name. For example if a directory has the * long name "New folder" you should not delete the 8.3 name "NEWFOL~1". * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include the file is not a directory, is the root * directory, is not empty, or an I/O error occurred. */ uint8_t SdFile::rmDir(void) { // must be open subdirectory if (!isSubDir()) return false; rewind(); // make sure directory is empty while (curPosition_ < fileSize_) { dir_t* p = readDirCache(); if (p == NULL) return false; // done if past last used entry if (p->name[0] == DIR_NAME_FREE) break; // skip empty slot or '.' or '..' if (p->name[0] == DIR_NAME_DELETED || p->name[0] == '.') continue; // error not empty if (DIR_IS_FILE_OR_SUBDIR(p)) return false; } // convert empty directory to normal file for remove type_ = FAT_FILE_TYPE_NORMAL; flags_ |= O_WRITE; return remove(); } //------------------------------------------------------------------------------ /** Recursively delete a directory and all contained files. * * This is like the Unix/Linux 'rm -rf *' if called with the root directory * hence the name. * * Warning - This will remove all contents of the directory including * subdirectories. The directory will then be removed if it is not root. * The read-only attribute for files will be ignored. * * \note This function should not be used to delete the 8.3 version of * a directory that has a long name. See remove() and rmDir(). * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t SdFile::rmRfStar(void) { rewind(); while (curPosition_ < fileSize_) { SdFile f; // remember position uint16_t index = curPosition_/32; dir_t* p = readDirCache(); if (!p) return false; // done if past last entry if (p->name[0] == DIR_NAME_FREE) break; // skip empty slot or '.' or '..' if (p->name[0] == DIR_NAME_DELETED || p->name[0] == '.') continue; // skip if part of long file name or volume label in root if (!DIR_IS_FILE_OR_SUBDIR(p)) continue; if (!f.open(this, index, O_READ)) return false; if (f.isSubDir()) { // recursively delete if (!f.rmRfStar()) return false; } else { // ignore read-only f.flags_ |= O_WRITE; if (!f.remove()) return false; } // position to next entry if required if (curPosition_ != (32*(index + 1))) { if (!seekSet(32*(index + 1))) return false; } } // don't try to delete root if (isRoot()) return true; return rmDir(); } //------------------------------------------------------------------------------ /** * Sets a file's position. * * \param[in] pos The new position in bytes from the beginning of the file. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t SdFile::seekSet(uint32_t pos) { // error if file not open or seek past end of file if (!isOpen() || pos > fileSize_) return false; if (type_ == FAT_FILE_TYPE_ROOT16) { curPosition_ = pos; return true; } if (pos == 0) { // set position to start of file curCluster_ = 0; curPosition_ = 0; return true; } // calculate cluster index for cur and new position uint32_t nCur = (curPosition_ - 1) >> (vol_->clusterSizeShift_ + 9); uint32_t nNew = (pos - 1) >> (vol_->clusterSizeShift_ + 9); if (nNew < nCur || curPosition_ == 0) { // must follow chain from first cluster curCluster_ = firstCluster_; } else { // advance from curPosition nNew -= nCur; } while (nNew--) { if (!vol_->fatGet(curCluster_, &curCluster_)) return false; } curPosition_ = pos; return true; } //------------------------------------------------------------------------------ /** * The sync() call causes all modified data and directory fields * to be written to the storage device. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include a call to sync() before a file has been * opened or an I/O error. */ uint8_t SdFile::sync(void) { // only allow open files and directories if (!isOpen()) return false; if (flags_ & F_FILE_DIR_DIRTY) { dir_t* d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!d) return false; // do not set filesize for dir files if (!isDir()) d->fileSize = fileSize_; // update first cluster fields d->firstClusterLow = firstCluster_ & 0XFFFF; d->firstClusterHigh = firstCluster_ >> 16; // set modify time if user supplied a callback date/time function if (dateTime_) { dateTime_(&d->lastWriteDate, &d->lastWriteTime); d->lastAccessDate = d->lastWriteDate; } // clear directory dirty flags_ &= ~F_FILE_DIR_DIRTY; } return SdVolume::cacheFlush(); } //------------------------------------------------------------------------------ /** * Set a file's timestamps in its directory entry. * * \param[in] flags Values for \a flags are constructed by a bitwise-inclusive * OR of flags from the following list * * T_ACCESS - Set the file's last access date. * * T_CREATE - Set the file's creation date and time. * * T_WRITE - Set the file's last write/modification date and time. * * \param[in] year Valid range 1980 - 2107 inclusive. * * \param[in] month Valid range 1 - 12 inclusive. * * \param[in] day Valid range 1 - 31 inclusive. * * \param[in] hour Valid range 0 - 23 inclusive. * * \param[in] minute Valid range 0 - 59 inclusive. * * \param[in] second Valid range 0 - 59 inclusive * * \note It is possible to set an invalid date since there is no check for * the number of days in a month. * * \note * Modify and access timestamps may be overwritten if a date time callback * function has been set by dateTimeCallback(). * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. */ uint8_t SdFile::timestamp(uint8_t flags, uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t minute, uint8_t second) { if (!isOpen() || year < 1980 || year > 2107 || month < 1 || month > 12 || day < 1 || day > 31 || hour > 23 || minute > 59 || second > 59) { return false; } dir_t* d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); if (!d) return false; uint16_t dirDate = FAT_DATE(year, month, day); uint16_t dirTime = FAT_TIME(hour, minute, second); if (flags & T_ACCESS) { d->lastAccessDate = dirDate; } if (flags & T_CREATE) { d->creationDate = dirDate; d->creationTime = dirTime; // seems to be units of 1/100 second not 1/10 as Microsoft states d->creationTimeTenths = second & 1 ? 100 : 0; } if (flags & T_WRITE) { d->lastWriteDate = dirDate; d->lastWriteTime = dirTime; } SdVolume::cacheSetDirty(); return sync(); } //------------------------------------------------------------------------------ /** * Truncate a file to a specified length. The current file position * will be maintained if it is less than or equal to \a length otherwise * it will be set to end of file. * * \param[in] length The desired length for the file. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. * Reasons for failure include file is read only, file is a directory, * \a length is greater than the current file size or an I/O error occurs. */ uint8_t SdFile::truncate(uint32_t length) { // error if not a normal file or read-only if (!isFile() || !(flags_ & O_WRITE)) return false; // error if length is greater than current size if (length > fileSize_) return false; // fileSize and length are zero - nothing to do if (fileSize_ == 0) return true; // remember position for seek after truncation uint32_t newPos = curPosition_ > length ? length : curPosition_; // position to last cluster in truncated file if (!seekSet(length)) return false; if (length == 0) { // free all clusters if (!vol_->freeChain(firstCluster_)) return false; firstCluster_ = 0; } else { uint32_t toFree; if (!vol_->fatGet(curCluster_, &toFree)) return false; if (!vol_->isEOC(toFree)) { // free extra clusters if (!vol_->freeChain(toFree)) return false; // current cluster is end of chain if (!vol_->fatPutEOC(curCluster_)) return false; } } fileSize_ = length; // need to update directory entry flags_ |= F_FILE_DIR_DIRTY; if (!sync()) return false; // set file to correct position return seekSet(newPos); } //------------------------------------------------------------------------------ /** * Write data to an open file. * * \note Data is moved to the cache but may not be written to the * storage device until sync() is called. * * \param[in] buf Pointer to the location of the data to be written. * * \param[in] nbyte Number of bytes to write. * * \return For success write() returns the number of bytes written, always * \a nbyte. If an error occurs, write() returns -1. Possible errors * include write() is called before a file has been opened, write is called * for a read-only file, device is full, a corrupt file system or an I/O error. * */ int16_t SdFile::write(const void* buf, uint16_t nbyte) { // convert void* to uint8_t* - must be before goto statements const uint8_t* src = reinterpret_cast(buf); // number of bytes left to write - must be before goto statements uint16_t nToWrite = nbyte; // error if not a normal file or is read-only if (!isFile() || !(flags_ & O_WRITE)) goto writeErrorReturn; // seek to end of file if append flag if ((flags_ & O_APPEND) && curPosition_ != fileSize_) { if (!seekEnd()) goto writeErrorReturn; } while (nToWrite > 0) { uint8_t blockOfCluster = vol_->blockOfCluster(curPosition_); uint16_t blockOffset = curPosition_ & 0X1FF; if (blockOfCluster == 0 && blockOffset == 0) { // start of new cluster if (curCluster_ == 0) { if (firstCluster_ == 0) { // allocate first cluster of file if (!addCluster()) goto writeErrorReturn; } else { curCluster_ = firstCluster_; } } else { uint32_t next; if (!vol_->fatGet(curCluster_, &next)) return false; if (vol_->isEOC(next)) { // add cluster if at end of chain if (!addCluster()) goto writeErrorReturn; } else { curCluster_ = next; } } } // max space in block uint16_t n = 512 - blockOffset; // lesser of space and amount to write if (n > nToWrite) n = nToWrite; // block for data write uint32_t block = vol_->clusterStartBlock(curCluster_) + blockOfCluster; if (n == 512) { // full block - don't need to use cache // invalidate cache if block is in cache if (SdVolume::cacheBlockNumber_ == block) { SdVolume::cacheBlockNumber_ = 0XFFFFFFFF; } if (!vol_->writeBlock(block, src)) goto writeErrorReturn; src += 512; } else { if (blockOffset == 0 && curPosition_ >= fileSize_) { // start of new block don't need to read into cache if (!SdVolume::cacheFlush()) goto writeErrorReturn; SdVolume::cacheBlockNumber_ = block; SdVolume::cacheSetDirty(); } else { // rewrite part of block if (!SdVolume::cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) { goto writeErrorReturn; } } uint8_t* dst = SdVolume::cacheBuffer_.data + blockOffset; uint8_t* end = dst + n; while (dst != end) *dst++ = *src++; } nToWrite -= n; curPosition_ += n; } if (curPosition_ > fileSize_) { // update fileSize and insure sync will update dir entry fileSize_ = curPosition_; flags_ |= F_FILE_DIR_DIRTY; } else if (dateTime_ && nbyte) { // insure sync will update modified date and time flags_ |= F_FILE_DIR_DIRTY; } if (flags_ & O_SYNC) { if (!sync()) goto writeErrorReturn; } return nbyte; writeErrorReturn: // return for write error writeError = true; return -1; } //------------------------------------------------------------------------------ /** * Write a byte to a file. Required by the Arduino Print class. * * Use SdFile::writeError to check for errors. */ #if ARDUINO >= 100 size_t SdFile::write(uint8_t b) #else void SdFile::write(uint8_t b) #endif { #if ARDUINO >= 100 return (size_t) write(&b, 1); #else write(&b, 1); #endif } //------------------------------------------------------------------------------ /** * Write a string to a file. Used by the Arduino Print class. * * Use SdFile::writeError to check for errors. */ void SdFile::write(const char* str) { write(str, strlen(str)); } //------------------------------------------------------------------------------ /** * Write a PROGMEM string to a file. * * Use SdFile::writeError to check for errors. */ void SdFile::write_P(PGM_P str) { for (uint8_t c; (c = pgm_read_byte(str)); str++) write(c); } //------------------------------------------------------------------------------ /** * Write a PROGMEM string followed by CR/LF to a file. * * Use SdFile::writeError to check for errors. */ void SdFile::writeln_P(PGM_P str) { write_P(str); println(); } ================================================ FILE: Sprinter/SdInfo.h ================================================ /* Arduino Sd2Card Library * Copyright (C) 2009 by William Greiman * * This file is part of the Arduino Sd2Card Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with the Arduino Sd2Card Library. If not, see * . */ #ifndef SdInfo_h #define SdInfo_h #include // Based on the document: // // SD Specifications // Part 1 // Physical Layer // Simplified Specification // Version 2.00 // September 25, 2006 // // www.sdcard.org/developers/tech/sdcard/pls/Simplified_Physical_Layer_Spec.pdf //------------------------------------------------------------------------------ // SD card commands /** GO_IDLE_STATE - init card in spi mode if CS low */ uint8_t const CMD0 = 0X00; /** SEND_IF_COND - verify SD Memory Card interface operating condition.*/ uint8_t const CMD8 = 0X08; /** SEND_CSD - read the Card Specific Data (CSD register) */ uint8_t const CMD9 = 0X09; /** SEND_CID - read the card identification information (CID register) */ uint8_t const CMD10 = 0X0A; /** SEND_STATUS - read the card status register */ uint8_t const CMD13 = 0X0D; /** READ_BLOCK - read a single data block from the card */ uint8_t const CMD17 = 0X11; /** WRITE_BLOCK - write a single data block to the card */ uint8_t const CMD24 = 0X18; /** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */ uint8_t const CMD25 = 0X19; /** ERASE_WR_BLK_START - sets the address of the first block to be erased */ uint8_t const CMD32 = 0X20; /** ERASE_WR_BLK_END - sets the address of the last block of the continuous range to be erased*/ uint8_t const CMD33 = 0X21; /** ERASE - erase all previously selected blocks */ uint8_t const CMD38 = 0X26; /** APP_CMD - escape for application specific command */ uint8_t const CMD55 = 0X37; /** READ_OCR - read the OCR register of a card */ uint8_t const CMD58 = 0X3A; /** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be pre-erased before writing */ uint8_t const ACMD23 = 0X17; /** SD_SEND_OP_COMD - Sends host capacity support information and activates the card's initialization process */ uint8_t const ACMD41 = 0X29; //------------------------------------------------------------------------------ /** status for card in the ready state */ uint8_t const R1_READY_STATE = 0X00; /** status for card in the idle state */ uint8_t const R1_IDLE_STATE = 0X01; /** status bit for illegal command */ uint8_t const R1_ILLEGAL_COMMAND = 0X04; /** start data token for read or write single block*/ uint8_t const DATA_START_BLOCK = 0XFE; /** stop token for write multiple blocks*/ uint8_t const STOP_TRAN_TOKEN = 0XFD; /** start data token for write multiple blocks*/ uint8_t const WRITE_MULTIPLE_TOKEN = 0XFC; /** mask for data response tokens after a write block operation */ uint8_t const DATA_RES_MASK = 0X1F; /** write data accepted token */ uint8_t const DATA_RES_ACCEPTED = 0X05; //------------------------------------------------------------------------------ typedef struct CID { // byte 0 uint8_t mid; // Manufacturer ID // byte 1-2 char oid[2]; // OEM/Application ID // byte 3-7 char pnm[5]; // Product name // byte 8 unsigned prv_m : 4; // Product revision n.m unsigned prv_n : 4; // byte 9-12 uint32_t psn; // Product serial number // byte 13 unsigned mdt_year_high : 4; // Manufacturing date unsigned reserved : 4; // byte 14 unsigned mdt_month : 4; unsigned mdt_year_low :4; // byte 15 unsigned always1 : 1; unsigned crc : 7; }cid_t; //------------------------------------------------------------------------------ // CSD for version 1.00 cards typedef struct CSDV1 { // byte 0 unsigned reserved1 : 6; unsigned csd_ver : 2; // byte 1 uint8_t taac; // byte 2 uint8_t nsac; // byte 3 uint8_t tran_speed; // byte 4 uint8_t ccc_high; // byte 5 unsigned read_bl_len : 4; unsigned ccc_low : 4; // byte 6 unsigned c_size_high : 2; unsigned reserved2 : 2; unsigned dsr_imp : 1; unsigned read_blk_misalign :1; unsigned write_blk_misalign : 1; unsigned read_bl_partial : 1; // byte 7 uint8_t c_size_mid; // byte 8 unsigned vdd_r_curr_max : 3; unsigned vdd_r_curr_min : 3; unsigned c_size_low :2; // byte 9 unsigned c_size_mult_high : 2; unsigned vdd_w_cur_max : 3; unsigned vdd_w_curr_min : 3; // byte 10 unsigned sector_size_high : 6; unsigned erase_blk_en : 1; unsigned c_size_mult_low : 1; // byte 11 unsigned wp_grp_size : 7; unsigned sector_size_low : 1; // byte 12 unsigned write_bl_len_high : 2; unsigned r2w_factor : 3; unsigned reserved3 : 2; unsigned wp_grp_enable : 1; // byte 13 unsigned reserved4 : 5; unsigned write_partial : 1; unsigned write_bl_len_low : 2; // byte 14 unsigned reserved5: 2; unsigned file_format : 2; unsigned tmp_write_protect : 1; unsigned perm_write_protect : 1; unsigned copy : 1; unsigned file_format_grp : 1; // byte 15 unsigned always1 : 1; unsigned crc : 7; }csd1_t; //------------------------------------------------------------------------------ // CSD for version 2.00 cards typedef struct CSDV2 { // byte 0 unsigned reserved1 : 6; unsigned csd_ver : 2; // byte 1 uint8_t taac; // byte 2 uint8_t nsac; // byte 3 uint8_t tran_speed; // byte 4 uint8_t ccc_high; // byte 5 unsigned read_bl_len : 4; unsigned ccc_low : 4; // byte 6 unsigned reserved2 : 4; unsigned dsr_imp : 1; unsigned read_blk_misalign :1; unsigned write_blk_misalign : 1; unsigned read_bl_partial : 1; // byte 7 unsigned reserved3 : 2; unsigned c_size_high : 6; // byte 8 uint8_t c_size_mid; // byte 9 uint8_t c_size_low; // byte 10 unsigned sector_size_high : 6; unsigned erase_blk_en : 1; unsigned reserved4 : 1; // byte 11 unsigned wp_grp_size : 7; unsigned sector_size_low : 1; // byte 12 unsigned write_bl_len_high : 2; unsigned r2w_factor : 3; unsigned reserved5 : 2; unsigned wp_grp_enable : 1; // byte 13 unsigned reserved6 : 5; unsigned write_partial : 1; unsigned write_bl_len_low : 2; // byte 14 unsigned reserved7: 2; unsigned file_format : 2; unsigned tmp_write_protect : 1; unsigned perm_write_protect : 1; unsigned copy : 1; unsigned file_format_grp : 1; // byte 15 unsigned always1 : 1; unsigned crc : 7; }csd2_t; //------------------------------------------------------------------------------ // union of old and new style CSD register union csd_t { csd1_t v1; csd2_t v2; }; #endif // SdInfo_h ================================================ FILE: Sprinter/SdVolume.cpp ================================================ /* Arduino SdFat Library * Copyright (C) 2009 by William Greiman * * This file is part of the Arduino SdFat Library * * This Library is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This Library is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with the Arduino SdFat Library. If not, see * . */ #include "SdFat.h" //------------------------------------------------------------------------------ // raw block cache // init cacheBlockNumber_to invalid SD block number uint32_t SdVolume::cacheBlockNumber_ = 0XFFFFFFFF; cache_t SdVolume::cacheBuffer_; // 512 byte cache for Sd2Card Sd2Card* SdVolume::sdCard_; // pointer to SD card object uint8_t SdVolume::cacheDirty_ = 0; // cacheFlush() will write block if true uint32_t SdVolume::cacheMirrorBlock_ = 0; // mirror block for second FAT //------------------------------------------------------------------------------ // find a contiguous group of clusters uint8_t SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) { // start of group uint32_t bgnCluster; // flag to save place to start next search uint8_t setStart; // set search start cluster if (*curCluster) { // try to make file contiguous bgnCluster = *curCluster + 1; // don't save new start location setStart = false; } else { // start at likely place for free cluster bgnCluster = allocSearchStart_; // save next search start if one cluster setStart = 1 == count; } // end of group uint32_t endCluster = bgnCluster; // last cluster of FAT uint32_t fatEnd = clusterCount_ + 1; // search the FAT for free clusters for (uint32_t n = 0;; n++, endCluster++) { // can't find space checked all clusters if (n >= clusterCount_) return false; // past end - start from beginning of FAT if (endCluster > fatEnd) { bgnCluster = endCluster = 2; } uint32_t f; if (!fatGet(endCluster, &f)) return false; if (f != 0) { // cluster in use try next cluster as bgnCluster bgnCluster = endCluster + 1; } else if ((endCluster - bgnCluster + 1) == count) { // done - found space break; } } // mark end of chain if (!fatPutEOC(endCluster)) return false; // link clusters while (endCluster > bgnCluster) { if (!fatPut(endCluster - 1, endCluster)) return false; endCluster--; } if (*curCluster != 0) { // connect chains if (!fatPut(*curCluster, bgnCluster)) return false; } // return first cluster number to caller *curCluster = bgnCluster; // remember possible next free cluster if (setStart) allocSearchStart_ = bgnCluster + 1; return true; } //------------------------------------------------------------------------------ uint8_t SdVolume::cacheFlush(void) { if (cacheDirty_) { if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) { return false; } // mirror FAT tables if (cacheMirrorBlock_) { if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data)) { return false; } cacheMirrorBlock_ = 0; } cacheDirty_ = 0; } return true; } //------------------------------------------------------------------------------ uint8_t SdVolume::cacheRawBlock(uint32_t blockNumber, uint8_t action) { if (cacheBlockNumber_ != blockNumber) { if (!cacheFlush()) return false; if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) return false; cacheBlockNumber_ = blockNumber; } cacheDirty_ |= action; return true; } //------------------------------------------------------------------------------ // cache a zero block for blockNumber uint8_t SdVolume::cacheZeroBlock(uint32_t blockNumber) { if (!cacheFlush()) return false; // loop take less flash than memset(cacheBuffer_.data, 0, 512); for (uint16_t i = 0; i < 512; i++) { cacheBuffer_.data[i] = 0; } cacheBlockNumber_ = blockNumber; cacheSetDirty(); return true; } //------------------------------------------------------------------------------ // return the size in bytes of a cluster chain uint8_t SdVolume::chainSize(uint32_t cluster, uint32_t* size) const { uint32_t s = 0; do { if (!fatGet(cluster, &cluster)) return false; s += 512UL << clusterSizeShift_; } while (!isEOC(cluster)); *size = s; return true; } //------------------------------------------------------------------------------ // Fetch a FAT entry uint8_t SdVolume::fatGet(uint32_t cluster, uint32_t* value) const { if (cluster > (clusterCount_ + 1)) return false; uint32_t lba = fatStartBlock_; lba += fatType_ == 16 ? cluster >> 8 : cluster >> 7; if (lba != cacheBlockNumber_) { if (!cacheRawBlock(lba, CACHE_FOR_READ)) return false; } if (fatType_ == 16) { *value = cacheBuffer_.fat16[cluster & 0XFF]; } else { *value = cacheBuffer_.fat32[cluster & 0X7F] & FAT32MASK; } return true; } //------------------------------------------------------------------------------ // Store a FAT entry uint8_t SdVolume::fatPut(uint32_t cluster, uint32_t value) { // error if reserved cluster if (cluster < 2) return false; // error if not in FAT if (cluster > (clusterCount_ + 1)) return false; // calculate block address for entry uint32_t lba = fatStartBlock_; lba += fatType_ == 16 ? cluster >> 8 : cluster >> 7; if (lba != cacheBlockNumber_) { if (!cacheRawBlock(lba, CACHE_FOR_READ)) return false; } // store entry if (fatType_ == 16) { cacheBuffer_.fat16[cluster & 0XFF] = value; } else { cacheBuffer_.fat32[cluster & 0X7F] = value; } cacheSetDirty(); // mirror second FAT if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_; return true; } //------------------------------------------------------------------------------ // free a cluster chain uint8_t SdVolume::freeChain(uint32_t cluster) { // clear free cluster location allocSearchStart_ = 2; do { uint32_t next; if (!fatGet(cluster, &next)) return false; // free cluster if (!fatPut(cluster, 0)) return false; cluster = next; } while (!isEOC(cluster)); return true; } //------------------------------------------------------------------------------ /** * Initialize a FAT volume. * * \param[in] dev The SD card where the volume is located. * * \param[in] part The partition to be used. Legal values for \a part are * 1-4 to use the corresponding partition on a device formatted with * a MBR, Master Boot Record, or zero if the device is formatted as * a super floppy with the FAT boot sector in block zero. * * \return The value one, true, is returned for success and * the value zero, false, is returned for failure. Reasons for * failure include not finding a valid partition, not finding a valid * FAT file system in the specified partition or an I/O error. */ uint8_t SdVolume::init(Sd2Card* dev, uint8_t part) { uint32_t volumeStartBlock = 0; sdCard_ = dev; // if part == 0 assume super floppy with FAT boot sector in block zero // if part > 0 assume mbr volume with partition table if (part) { if (part > 4)return false; if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) return false; part_t* p = &cacheBuffer_.mbr.part[part-1]; if ((p->boot & 0X7F) !=0 || p->totalSectors < 100 || p->firstSector == 0) { // not a valid partition return false; } volumeStartBlock = p->firstSector; } if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) return false; bpb_t* bpb = &cacheBuffer_.fbs.bpb; if (bpb->bytesPerSector != 512 || bpb->fatCount == 0 || bpb->reservedSectorCount == 0 || bpb->sectorsPerCluster == 0) { // not valid FAT volume return false; } fatCount_ = bpb->fatCount; blocksPerCluster_ = bpb->sectorsPerCluster; // determine shift that is same as multiply by blocksPerCluster_ clusterSizeShift_ = 0; while (blocksPerCluster_ != (1 << clusterSizeShift_)) { // error if not power of 2 if (clusterSizeShift_++ > 7) return false; } blocksPerFat_ = bpb->sectorsPerFat16 ? bpb->sectorsPerFat16 : bpb->sectorsPerFat32; fatStartBlock_ = volumeStartBlock + bpb->reservedSectorCount; // count for FAT16 zero for FAT32 rootDirEntryCount_ = bpb->rootDirEntryCount; // directory start for FAT16 dataStart for FAT32 rootDirStart_ = fatStartBlock_ + bpb->fatCount * blocksPerFat_; // data start for FAT16 and FAT32 dataStartBlock_ = rootDirStart_ + ((32 * bpb->rootDirEntryCount + 511)/512); // total blocks for FAT16 or FAT32 uint32_t totalBlocks = bpb->totalSectors16 ? bpb->totalSectors16 : bpb->totalSectors32; // total data blocks clusterCount_ = totalBlocks - (dataStartBlock_ - volumeStartBlock); // divide by cluster size to get cluster count clusterCount_ >>= clusterSizeShift_; // FAT type is determined by cluster count if (clusterCount_ < 4085) { fatType_ = 12; } else if (clusterCount_ < 65525) { fatType_ = 16; } else { rootDirStart_ = bpb->fat32RootCluster; fatType_ = 32; } return true; } ================================================ FILE: Sprinter/Sprinter.h ================================================ // Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware. // Licence: GPL //Check Version of Arduino and then include the right libraries #if defined(ARDUINO) && ARDUINO >= 100 #include "Arduino.h" #else #include #endif #include "fastio.h" extern "C" void __cxa_pure_virtual(); #define FORCE_INLINE __attribute__((always_inline)) inline #if X_ENABLE_PIN > -1 #define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON) #define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON) #else #define enable_x() ; #define disable_x() ; #endif #if Y_ENABLE_PIN > -1 #define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON) #define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON) #else #define enable_y() ; #define disable_y() ; #endif #if Z_ENABLE_PIN > -1 #define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON) #define disable_z() WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON) #else #define enable_z() ; #define disable_z() ; #endif #if E_ENABLE_PIN > -1 #define enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON) #define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON) #else #define enable_e() ; #define disable_e() ; #endif #define X_AXIS 0 #define Y_AXIS 1 #define Z_AXIS 2 #define E_AXIS 3 // This struct is used when buffering the setup for each linear movement "nominal" values are as specified in // the source g-code and may never actually be reached if acceleration management is active. typedef struct { // Fields used by the bresenham algorithm for tracing the line long steps_x, steps_y, steps_z, steps_e; // Step count along each axis unsigned long step_event_count; // The number of step events required to complete this block long accelerate_until; // The index of the step event on which to stop acceleration long decelerate_after; // The index of the step event on which to start decelerating long acceleration_rate; // The acceleration rate used for acceleration calculation unsigned char direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h) #ifdef ADVANCE long advance_rate; volatile long initial_advance; volatile long final_advance; float advance; #endif // Fields used by the motion planner to manage acceleration // float speed_x, speed_y, speed_z, speed_e; // Nominal mm/minute for each axis float nominal_speed; // The nominal speed for this block in mm/min float entry_speed; // Entry speed at previous-current junction in mm/min float max_entry_speed; // Maximum allowable junction entry speed in mm/min float millimeters; // The total travel of this block in mm float acceleration; // acceleration mm/sec^2 unsigned char recalculate_flag; // Planner flag to recalculate trapezoids on entry junction unsigned char nominal_length_flag; // Planner flag for nominal speed always reached // Settings for the trapezoid generator long nominal_rate; // The nominal step rate for this block in step_events/sec long initial_rate; // The jerk-adjusted step rate at start of block long final_rate; // The minimal rate at exit long acceleration_st; // acceleration steps/sec^2 volatile char busy; } block_t; void FlushSerialRequestResend(); void ClearToSend(); void analogWrite_check(uint8_t check_pin, int val); void showString (PGM_P s); void manage_inactivity(byte debug); void get_command(); void get_coordinates(); void prepare_move(); void prepare_arc_move(char isclockwise); FORCE_INLINE void process_commands(); #ifdef USE_ARC_FUNCTION FORCE_INLINE void get_arc_coordinates(); #endif void kill(byte debug); void check_axes_activity(); void plan_init(); void st_init(); void tp_init(); void plan_buffer_line(float x, float y, float z, float e, float feed_rate); void plan_set_position(float x, float y, float z, float e); void st_wake_up(); void st_synchronize(); void st_set_position(const long &x, const long &y, const long &z, const long &e); void check_buffer_while_arc(); #ifdef SDSUPPORT void print_disk_info(void); #endif //SDSUPPORT #if (MINIMUM_FAN_START_SPEED > 0) void manage_fan_start_speed(void); #endif #ifdef DEBUG void log_message(char* message); void log_bool(char* message, bool value); void log_int(char* message, int value); void log_long(char* message, long value); void log_float(char* message, float value); void log_uint(char* message, unsigned int value); void log_ulong(char* message, unsigned long value); #endif ================================================ FILE: Sprinter/Sprinter.pde ================================================ /* Reprap firmware based on Sprinter Optimized for Sanguinololu 1.2 and above / RAMPS This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ /* This firmware is a mashup between Sprinter, grbl and parts from marlin. (https://github.com/kliment/Sprinter) Changes by Doppler Michael (midopple) Planner is from Simen Svale Skogsrud https://github.com/simen/grbl Parts of Marlin Firmware from ErikZalm https://github.com/ErikZalm/Marlin-non-gen6 Sprinter Changelog - Look forward function --> calculate 16 Steps forward, get from Firmaware Marlin and Grbl - Stepper control with Timer 1 (Interrupt) - Extruder heating with PID use a Softpwm (Timer 2) with 500 hz to free Timer1 for Steppercontrol - command M220 Sxxx --> tune Printing speed online (+/- 50 %) - G2 / G3 command --> circle function - Baudrate set to 250 kbaud - Testet on Sanguinololu Board - M30 Command can delete files on SD Card - move string to flash to free RAM vor forward planner - M203 Temperature monitor for Repetier Version 1.3.04T - Implement Plannercode from Marlin V1 big thanks to Erik - Stepper interrupt with Step loops - Stepperfrequency 30 Khz - New Command * M202 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec * M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2 * M205 - advanced settings: minimum travel speed S=while printing T=travel only, X= maximum xy jerk, Z=maximum Z jerk, E = max E jerk - Remove unused Variables - Check Uart Puffer while circle processing (CMD: G2 / G3) - Fast Xfer Function --> move Text to Flash - Option to deactivate ARC (G2/G3) function (save flash) - Removed modulo (%) operator, which uses an expensive divide Version 1.3.05T - changed homing function to not conflict with min_software_endstops/max_software_endstops (thanks rGlory) - Changed check in arc_func - Corrected distance calculation. (thanks jv4779) - MAX Feed Rate for Z-Axis reduced to 2 mm/s some Printers had problems with 4 mm/s Version 1.3.06T - the microcontroller can store settings in the EEPROM - M500 - stores paramters in EEPROM - M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). - M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. - M503 - Print settings Version 1.3.07T - Optimize Variable Size (faster Code) - Remove unused Code from Interrupt --> faster ~ 22 us per step - Replace abs with fabs --> Faster and smaler - Add "store_eeprom.cpp" to makefile Version 1.3.08T - If a line starts with ';', it is ignored but comment_mode is reset. A ';' inside a line ignores just the portion following the ';' character. The beginning of the line is still interpreted. - Same fix for SD Card, tested and work Version 1.3.09T - Move SLOWDOWN Function up Version 1.3.10T - Add info to GEN7 Pins - Update pins.h for gen7, working setup for 20MHz - calculate feedrate without extrude before planner block is set - New Board --> GEN7 @ 20 Mhz … - ENDSTOPS_ONLY_FOR_HOMING Option ignore Endstop always --> fault is cleared Version 1.3.11T - fix for broken include in store_eeprom.cpp --> Thanks to kmeehl (issue #145) - Make fastio & Arduino pin numbering consistent for AT90USB128x. --> Thanks to lincomatic - Select Speedtable with F_CPU - Use same Values for Speedtables as Marlin Version 1.3.12T - Fixed arc offset. Version 1.3.13T - Extrudemultiply with code M221 Sxxx (S100 original Extrude value) - use Feedratefactor only when Extrude > 0 - M106 / M107 can drive the FAN with PWM + Port check for not using Timer 1 - Added M93 command. Sends current steps for all axis. - New Option --> FAN_SOFT_PWM, with this option the FAN PWM can use every digital I/O Version 1.3.14T - When endstop is hit count the virtual steps, so the print lose no position when endstop is hit Version 1.3.15T - M206 - set additional homing offset - Option for minimum FAN start speed --> #define MINIMUM_FAN_START_SPEED 50 (set it to zero to deactivate) Version 1.3.16T - Extra Max Feedrate for Retract (MAX_RETRACT_FEEDRATE) Version 1.3.17T - M303 - PID relay autotune possible - G4 Wait until last move is done Version 1.3.18T - Problem with Thermistor 3 table when sensor is broken and temp is -20 °C Version 1.3.19T - Set maximum acceleration. If "steps per unit" is Change the acc were not recalculated - Extra Parameter for Max Extruder Jerk - New Parameter (max_e_jerk) in EEPROM --> Default settings after update ! Version 1.3.20T - fix a few typos and correct english usage - reimplement homing routine as an inline function - refactor eeprom routines to make it possible to modify the value of a single parameter - calculate eeprom parameter addresses based on previous param address plus sizeof(type) - add 0 C point in Thermistortable 7 Version 1.3.21T - M301 set PID Parameter, and Store to EEPROM - If no PID is used, deaktivate Variables for PID settings Version 1.3.22T - Error in JERK calculation after G92 command is send, make problems with Z-Lift function in Slic3r - Add homing values can shown with M206 D */ #include #include #include "fastio.h" #include "Configuration.h" #include "pins.h" #include "Sprinter.h" #include "speed_lookuptable.h" #include "heater.h" #ifdef USE_ARC_FUNCTION #include "arc_func.h" #endif #ifdef SDSUPPORT #include "SdFat.h" #endif #ifdef USE_EEPROM_SETTINGS #include "store_eeprom.h" #endif #ifndef CRITICAL_SECTION_START #define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli() #define CRITICAL_SECTION_END SREG = _sreg #endif //CRITICAL_SECTION_START void __cxa_pure_virtual(){}; // look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes //Implemented Codes //------------------- // G0 -> G1 // G1 - Coordinated Movement X Y Z E // G2 - CW ARC // G3 - CCW ARC // G4 - Dwell S or P // G28 - Home all Axis // G90 - Use Absolute Coordinates // G91 - Use Relative Coordinates // G92 - Set current position to cordinates given //RepRap M Codes // M104 - Set extruder target temp // M105 - Read current temp // M106 - Fan on // M107 - Fan off // M109 - Wait for extruder current temp to reach target temp. // M114 - Display current position //Custom M Codes // M20 - List SD card // M21 - Init SD card // M22 - Release SD card // M23 - Select SD file (M23 filename.g) // M24 - Start/resume SD print // M25 - Pause SD print // M26 - Set SD position in bytes (M26 S12345) // M27 - Report SD print status // M28 - Start SD write (M28 filename.g) // M29 - Stop SD write // - - Delete file on sd card // M42 - Set output on free pins, on a non pwm pin (over pin 13 on an arduino mega) use S255 to turn it on and S0 to turn it off. Use P to decide the pin (M42 P23 S255) would turn pin 23 on // M80 - Turn on Power Supply // M81 - Turn off Power Supply // M82 - Set E codes absolute (default) // M83 - Set E codes relative while in Absolute Coordinates (G90) mode // M84 - Disable steppers until next move, // or use S to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout. // M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) // M92 - Set axis_steps_per_unit - same syntax as G92 // M93 - Send axis_steps_per_unit // M115 - Capabilities string // M119 - Show Endstopper State // M140 - Set bed target temp // M190 - Wait for bed current temp to reach target temp. // M201 - Set maximum acceleration in units/s^2 for print moves (M201 X1000 Y1000) // M202 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec // M203 - Set temperture monitor to Sx // M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) in mm/sec^2 // M205 - advanced settings: minimum travel speed S=while printing T=travel only, X=maximum xy jerk, Z=maximum Z jerk // M206 - set additional homing offset // M220 - set speed factor override percentage S=factor in percent // M221 - set extruder multiply factor S100 --> original Extrude Speed // M301 - Set PID parameters P I and D // M303 - PID relay autotune S sets the target temperature. (default target temperature = 150C) // M400 - Finish all moves // M500 - stores paramters in EEPROM // M501 - reads parameters from EEPROM (if you need to reset them after you changed them temporarily). // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. // M503 - Print settings // Debug feature / Testing the PID for Hotend // M601 - Show Temp jitter from Extruder (min / max value from Hotend Temperature while printing) // M602 - Reset Temp jitter from Extruder (min / max val) --> Don't use it while Printing // M603 - Show Free Ram #define _VERSION_TEXT "1.3.22T / 20.08.2012" //Stepper Movement Variables char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'}; float axis_steps_per_unit[4] = _AXIS_STEP_PER_UNIT; float max_feedrate[4] = _MAX_FEEDRATE; float homing_feedrate[] = _HOMING_FEEDRATE; bool axis_relative_modes[] = _AXIS_RELATIVE_MODES; float move_acceleration = _ACCELERATION; // Normal acceleration mm/s^2 float retract_acceleration = _RETRACT_ACCELERATION; // Normal acceleration mm/s^2 float max_xy_jerk = _MAX_XY_JERK; float max_z_jerk = _MAX_Z_JERK; float max_e_jerk = _MAX_E_JERK; unsigned long min_seg_time = _MIN_SEG_TIME; #ifdef PIDTEMP unsigned int PID_Kp = PID_PGAIN, PID_Ki = PID_IGAIN, PID_Kd = PID_DGAIN; #endif long max_acceleration_units_per_sq_second[4] = _MAX_ACCELERATION_UNITS_PER_SQ_SECOND; // X, Y, Z and E max acceleration in mm/s^2 for printing moves or retracts //float max_start_speed_units_per_second[] = _MAX_START_SPEED_UNITS_PER_SECOND; //long max_travel_acceleration_units_per_sq_second[] = _MAX_TRAVEL_ACCELERATION_UNITS_PER_SQ_SECOND; // X, Y, Z max acceleration in mm/s^2 for travel moves float mintravelfeedrate = DEFAULT_MINTRAVELFEEDRATE; float minimumfeedrate = DEFAULT_MINIMUMFEEDRATE; unsigned long axis_steps_per_sqr_second[NUM_AXIS]; unsigned long plateau_steps; //unsigned long axis_max_interval[NUM_AXIS]; //unsigned long axis_travel_steps_per_sqr_second[NUM_AXIS]; //unsigned long max_interval; //unsigned long steps_per_sqr_second; //adjustable feed factor for online tuning printer speed volatile int feedmultiply=100; //100->original / 200 -> Factor 2 / 50 -> Factor 0.5 int saved_feedmultiply; volatile bool feedmultiplychanged=false; volatile int extrudemultiply=100; //100->1 200->2 //boolean acceleration_enabled = false, accelerating = false; //unsigned long interval; float destination[NUM_AXIS] = {0.0, 0.0, 0.0, 0.0}; float current_position[NUM_AXIS] = {0.0, 0.0, 0.0, 0.0}; float add_homing[3]={0,0,0}; static unsigned short virtual_steps_x = 0; static unsigned short virtual_steps_y = 0; static unsigned short virtual_steps_z = 0; bool home_all_axis = true; //unsigned ?? ToDo: Check int feedrate = 1500, next_feedrate, saved_feedrate; long gcode_N, gcode_LastN; bool relative_mode = false; //Determines Absolute or Relative Coordinates //unsigned long steps_taken[NUM_AXIS]; //long axis_interval[NUM_AXIS]; // for speed delay //float time_for_move; //bool relative_mode_e = false; //Determines Absolute or Relative E Codes while in Absolute Coordinates mode. E is always relative in Relative Coordinates mode. //long timediff = 0; bool is_homing = false; //experimental feedrate calc //float d = 0; //float axis_diff[NUM_AXIS] = {0, 0, 0, 0}; #ifdef USE_ARC_FUNCTION //For arc center point coordinates, sent by commands G2/G3 float offset[3] = {0.0, 0.0, 0.0}; #endif #ifdef STEP_DELAY_RATIO long long_step_delay_ratio = STEP_DELAY_RATIO * 100; #endif ///oscillation reduction #ifdef RAPID_OSCILLATION_REDUCTION float cumm_wait_time_in_dir[NUM_AXIS]={0.0,0.0,0.0,0.0}; bool prev_move_direction[NUM_AXIS]={1,1,1,1}; float osc_wait_remainder = 0.0; #endif #if (MINIMUM_FAN_START_SPEED > 0) unsigned char fan_last_speed = 0; unsigned char fan_org_start_speed = 0; unsigned long previous_millis_fan_start = 0; #endif // comm variables and Commandbuffer // BUFSIZE is reduced from 8 to 6 to free more RAM for the PLANNER #define MAX_CMD_SIZE 96 #define BUFSIZE 6 //8 char cmdbuffer[BUFSIZE][MAX_CMD_SIZE]; bool fromsd[BUFSIZE]; //Need 1kb Ram --> only work with Atmega1284 #ifdef SD_FAST_XFER_AKTIV char fastxferbuffer[SD_FAST_XFER_CHUNK_SIZE + 1]; int lastxferchar; long xferbytes; #endif unsigned char bufindr = 0; unsigned char bufindw = 0; unsigned char buflen = 0; char serial_char; int serial_count = 0; boolean comment_mode = false; char *strchr_pointer; // just a pointer to find chars in the cmd string like X, Y, Z, E, etc //Send Temperature in °C to Host int hotendtC = 0, bedtempC = 0; //Inactivity shutdown variables unsigned long previous_millis_cmd = 0; unsigned long max_inactive_time = 0; unsigned long stepper_inactive_time = 0; //Temp Monitor for repetier unsigned char manage_monitor = 255; //------------------------------------------------ //Init the SD card //------------------------------------------------ #ifdef SDSUPPORT Sd2Card card; SdVolume volume; SdFile root; SdFile file; uint32_t filesize = 0; uint32_t sdpos = 0; bool sdmode = false; bool sdactive = false; bool savetosd = false; int16_t read_char_int; void initsd() { sdactive = false; #if SDSS >- 1 if(root.isOpen()) root.close(); if (!card.init(SPI_FULL_SPEED,SDSS)){ //if (!card.init(SPI_HALF_SPEED,SDSS)) showString(PSTR("SD init fail\r\n")); } else if (!volume.init(&card)) showString(PSTR("volume.init failed\r\n")); else if (!root.openRoot(&volume)) showString(PSTR("openRoot failed\r\n")); else{ sdactive = true; print_disk_info(); #ifdef SDINITFILE file.close(); if(file.open(&root, "init.g", O_READ)){ sdpos = 0; filesize = file.fileSize(); sdmode = true; } #endif } #endif } #ifdef SD_FAST_XFER_AKTIV #ifdef PIDTEMP extern volatile unsigned char g_heater_pwm_val; #endif void fast_xfer() { char *pstr; boolean done = false; //force heater pins low if(HEATER_0_PIN > -1) WRITE(HEATER_0_PIN,LOW); if(HEATER_1_PIN > -1) WRITE(HEATER_1_PIN,LOW); #ifdef PIDTEMP g_heater_pwm_val = 0; #endif lastxferchar = 1; xferbytes = 0; pstr = strstr(strchr_pointer+4, " "); if(pstr == NULL) { showString(PSTR("invalid command\r\n")); return; } *pstr = '\0'; //check mode (currently only RAW is supported if(strcmp(strchr_pointer+4, "RAW") != 0) { showString(PSTR("Invalid transfer codec\r\n")); return; }else{ showString(PSTR("Selected codec: ")); Serial.println(strchr_pointer+4); } if (!file.open(&root, pstr+1, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { showString(PSTR("open failed, File: ")); Serial.print(pstr+1); showString(PSTR(".")); }else{ showString(PSTR("Writing to file: ")); Serial.println(pstr+1); } showString(PSTR("ok\r\n")); //RAW transfer codec //Host sends \0 then up to SD_FAST_XFER_CHUNK_SIZE then \0 //when host is done, it sends \0\0. //if a non \0 character is recieved at the beginning, host has failed somehow, kill the transfer. //read SD_FAST_XFER_CHUNK_SIZE bytes (or until \0 is recieved) while(!done) { while(!Serial.available()) { } if(Serial.read() != 0) { //host has failed, this isn't a RAW chunk, it's an actual command file.sync(); file.close(); return; } for(int i=0;i(__brkval) == 0) { // if no heap use from end of bss section free_memory = reinterpret_cast(&free_memory) - reinterpret_cast(&__bss_end); } else { // use from top of stack to heap free_memory = reinterpret_cast(&free_memory) - reinterpret_cast(__brkval); } return free_memory; } //------------------------------------------------ //Function the check the Analog OUT pin for not using the Timer1 //------------------------------------------------ void analogWrite_check(uint8_t check_pin, int val) { #if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__) //Atmega168/328 can't use OCR1A and OCR1B //These are pins PB1/PB2 or on Arduino D9/D10 if((check_pin != 9) && (check_pin != 10)) { analogWrite(check_pin, val); } #endif #if defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__) //Atmega664P/1284P can't use OCR1A and OCR1B //These are pins PD4/PD5 or on Arduino D12/D13 if((check_pin != 12) && (check_pin != 13)) { analogWrite(check_pin, val); } #endif #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //Atmega1280/2560 can't use OCR1A, OCR1B and OCR1C //These are pins PB5,PB6,PB7 or on Arduino D11,D12 and D13 if((check_pin != 11) && (check_pin != 12) && (check_pin != 13)) { analogWrite(check_pin, val); } #endif } //------------------------------------------------ //Print a String from Flash to Serial (save RAM) //------------------------------------------------ void showString (PGM_P s) { char c; while ((c = pgm_read_byte(s++)) != 0) Serial.print(c); } //------------------------------------------------ // Init //------------------------------------------------ void setup() { Serial.begin(BAUDRATE); showString(PSTR("Sprinter\r\n")); showString(PSTR(_VERSION_TEXT)); showString(PSTR("\r\n")); showString(PSTR("start\r\n")); for(int i = 0; i < BUFSIZE; i++) { fromsd[i] = false; } //Initialize Dir Pins #if X_DIR_PIN > -1 SET_OUTPUT(X_DIR_PIN); #endif #if Y_DIR_PIN > -1 SET_OUTPUT(Y_DIR_PIN); #endif #if Z_DIR_PIN > -1 SET_OUTPUT(Z_DIR_PIN); #endif #if E_DIR_PIN > -1 SET_OUTPUT(E_DIR_PIN); #endif //Initialize Enable Pins - steppers default to disabled. #if (X_ENABLE_PIN > -1) SET_OUTPUT(X_ENABLE_PIN); if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH); #endif #if (Y_ENABLE_PIN > -1) SET_OUTPUT(Y_ENABLE_PIN); if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH); #endif #if (Z_ENABLE_PIN > -1) SET_OUTPUT(Z_ENABLE_PIN); if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH); #endif #if (E_ENABLE_PIN > -1) SET_OUTPUT(E_ENABLE_PIN); if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH); #endif #ifdef CONTROLLERFAN_PIN SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan #endif #ifdef EXTRUDERFAN_PIN SET_OUTPUT(EXTRUDERFAN_PIN); //Set pin used for extruder cooling fan #endif //endstops and pullups #ifdef ENDSTOPPULLUPS #if X_MIN_PIN > -1 SET_INPUT(X_MIN_PIN); WRITE(X_MIN_PIN,HIGH); #endif #if X_MAX_PIN > -1 SET_INPUT(X_MAX_PIN); WRITE(X_MAX_PIN,HIGH); #endif #if Y_MIN_PIN > -1 SET_INPUT(Y_MIN_PIN); WRITE(Y_MIN_PIN,HIGH); #endif #if Y_MAX_PIN > -1 SET_INPUT(Y_MAX_PIN); WRITE(Y_MAX_PIN,HIGH); #endif #if Z_MIN_PIN > -1 SET_INPUT(Z_MIN_PIN); WRITE(Z_MIN_PIN,HIGH); #endif #if Z_MAX_PIN > -1 SET_INPUT(Z_MAX_PIN); WRITE(Z_MAX_PIN,HIGH); #endif #else #if X_MIN_PIN > -1 SET_INPUT(X_MIN_PIN); #endif #if X_MAX_PIN > -1 SET_INPUT(X_MAX_PIN); #endif #if Y_MIN_PIN > -1 SET_INPUT(Y_MIN_PIN); #endif #if Y_MAX_PIN > -1 SET_INPUT(Y_MAX_PIN); #endif #if Z_MIN_PIN > -1 SET_INPUT(Z_MIN_PIN); #endif #if Z_MAX_PIN > -1 SET_INPUT(Z_MAX_PIN); #endif #endif #if (HEATER_0_PIN > -1) SET_OUTPUT(HEATER_0_PIN); WRITE(HEATER_0_PIN,LOW); #endif #if (HEATER_1_PIN > -1) SET_OUTPUT(HEATER_1_PIN); WRITE(HEATER_1_PIN,LOW); #endif //Initialize Fan Pin #if (FAN_PIN > -1) SET_OUTPUT(FAN_PIN); #endif //Initialize Alarm Pin #if (ALARM_PIN > -1) SET_OUTPUT(ALARM_PIN); WRITE(ALARM_PIN,LOW); #endif //Initialize LED Pin #if (LED_PIN > -1) SET_OUTPUT(LED_PIN); WRITE(LED_PIN,LOW); #endif //Initialize Step Pins #if (X_STEP_PIN > -1) SET_OUTPUT(X_STEP_PIN); #endif #if (Y_STEP_PIN > -1) SET_OUTPUT(Y_STEP_PIN); #endif #if (Z_STEP_PIN > -1) SET_OUTPUT(Z_STEP_PIN); #endif #if (E_STEP_PIN > -1) SET_OUTPUT(E_STEP_PIN); #endif // for(int i=0; i < NUM_AXIS; i++){ // axis_max_interval[i] = 100000000.0 / (max_start_speed_units_per_second[i] * axis_steps_per_unit[i]); // axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; // axis_travel_steps_per_sqr_second[i] = max_travel_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; // } #ifdef HEATER_USES_MAX6675 SET_OUTPUT(SCK_PIN); WRITE(SCK_PIN,0); SET_OUTPUT(MOSI_PIN); WRITE(MOSI_PIN,1); SET_INPUT(MISO_PIN); WRITE(MISO_PIN,1); SET_OUTPUT(MAX6675_SS); WRITE(MAX6675_SS,1); #endif #ifdef SDSUPPORT //power to SD reader #if SDPOWER > -1 SET_OUTPUT(SDPOWER); WRITE(SDPOWER,HIGH); #endif showString(PSTR("SD Start\r\n")); initsd(); #endif #if defined(PID_SOFT_PWM) || (defined(FAN_SOFT_PWM) && (FAN_PIN > -1)) showString(PSTR("Soft PWM Init\r\n")); init_Timer2_softpwm(); #endif showString(PSTR("Planner Init\r\n")); plan_init(); // Initialize planner; showString(PSTR("Stepper Timer init\r\n")); st_init(); // Initialize stepper #ifdef USE_EEPROM_SETTINGS //first Value --> Init with default //second value --> Print settings to UART EEPROM_RetrieveSettings(false,false); #endif #ifdef PIDTEMP updatePID(); #endif //Free Ram showString(PSTR("Free Ram: ")); Serial.println(FreeRam1()); //Planner Buffer Size showString(PSTR("Plan Buffer Size:")); Serial.print((int)sizeof(block_t)*BLOCK_BUFFER_SIZE); showString(PSTR(" / ")); Serial.println(BLOCK_BUFFER_SIZE); for(int8_t i=0; i < NUM_AXIS; i++) { axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; } } //------------------------------------------------ //MAIN LOOP //------------------------------------------------ void loop() { if(buflen < (BUFSIZE-1)) get_command(); if(buflen) { #ifdef SDSUPPORT if(savetosd) { if(strstr(cmdbuffer[bufindr],"M29") == NULL) { write_command(cmdbuffer[bufindr]); showString(PSTR("ok\r\n")); } else { file.sync(); file.close(); savetosd = false; showString(PSTR("Done saving file.\r\n")); } } else { process_commands(); } #else process_commands(); #endif buflen = (buflen-1); //bufindr = (bufindr + 1)%BUFSIZE; //Removed modulo (%) operator, which uses an expensive divide and multiplication bufindr++; if(bufindr == BUFSIZE) bufindr = 0; } //check heater every n milliseconds manage_heater(); manage_inactivity(1); #if (MINIMUM_FAN_START_SPEED > 0) manage_fan_start_speed(); #endif } //------------------------------------------------ //Check Uart buffer while arc function ist calc a circle //------------------------------------------------ void check_buffer_while_arc() { if(buflen < (BUFSIZE-1)) { get_command(); } } //------------------------------------------------ //READ COMMAND FROM UART //------------------------------------------------ void get_command() { while( Serial.available() > 0 && buflen < BUFSIZE) { serial_char = Serial.read(); if(serial_char == '\n' || serial_char == '\r' || (serial_char == ':' && comment_mode == false) || serial_count >= (MAX_CMD_SIZE - 1) ) { if(!serial_count) { //if empty line comment_mode = false; // for new command return; } cmdbuffer[bufindw][serial_count] = 0; //terminate string fromsd[bufindw] = false; if(strstr(cmdbuffer[bufindw], "N") != NULL) { strchr_pointer = strchr(cmdbuffer[bufindw], 'N'); gcode_N = (strtol(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL, 10)); if(gcode_N != gcode_LastN+1 && (strstr(cmdbuffer[bufindw], "M110") == NULL) ) { showString(PSTR("Serial Error: Line Number is not Last Line Number+1, Last Line:")); Serial.println(gcode_LastN); //Serial.println(gcode_N); FlushSerialRequestResend(); serial_count = 0; return; } if(strstr(cmdbuffer[bufindw], "*") != NULL) { byte checksum = 0; byte count = 0; while(cmdbuffer[bufindw][count] != '*') checksum = checksum^cmdbuffer[bufindw][count++]; strchr_pointer = strchr(cmdbuffer[bufindw], '*'); if( (int)(strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)) != checksum) { showString(PSTR("Error: checksum mismatch, Last Line:")); Serial.println(gcode_LastN); FlushSerialRequestResend(); serial_count = 0; return; } //if no errors, continue parsing } else { showString(PSTR("Error: No Checksum with line number, Last Line:")); Serial.println(gcode_LastN); FlushSerialRequestResend(); serial_count = 0; return; } gcode_LastN = gcode_N; //if no errors, continue parsing } else // if we don't receive 'N' but still see '*' { if((strstr(cmdbuffer[bufindw], "*") != NULL)) { showString(PSTR("Error: No Line Number with checksum, Last Line:")); Serial.println(gcode_LastN); serial_count = 0; return; } } if((strstr(cmdbuffer[bufindw], "G") != NULL)) { strchr_pointer = strchr(cmdbuffer[bufindw], 'G'); switch((int)((strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)))) { case 0: case 1: #ifdef USE_ARC_FUNCTION case 2: //G2 case 3: //G3 arc func #endif #ifdef SDSUPPORT if(savetosd) break; #endif showString(PSTR("ok\r\n")); //Serial.println("ok"); break; default: break; } } //Removed modulo (%) operator, which uses an expensive divide and multiplication //bufindw = (bufindw + 1)%BUFSIZE; bufindw++; if(bufindw == BUFSIZE) bufindw = 0; buflen += 1; comment_mode = false; //for new command serial_count = 0; //clear buffer } else { if(serial_char == ';') comment_mode = true; if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char; } } #ifdef SDSUPPORT if(!sdmode || serial_count!=0) { return; } while( filesize > sdpos && buflen < BUFSIZE) { serial_char = file.read(); read_char_int = (int)serial_char; if(serial_char == '\n' || serial_char == '\r' || (serial_char == ':' && comment_mode == false) || serial_count >= (MAX_CMD_SIZE - 1) || read_char_int == -1) { sdpos = file.curPosition(); if(sdpos >= filesize) { sdmode = false; showString(PSTR("Done printing file\r\n")); } if(!serial_count) { //if empty line comment_mode = false; // for new command return; } cmdbuffer[bufindw][serial_count] = 0; //terminate string fromsd[bufindw] = true; buflen += 1; //Removed modulo (%) operator, which uses an expensive divide and multiplication //bufindw = (bufindw + 1)%BUFSIZE; bufindw++; if(bufindw == BUFSIZE) bufindw = 0; comment_mode = false; //for new command serial_count = 0; //clear buffer } else { if(serial_char == ';') comment_mode = true; if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char; } } #endif } static bool check_endstops = true; void enable_endstops(bool check) { check_endstops = check; } FORCE_INLINE float code_value() { return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL)); } FORCE_INLINE long code_value_long() { return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10)); } FORCE_INLINE bool code_seen(char code_string[]) { return (strstr(cmdbuffer[bufindr], code_string) != NULL); } //Return True if the string was found FORCE_INLINE bool code_seen(char code) { strchr_pointer = strchr(cmdbuffer[bufindr], code); return (strchr_pointer != NULL); //Return True if a character was found } FORCE_INLINE void homing_routine(char axis) { int min_pin, max_pin, home_dir, max_length, home_bounce; switch(axis){ case X_AXIS: min_pin = X_MIN_PIN; max_pin = X_MAX_PIN; home_dir = X_HOME_DIR; max_length = X_MAX_LENGTH; home_bounce = 10; break; case Y_AXIS: min_pin = Y_MIN_PIN; max_pin = Y_MAX_PIN; home_dir = Y_HOME_DIR; max_length = Y_MAX_LENGTH; home_bounce = 10; break; case Z_AXIS: min_pin = Z_MIN_PIN; max_pin = Z_MAX_PIN; home_dir = Z_HOME_DIR; max_length = Z_MAX_LENGTH; home_bounce = 4; break; default: //never reached break; } if ((min_pin > -1 && home_dir==-1) || (max_pin > -1 && home_dir==1)) { current_position[axis] = -1.5 * max_length * home_dir; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); destination[axis] = 0; feedrate = homing_feedrate[axis]; prepare_move(); st_synchronize(); current_position[axis] = home_bounce/2 * home_dir; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); destination[axis] = 0; prepare_move(); st_synchronize(); current_position[axis] = -home_bounce * home_dir; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); destination[axis] = 0; feedrate = homing_feedrate[axis]/2; prepare_move(); st_synchronize(); current_position[axis] = (home_dir == -1) ? 0 : max_length; current_position[axis] += add_homing[axis]; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); destination[axis] = current_position[axis]; feedrate = 0; } } //------------------------------------------------ // CHECK COMMAND AND CONVERT VALUES //------------------------------------------------ FORCE_INLINE void process_commands() { unsigned long codenum; //throw away variable char *starpos = NULL; if(code_seen('G')) { switch((int)code_value()) { case 0: // G0 -> G1 case 1: // G1 #if (defined DISABLE_CHECK_DURING_ACC) || (defined DISABLE_CHECK_DURING_MOVE) || (defined DISABLE_CHECK_DURING_TRAVEL) manage_heater(); #endif get_coordinates(); // For X Y Z E F prepare_move(); previous_millis_cmd = millis(); //ClearToSend(); return; //break; #ifdef USE_ARC_FUNCTION case 2: // G2 - CW ARC get_arc_coordinates(); prepare_arc_move(true); previous_millis_cmd = millis(); //break; return; case 3: // G3 - CCW ARC get_arc_coordinates(); prepare_arc_move(false); previous_millis_cmd = millis(); //break; return; #endif case 4: // G4 dwell codenum = 0; if(code_seen('P')) codenum = code_value(); // milliseconds to wait if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait codenum += millis(); // keep track of when we started waiting st_synchronize(); // wait for all movements to finish while(millis() < codenum ){ manage_heater(); } break; case 28: //G28 Home all Axis one at a time saved_feedrate = feedrate; saved_feedmultiply = feedmultiply; previous_millis_cmd = millis(); feedmultiply = 100; enable_endstops(true); for(int i=0; i < NUM_AXIS; i++) { destination[i] = current_position[i]; } feedrate = 0; is_homing = true; home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2]))); if((home_all_axis) || (code_seen(axis_codes[X_AXIS]))) homing_routine(X_AXIS); if((home_all_axis) || (code_seen(axis_codes[Y_AXIS]))) homing_routine(Y_AXIS); if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) homing_routine(Z_AXIS); #ifdef ENDSTOPS_ONLY_FOR_HOMING enable_endstops(false); #endif is_homing = false; feedrate = saved_feedrate; feedmultiply = saved_feedmultiply; previous_millis_cmd = millis(); break; case 90: // G90 relative_mode = false; break; case 91: // G91 relative_mode = true; break; case 92: // G92 if(!code_seen(axis_codes[E_AXIS])) st_synchronize(); for(int i=0; i < NUM_AXIS; i++) { if(code_seen(axis_codes[i])) current_position[i] = code_value(); } plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); break; default: #ifdef SEND_WRONG_CMD_INFO showString(PSTR("Unknown G-COM:")); Serial.println(cmdbuffer[bufindr]); #endif break; } } else if(code_seen('M')) { switch( (int)code_value() ) { #ifdef SDSUPPORT case 20: // M20 - list SD card showString(PSTR("Begin file list\r\n")); root.ls(); showString(PSTR("End file list\r\n")); break; case 21: // M21 - init SD card sdmode = false; initsd(); break; case 22: //M22 - release SD card sdmode = false; sdactive = false; break; case 23: //M23 - Select file if(sdactive) { sdmode = false; file.close(); starpos = (strchr(strchr_pointer + 4,'*')); if(starpos!=NULL) *(starpos-1)='\0'; if (file.open(&root, strchr_pointer + 4, O_READ)) { showString(PSTR("File opened:")); Serial.print(strchr_pointer + 4); showString(PSTR(" Size:")); Serial.println(file.fileSize()); sdpos = 0; filesize = file.fileSize(); showString(PSTR("File selected\r\n")); } else { showString(PSTR("file.open failed\r\n")); } } break; case 24: //M24 - Start SD print if(sdactive) { sdmode = true; } break; case 25: //M25 - Pause SD print if(sdmode) { sdmode = false; } break; case 26: //M26 - Set SD index if(sdactive && code_seen('S')) { sdpos = code_value_long(); file.seekSet(sdpos); } break; case 27: //M27 - Get SD status if(sdactive) { showString(PSTR("SD printing byte ")); Serial.print(sdpos); showString(PSTR("/")); Serial.println(filesize); } else { showString(PSTR("Not SD printing\r\n")); } break; case 28: //M28 - Start SD write if(sdactive) { char* npos = 0; file.close(); sdmode = false; starpos = (strchr(strchr_pointer + 4,'*')); if(starpos != NULL) { npos = strchr(cmdbuffer[bufindr], 'N'); strchr_pointer = strchr(npos,' ') + 1; *(starpos-1) = '\0'; } if (!file.open(&root, strchr_pointer+4, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { showString(PSTR("open failed, File: ")); Serial.print(strchr_pointer + 4); showString(PSTR(".")); } else { savetosd = true; showString(PSTR("Writing to file: ")); Serial.println(strchr_pointer + 4); } } break; case 29: //M29 - Stop SD write //processed in write to file routine above //savetosd = false; break; #ifndef SD_FAST_XFER_AKTIV case 30: // M30 filename - Delete file if(sdactive) { sdmode = false; file.close(); starpos = (strchr(strchr_pointer + 4,'*')); if(starpos!=NULL) *(starpos-1)='\0'; if(file.remove(&root, strchr_pointer + 4)) { showString(PSTR("File deleted\r\n")); } else { showString(PSTR("Deletion failed\r\n")); } } break; #else case 30: //M30 - fast SD transfer fast_xfer(); break; case 31: //M31 - high speed xfer capabilities showString(PSTR("RAW:")); Serial.println(SD_FAST_XFER_CHUNK_SIZE); break; #endif #endif case 42: //M42 -Change pin status via gcode if (code_seen('S')) { #ifdef CHAIN_OF_COMMAND st_synchronize(); // wait for all movements to finish #endif int pin_status = code_value(); if (code_seen('P') && pin_status >= 0 && pin_status <= 255) { int pin_number = code_value(); for(int i = 0; i < sizeof(sensitive_pins) / sizeof(int); i++) { if (sensitive_pins[i] == pin_number) { pin_number = -1; break; } } if (pin_number > -1) { pinMode(pin_number, OUTPUT); digitalWrite(pin_number, pin_status); //analogWrite(pin_number, pin_status); } } } break; case 104: // M104 #ifdef CHAIN_OF_COMMAND st_synchronize(); // wait for all movements to finish #endif if (code_seen('S')) target_raw = temp2analogh(target_temp = code_value()); #ifdef WATCHPERIOD if(target_raw > current_raw) { watchmillis = max(1,millis()); watch_raw = current_raw; } else { watchmillis = 0; } #endif break; case 140: // M140 set bed temp #ifdef CHAIN_OF_COMMAND st_synchronize(); // wait for all movements to finish #endif #if TEMP_1_PIN > -1 || defined BED_USES_AD595 if (code_seen('S')) target_bed_raw = temp2analogBed(code_value()); #endif break; case 105: // M105 #if (TEMP_0_PIN > -1) || defined (HEATER_USES_MAX6675)|| defined HEATER_USES_AD595 hotendtC = analog2temp(current_raw); #endif #if TEMP_1_PIN > -1 || defined BED_USES_AD595 bedtempC = analog2tempBed(current_bed_raw); #endif #if (TEMP_0_PIN > -1) || defined (HEATER_USES_MAX6675) || defined HEATER_USES_AD595 showString(PSTR("ok T:")); Serial.print(hotendtC); #ifdef PIDTEMP showString(PSTR(" @:")); Serial.print(heater_duty); /* showString(PSTR(",P:")); Serial.print(pTerm); showString(PSTR(",I:")); Serial.print(iTerm); showString(PSTR(",D:")); Serial.print(dTerm); */ #ifdef AUTOTEMP showString(PSTR(",AU:")); Serial.print(autotemp_setpoint); #endif #endif #if TEMP_1_PIN > -1 || defined BED_USES_AD595 showString(PSTR(" B:")); Serial.println(bedtempC); #else Serial.println(); #endif #else #error No temperature source available #endif return; //break; case 109: { // M109 - Wait for extruder heater to reach target. #ifdef CHAIN_OF_COMMAND st_synchronize(); // wait for all movements to finish #endif if (code_seen('S')) target_raw = temp2analogh(target_temp = code_value()); #ifdef WATCHPERIOD if(target_raw>current_raw) { watchmillis = max(1,millis()); watch_raw = current_raw; } else { watchmillis = 0; } #endif codenum = millis(); /* See if we are heating up or cooling down */ bool target_direction = (current_raw < target_raw); // true if heating, false if cooling #ifdef TEMP_RESIDENCY_TIME long residencyStart; residencyStart = -1; /* continue to loop until we have reached the target temp _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */ while( (target_direction ? (current_raw < target_raw) : (current_raw > target_raw)) || (residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) { #else while ( target_direction ? (current_raw < target_raw) : (current_raw > target_raw) ) { #endif if( (millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up/cooling down { showString(PSTR("T:")); Serial.println( analog2temp(current_raw) ); codenum = millis(); } manage_heater(); #if (MINIMUM_FAN_START_SPEED > 0) manage_fan_start_speed(); #endif #ifdef TEMP_RESIDENCY_TIME /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time or when current temp falls outside the hysteresis after target temp was reached */ if ( (residencyStart == -1 && target_direction && current_raw >= target_raw) || (residencyStart == -1 && !target_direction && current_raw <= target_raw) || (residencyStart > -1 && labs(analog2temp(current_raw) - analog2temp(target_raw)) > TEMP_HYSTERESIS) ) { residencyStart = millis(); } #endif } } break; case 190: // M190 - Wait for bed heater to reach target temperature. #ifdef CHAIN_OF_COMMAND st_synchronize(); // wait for all movements to finish #endif #if TEMP_1_PIN > -1 if (code_seen('S')) target_bed_raw = temp2analogBed(code_value()); codenum = millis(); while(current_bed_raw < target_bed_raw) { if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up. { hotendtC=analog2temp(current_raw); showString(PSTR("T:")); Serial.print( hotendtC ); showString(PSTR(" B:")); Serial.println( analog2tempBed(current_bed_raw) ); codenum = millis(); } manage_heater(); #if (MINIMUM_FAN_START_SPEED > 0) manage_fan_start_speed(); #endif } #endif break; #if FAN_PIN > -1 case 106: //M106 Fan On #ifdef CHAIN_OF_COMMAND st_synchronize(); // wait for all movements to finish #endif if (code_seen('S')) { unsigned char l_fan_code_val = constrain(code_value(),0,255); #if (MINIMUM_FAN_START_SPEED > 0) if(l_fan_code_val > 0 && fan_last_speed == 0) { if(l_fan_code_val < MINIMUM_FAN_START_SPEED) { fan_org_start_speed = l_fan_code_val; l_fan_code_val = MINIMUM_FAN_START_SPEED; previous_millis_fan_start = millis(); } fan_last_speed = l_fan_code_val; } else { fan_last_speed = l_fan_code_val; fan_org_start_speed = 0; } #endif #if defined(FAN_SOFT_PWM) && (FAN_PIN > -1) g_fan_pwm_val = l_fan_code_val; #else WRITE(FAN_PIN, HIGH); analogWrite_check(FAN_PIN, l_fan_code_val; #endif } else { #if defined(FAN_SOFT_PWM) && (FAN_PIN > -1) g_fan_pwm_val = 255; #else WRITE(FAN_PIN, HIGH); analogWrite_check(FAN_PIN, 255 ); #endif } break; case 107: //M107 Fan Off #if defined(FAN_SOFT_PWM) && (FAN_PIN > -1) g_fan_pwm_val = 0; #else analogWrite_check(FAN_PIN, 0); WRITE(FAN_PIN, LOW); #endif break; #endif #if (PS_ON_PIN > -1) case 80: // M81 - ATX Power On SET_OUTPUT(PS_ON_PIN); //GND break; case 81: // M81 - ATX Power Off #ifdef CHAIN_OF_COMMAND st_synchronize(); // wait for all movements to finish #endif SET_INPUT(PS_ON_PIN); //Floating break; #endif case 82: axis_relative_modes[3] = false; break; case 83: axis_relative_modes[3] = true; break; case 84: st_synchronize(); // wait for all movements to finish if(code_seen('S')) { stepper_inactive_time = code_value() * 1000; } else if(code_seen('T')) { enable_x(); enable_y(); enable_z(); enable_e(); } else { disable_x(); disable_y(); disable_z(); disable_e(); } break; case 85: // M85 code_seen('S'); max_inactive_time = code_value() * 1000; break; case 92: // M92 for(int i=0; i < NUM_AXIS; i++) { if(code_seen(axis_codes[i])) { axis_steps_per_unit[i] = code_value(); axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; } } // Update start speed intervals and axis order. TODO: refactor axis_max_interval[] calculation into a function, as it // should also be used in setup() as well // long temp_max_intervals[NUM_AXIS]; // for(int i=0; i < NUM_AXIS; i++) // { // axis_max_interval[i] = 100000000.0 / (max_start_speed_units_per_second[i] * axis_steps_per_unit[i]);//TODO: do this for // all steps_per_unit related variables // } break; case 93: // M93 show current axis steps. showString(PSTR("ok ")); showString(PSTR("X:")); Serial.print(axis_steps_per_unit[0]); showString(PSTR("Y:")); Serial.print(axis_steps_per_unit[1]); showString(PSTR("Z:")); Serial.print(axis_steps_per_unit[2]); showString(PSTR("E:")); Serial.println(axis_steps_per_unit[3]); break; case 115: // M115 showString(PSTR("FIRMWARE_NAME: Sprinter Experimental PROTOCOL_VERSION:1.0 MACHINE_TYPE:Mendel EXTRUDER_COUNT:1\r\n")); //Serial.println(uuid); showString(PSTR(_DEF_CHAR_UUID)); showString(PSTR("\r\n")); break; case 114: // M114 showString(PSTR("X:")); Serial.print(current_position[0]); showString(PSTR("Y:")); Serial.print(current_position[1]); showString(PSTR("Z:")); Serial.print(current_position[2]); showString(PSTR("E:")); Serial.println(current_position[3]); break; case 119: // M119 #if (X_MIN_PIN > -1) showString(PSTR("x_min:")); Serial.print((READ(X_MIN_PIN)^X_ENDSTOP_INVERT)?"H ":"L "); #endif #if (X_MAX_PIN > -1) showString(PSTR("x_max:")); Serial.print((READ(X_MAX_PIN)^X_ENDSTOP_INVERT)?"H ":"L "); #endif #if (Y_MIN_PIN > -1) showString(PSTR("y_min:")); Serial.print((READ(Y_MIN_PIN)^Y_ENDSTOP_INVERT)?"H ":"L "); #endif #if (Y_MAX_PIN > -1) showString(PSTR("y_max:")); Serial.print((READ(Y_MAX_PIN)^Y_ENDSTOP_INVERT)?"H ":"L "); #endif #if (Z_MIN_PIN > -1) showString(PSTR("z_min:")); Serial.print((READ(Z_MIN_PIN)^Z_ENDSTOP_INVERT)?"H ":"L "); #endif #if (Z_MAX_PIN > -1) showString(PSTR("z_max:")); Serial.print((READ(Z_MAX_PIN)^Z_ENDSTOP_INVERT)?"H ":"L "); #endif showString(PSTR("\r\n")); break; case 201: // M201 Set maximum acceleration in units/s^2 for print moves (M201 X1000 Y1000) for(int8_t i=0; i < NUM_AXIS; i++) { if(code_seen(axis_codes[i])) { max_acceleration_units_per_sq_second[i] = code_value(); axis_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i]; } } break; #if 0 // Not used for Sprinter/grbl gen6 case 202: // M202 for(int i=0; i < NUM_AXIS; i++) { if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i]; } break; #else case 202: // M202 max feedrate mm/sec for(int8_t i=0; i < NUM_AXIS; i++) { if(code_seen(axis_codes[i])) max_feedrate[i] = code_value(); } break; #endif case 203: // M203 Temperature monitor if(code_seen('S')) manage_monitor = code_value(); if(manage_monitor==100) manage_monitor=1; // Set 100 to heated bed break; case 204: // M204 acceleration S normal moves T filmanent only moves if(code_seen('S')) move_acceleration = code_value() ; if(code_seen('T')) retract_acceleration = code_value() ; break; case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E= max E jerk if(code_seen('S')) minimumfeedrate = code_value(); if(code_seen('T')) mintravelfeedrate = code_value(); //if(code_seen('B')) minsegmenttime = code_value() ; if(code_seen('X')) max_xy_jerk = code_value() ; if(code_seen('Z')) max_z_jerk = code_value() ; if(code_seen('E')) max_e_jerk = code_value() ; break; case 206: // M206 additional homing offset if(code_seen('D')) { showString(PSTR("Addhome X:")); Serial.print(add_homing[0]); showString(PSTR(" Y:")); Serial.print(add_homing[1]); showString(PSTR(" Z:")); Serial.println(add_homing[2]); } for(int8_t cnt_i=0; cnt_i < 3; cnt_i++) { if(code_seen(axis_codes[cnt_i])) add_homing[cnt_i] = code_value(); } break; case 220: // M220 S- set speed factor override percentage { if(code_seen('S')) { feedmultiply = code_value() ; feedmultiply = constrain(feedmultiply, 20, 200); feedmultiplychanged=true; } } break; case 221: // M221 S- set extrude factor override percentage { if(code_seen('S')) { extrudemultiply = code_value() ; extrudemultiply = constrain(extrudemultiply, 40, 200); } } break; #ifdef PIDTEMP case 301: // M301 { if(code_seen('P')) PID_Kp = code_value(); if(code_seen('I')) PID_Ki = code_value(); if(code_seen('D')) PID_Kd = code_value(); updatePID(); } break; #endif //PIDTEMP #ifdef PID_AUTOTUNE case 303: // M303 PID autotune { float help_temp = 150.0; if (code_seen('S')) help_temp=code_value(); PID_autotune(help_temp); } break; #endif case 400: // M400 finish all moves { st_synchronize(); } break; #ifdef USE_EEPROM_SETTINGS case 500: // Store settings in EEPROM { EEPROM_StoreSettings(); } break; case 501: // Read settings from EEPROM { EEPROM_RetrieveSettings(false,true); for(int8_t i=0; i < NUM_AXIS; i++) { axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; } } break; case 502: // Revert to default settings { EEPROM_RetrieveSettings(true,true); for(int8_t i=0; i < NUM_AXIS; i++) { axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; } } break; case 503: // print settings currently in memory { EEPROM_printSettings(); } break; #endif #ifdef DEBUG_HEATER_TEMP case 601: // M601 show Extruder Temp jitter #if (TEMP_0_PIN > -1) || defined (HEATER_USES_MAX6675)|| defined HEATER_USES_AD595 if(current_raw_maxval > 0) tt_maxval = analog2temp(current_raw_maxval); if(current_raw_minval < 10000) tt_minval = analog2temp(current_raw_minval); #endif showString(PSTR("Tmin:")); Serial.print(tt_minval); showString(PSTR(" / Tmax:")); Serial.print(tt_maxval); showString(PSTR(" ")); break; case 602: // M602 reset Extruder Temp jitter current_raw_minval = 32000; current_raw_maxval = -32000; showString(PSTR("T Minmax Reset ")); break; #endif case 603: // M603 Free RAM showString(PSTR("Free Ram: ")); Serial.println(FreeRam1()); break; default: #ifdef SEND_WRONG_CMD_INFO showString(PSTR("Unknown M-COM:")); Serial.println(cmdbuffer[bufindr]); #endif break; } } else{ showString(PSTR("Unknown command:\r\n")); Serial.println(cmdbuffer[bufindr]); } ClearToSend(); } void FlushSerialRequestResend() { //char cmdbuffer[bufindr][100]="Resend:"; Serial.flush(); showString(PSTR("Resend:")); Serial.println(gcode_LastN + 1); ClearToSend(); } void ClearToSend() { previous_millis_cmd = millis(); #ifdef SDSUPPORT if(fromsd[bufindr]) return; #endif showString(PSTR("ok\r\n")); //Serial.println("ok"); } FORCE_INLINE void get_coordinates() { for(int i=0; i < NUM_AXIS; i++) { if(code_seen(axis_codes[i])) destination[i] = (float)code_value() + (axis_relative_modes[i] || relative_mode)*current_position[i]; else destination[i] = current_position[i]; //Are these else lines really needed? } if(code_seen('F')) { next_feedrate = code_value(); if(next_feedrate > 0.0) feedrate = next_feedrate; } } #ifdef USE_ARC_FUNCTION void get_arc_coordinates() { get_coordinates(); if(code_seen('I')) { offset[0] = code_value(); } else { offset[0] = 0.0; } if(code_seen('J')) { offset[1] = code_value(); } else { offset[1] = 0.0; } } #endif void prepare_move() { long help_feedrate = 0; if(!is_homing){ if (min_software_endstops) { if (destination[X_AXIS] < 0) destination[X_AXIS] = 0.0; if (destination[Y_AXIS] < 0) destination[Y_AXIS] = 0.0; if (destination[Z_AXIS] < 0) destination[Z_AXIS] = 0.0; } if (max_software_endstops) { if (destination[X_AXIS] > X_MAX_LENGTH) destination[X_AXIS] = X_MAX_LENGTH; if (destination[Y_AXIS] > Y_MAX_LENGTH) destination[Y_AXIS] = Y_MAX_LENGTH; if (destination[Z_AXIS] > Z_MAX_LENGTH) destination[Z_AXIS] = Z_MAX_LENGTH; } } if(destination[E_AXIS] > current_position[E_AXIS]) { help_feedrate = ((long)feedrate*(long)feedmultiply); } else { help_feedrate = ((long)feedrate*(long)100); } plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], help_feedrate/6000.0); for(int i=0; i < NUM_AXIS; i++) { current_position[i] = destination[i]; } } #ifdef USE_ARC_FUNCTION void prepare_arc_move(char isclockwise) { float r = hypot(offset[X_AXIS], offset[Y_AXIS]); // Compute arc radius for mc_arc long help_feedrate = 0; if(destination[E_AXIS] > current_position[E_AXIS]) { help_feedrate = ((long)feedrate*(long)feedmultiply); } else { help_feedrate = ((long)feedrate*(long)100); } // Trace the arc mc_arc(current_position, destination, offset, X_AXIS, Y_AXIS, Z_AXIS, help_feedrate/6000.0, r, isclockwise); // As far as the parser is concerned, the position is now == target. In reality the // motion control system might still be processing the action and the real tool position // in any intermediate location. for(int8_t i=0; i < NUM_AXIS; i++) { current_position[i] = destination[i]; } } #endif FORCE_INLINE void kill() { #if TEMP_0_PIN > -1 target_raw=0; WRITE(HEATER_0_PIN,LOW); #endif #if TEMP_1_PIN > -1 target_bed_raw=0; if(HEATER_1_PIN > -1) WRITE(HEATER_1_PIN,LOW); #endif disable_x(); disable_y(); disable_z(); disable_e(); if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT); } FORCE_INLINE void manage_inactivity(byte debug) { if( (millis()-previous_millis_cmd) > max_inactive_time ) if(max_inactive_time) kill(); if( (millis()-previous_millis_cmd) > stepper_inactive_time ) if(stepper_inactive_time) { disable_x(); disable_y(); disable_z(); disable_e(); } check_axes_activity(); } #if (MINIMUM_FAN_START_SPEED > 0) void manage_fan_start_speed(void) { if(fan_org_start_speed > 0) { if((millis() - previous_millis_fan_start) > MINIMUM_FAN_START_TIME ) { #if FAN_PIN > -1 #if defined(FAN_SOFT_PWM) g_fan_pwm_val = fan_org_start_speed; #else WRITE(FAN_PIN, HIGH); analogWrite_check(FAN_PIN, fan_org_start_speed; #endif #endif fan_org_start_speed = 0; } } } #endif // Planner with Interrupt for Stepper /* Reasoning behind the mathematics in this module (in the key of 'Mathematica'): s == speed, a == acceleration, t == time, d == distance Basic definitions: Speed[s_, a_, t_] := s + (a*t) Travel[s_, a_, t_] := Integrate[Speed[s, a, t], t] Distance to reach a specific speed with a constant acceleration: Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t] d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance() Speed after a given distance of travel with constant acceleration: Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t] m -> Sqrt[2 a d + s^2] DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2] When to start braking (di) to reach a specified destionation speed (s2) after accelerating from initial speed s1 without ever stopping at a plateau: Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di] di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance() IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a) */ static block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instructions static volatile unsigned char block_buffer_head; // Index of the next block to be pushed static volatile unsigned char block_buffer_tail; // Index of the block to process now //=========================================================================== //=============================private variables ============================ //=========================================================================== // Returns the index of the next block in the ring buffer // NOTE: Removed modulo (%) operator, which uses an expensive divide and multiplication. static int8_t next_block_index(int8_t block_index) { block_index++; if (block_index == BLOCK_BUFFER_SIZE) { block_index = 0; } return(block_index); } // Returns the index of the previous block in the ring buffer static int8_t prev_block_index(int8_t block_index) { if (block_index == 0) { block_index = BLOCK_BUFFER_SIZE; } block_index--; return(block_index); } // The current position of the tool in absolute steps static long position[4]; static float previous_speed[4]; // Speed of previous path line segment static float previous_nominal_speed; // Nominal speed of previous path line segment static unsigned char G92_reset_previous_speed = 0; // Calculates the distance (not time) it takes to accelerate from initial_rate to target_rate using the // given acceleration: FORCE_INLINE float estimate_acceleration_distance(float initial_rate, float target_rate, float acceleration) { if (acceleration!=0) { return((target_rate*target_rate-initial_rate*initial_rate)/ (2.0*acceleration)); } else { return 0.0; // acceleration was 0, set acceleration distance to 0 } } // This function gives you the point at which you must start braking (at the rate of -acceleration) if // you started at speed initial_rate and accelerated until this point and want to end at the final_rate after // a total travel of distance. This can be used to compute the intersection point between acceleration and // deceleration in the cases where the trapezoid has no plateau (i.e. never reaches maximum speed) FORCE_INLINE float intersection_distance(float initial_rate, float final_rate, float acceleration, float distance) { if (acceleration!=0) { return((2.0*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/ (4.0*acceleration) ); } else { return 0.0; // acceleration was 0, set intersection distance to 0 } } // Calculates trapezoid parameters so that the entry- and exit-speed is compensated by the provided factors. void calculate_trapezoid_for_block(block_t *block, float entry_factor, float exit_factor) { unsigned long initial_rate = ceil(block->nominal_rate*entry_factor); // (step/min) unsigned long final_rate = ceil(block->nominal_rate*exit_factor); // (step/min) // Limit minimal step rate (Otherwise the timer will overflow.) if(initial_rate <120) {initial_rate=120; } if(final_rate < 120) {final_rate=120; } long acceleration = block->acceleration_st; int32_t accelerate_steps = ceil(estimate_acceleration_distance(block->initial_rate, block->nominal_rate, acceleration)); int32_t decelerate_steps = floor(estimate_acceleration_distance(block->nominal_rate, block->final_rate, -acceleration)); // Calculate the size of Plateau of Nominal Rate. int32_t plateau_steps = block->step_event_count-accelerate_steps-decelerate_steps; // Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will // have to use intersection_distance() to calculate when to abort acceleration and start breaking // in order to reach the final_rate exactly at the end of this block. if (plateau_steps < 0) { accelerate_steps = ceil( intersection_distance(block->initial_rate, block->final_rate, acceleration, block->step_event_count)); accelerate_steps = max(accelerate_steps,0); // Check limits due to numerical round-off accelerate_steps = min(accelerate_steps,block->step_event_count); plateau_steps = 0; } #ifdef ADVANCE volatile long initial_advance = block->advance*entry_factor*entry_factor; volatile long final_advance = block->advance*exit_factor*exit_factor; #endif // ADVANCE // block->accelerate_until = accelerate_steps; // block->decelerate_after = accelerate_steps+plateau_steps; CRITICAL_SECTION_START; // Fill variables used by the stepper in a critical section if(block->busy == false) { // Don't update variables if block is busy. block->accelerate_until = accelerate_steps; block->decelerate_after = accelerate_steps+plateau_steps; block->initial_rate = initial_rate; block->final_rate = final_rate; #ifdef ADVANCE block->initial_advance = initial_advance; block->final_advance = final_advance; #endif //ADVANCE } CRITICAL_SECTION_END; } // Calculates the maximum allowable speed at this point when you must be able to reach target_velocity using the // acceleration within the allotted distance. FORCE_INLINE float max_allowable_speed(float acceleration, float target_velocity, float distance) { return sqrt(target_velocity*target_velocity-2*acceleration*distance); } // "Junction jerk" in this context is the immediate change in speed at the junction of two blocks. // This method will calculate the junction jerk as the euclidean distance between the nominal // velocities of the respective blocks. //inline float junction_jerk(block_t *before, block_t *after) { // return sqrt( // pow((before->speed_x-after->speed_x), 2)+pow((before->speed_y-after->speed_y), 2)); //} // The kernel called by planner_recalculate() when scanning the plan from last to first entry. void planner_reverse_pass_kernel(block_t *previous, block_t *current, block_t *next) { if(!current) { return; } if (next) { // If entry speed is already at the maximum entry speed, no need to recheck. Block is cruising. // If not, block in state of acceleration or deceleration. Reset entry speed to maximum and // check for maximum allowable speed reductions to ensure maximum possible planned speed. if (current->entry_speed != current->max_entry_speed) { // If nominal length true, max junction speed is guaranteed to be reached. Only compute // for max allowable speed if block is decelerating and nominal length is false. if ((!current->nominal_length_flag) && (current->max_entry_speed > next->entry_speed)) { current->entry_speed = min( current->max_entry_speed, max_allowable_speed(-current->acceleration,next->entry_speed,current->millimeters)); } else { current->entry_speed = current->max_entry_speed; } current->recalculate_flag = true; } } // Skip last block. Already initialized and set for recalculation. } // planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This // implements the reverse pass. void planner_reverse_pass() { uint8_t block_index = block_buffer_head; //Make a local copy of block_buffer_tail, because the interrupt can alter it CRITICAL_SECTION_START; unsigned char tail = block_buffer_tail; CRITICAL_SECTION_END; if(((block_buffer_head-tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1)) > 3) { block_index = (block_buffer_head - 3) & (BLOCK_BUFFER_SIZE - 1); block_t *block[3] = { NULL, NULL, NULL }; while(block_index != tail) { block_index = prev_block_index(block_index); block[2]= block[1]; block[1]= block[0]; block[0] = &block_buffer[block_index]; planner_reverse_pass_kernel(block[0], block[1], block[2]); } } } // The kernel called by planner_recalculate() when scanning the plan from first to last entry. void planner_forward_pass_kernel(block_t *previous, block_t *current, block_t *next) { if(!previous) { return; } // If the previous block is an acceleration block, but it is not long enough to complete the // full speed change within the block, we need to adjust the entry speed accordingly. Entry // speeds have already been reset, maximized, and reverse planned by reverse planner. // If nominal length is true, max junction speed is guaranteed to be reached. No need to recheck. if (!previous->nominal_length_flag) { if (previous->entry_speed < current->entry_speed) { double entry_speed = min( current->entry_speed, max_allowable_speed(-previous->acceleration,previous->entry_speed,previous->millimeters) ); // Check for junction speed change if (current->entry_speed != entry_speed) { current->entry_speed = entry_speed; current->recalculate_flag = true; } } } } // planner_recalculate() needs to go over the current plan twice. Once in reverse and once forward. This // implements the forward pass. void planner_forward_pass() { uint8_t block_index = block_buffer_tail; block_t *block[3] = { NULL, NULL, NULL }; while(block_index != block_buffer_head) { block[0] = block[1]; block[1] = block[2]; block[2] = &block_buffer[block_index]; planner_forward_pass_kernel(block[0],block[1],block[2]); block_index = next_block_index(block_index); } planner_forward_pass_kernel(block[1], block[2], NULL); } // Recalculates the trapezoid speed profiles for all blocks in the plan according to the // entry_factor for each junction. Must be called by planner_recalculate() after // updating the blocks. void planner_recalculate_trapezoids() { int8_t block_index = block_buffer_tail; block_t *current; block_t *next = NULL; while(block_index != block_buffer_head) { current = next; next = &block_buffer[block_index]; if (current) { // Recalculate if current block entry or exit junction speed has changed. if (current->recalculate_flag || next->recalculate_flag) { // NOTE: Entry and exit factors always > 0 by all previous logic operations. calculate_trapezoid_for_block(current, current->entry_speed/current->nominal_speed, next->entry_speed/current->nominal_speed); current->recalculate_flag = false; // Reset current only to ensure next trapezoid is computed } } block_index = next_block_index( block_index ); } // Last/newest block in buffer. Exit speed is set with MINIMUM_PLANNER_SPEED. Always recalculated. if(next != NULL) { calculate_trapezoid_for_block(next, next->entry_speed/next->nominal_speed, MINIMUM_PLANNER_SPEED/next->nominal_speed); next->recalculate_flag = false; } } // Recalculates the motion plan according to the following algorithm: // // 1. Go over every block in reverse order and calculate a junction speed reduction (i.e. block_t.entry_factor) // so that: // a. The junction jerk is within the set limit // b. No speed reduction within one block requires faster deceleration than the one, true constant // acceleration. // 2. Go over every block in chronological order and dial down junction speed reduction values if // a. The speed increase within one block would require faster accelleration than the one, true // constant acceleration. // // When these stages are complete all blocks have an entry_factor that will allow all speed changes to // be performed using only the one, true constant acceleration, and where no junction jerk is jerkier than // the set limit. Finally it will: // // 3. Recalculate trapezoids for all blocks. void planner_recalculate() { planner_reverse_pass(); planner_forward_pass(); planner_recalculate_trapezoids(); } void plan_init() { block_buffer_head = 0; block_buffer_tail = 0; memset(position, 0, sizeof(position)); // clear position previous_speed[0] = 0.0; previous_speed[1] = 0.0; previous_speed[2] = 0.0; previous_speed[3] = 0.0; previous_nominal_speed = 0.0; } FORCE_INLINE void plan_discard_current_block() { if (block_buffer_head != block_buffer_tail) { block_buffer_tail = (block_buffer_tail + 1) & BLOCK_BUFFER_MASK; } } FORCE_INLINE block_t *plan_get_current_block() { if (block_buffer_head == block_buffer_tail) { return(NULL); } block_t *block = &block_buffer[block_buffer_tail]; block->busy = true; return(block); } // Gets the current block. Returns NULL if buffer empty FORCE_INLINE bool blocks_queued() { if (block_buffer_head == block_buffer_tail) { return false; } else return true; } void check_axes_activity() { unsigned char x_active = 0; unsigned char y_active = 0; unsigned char z_active = 0; unsigned char e_active = 0; block_t *block; if(block_buffer_tail != block_buffer_head) { uint8_t block_index = block_buffer_tail; while(block_index != block_buffer_head) { block = &block_buffer[block_index]; if(block->steps_x != 0) x_active++; if(block->steps_y != 0) y_active++; if(block->steps_z != 0) z_active++; if(block->steps_e != 0) e_active++; block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1); } } if((DISABLE_X) && (x_active == 0)) disable_x(); if((DISABLE_Y) && (y_active == 0)) disable_y(); if((DISABLE_Z) && (z_active == 0)) disable_z(); if((DISABLE_E) && (e_active == 0)) disable_e(); } float junction_deviation = 0.1; float max_E_feedrate_calc = MAX_RETRACT_FEEDRATE; bool retract_feedrate_aktiv = false; // Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in // mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration // calculation the caller must also provide the physical length of the line in millimeters. void plan_buffer_line(float x, float y, float z, float e, float feed_rate) { // Calculate the buffer head after we push this byte int next_buffer_head = next_block_index(block_buffer_head); // If the buffer is full: good! That means we are well ahead of the robot. // Rest here until there is room in the buffer. while(block_buffer_tail == next_buffer_head) { manage_heater(); manage_inactivity(1); #if (MINIMUM_FAN_START_SPEED > 0) manage_fan_start_speed(); #endif } // The target position of the tool in absolute steps // Calculate target position in absolute steps //this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow long target[4]; target[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]); target[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]); target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]); target[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]); // Prepare to set up new block block_t *block = &block_buffer[block_buffer_head]; // Mark block as not busy (Not executed by the stepper interrupt) block->busy = false; // Number of steps for each axis block->steps_x = labs(target[X_AXIS]-position[X_AXIS]); block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]); block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]); block->steps_e = labs(target[E_AXIS]-position[E_AXIS]); block->steps_e *= extrudemultiply; block->steps_e /= 100; block->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, block->steps_e))); // Bail if this is a zero-length block if (block->step_event_count <=dropsegments) { return; }; // Compute direction bits for this block block->direction_bits = 0; if (target[X_AXIS] < position[X_AXIS]) { block->direction_bits |= (1<direction_bits |= (1<direction_bits |= (1<direction_bits |= (1<steps_e > 0) retract_feedrate_aktiv = false; } else { max_E_feedrate_calc = max_feedrate[E_AXIS]; } } #ifdef DELAY_ENABLE if(block->steps_x != 0) { enable_x(); delayMicroseconds(DELAY_ENABLE); } if(block->steps_y != 0) { enable_y(); delayMicroseconds(DELAY_ENABLE); } if(block->steps_z != 0) { enable_z(); delayMicroseconds(DELAY_ENABLE); } if(block->steps_e != 0) { enable_e(); delayMicroseconds(DELAY_ENABLE); } #else //enable active axes if(block->steps_x != 0) enable_x(); if(block->steps_y != 0) enable_y(); if(block->steps_z != 0) enable_z(); if(block->steps_e != 0) enable_e(); #endif if (block->steps_e == 0) { if(feed_rate 1) feed_rate = feed_rate*moves_queued / (BLOCK_BUFFER_SIZE * 0.5); #endif float delta_mm[4]; delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS]; delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]; delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS]; //delta_mm[E_AXIS] = (target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS]; delta_mm[E_AXIS] = ((target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS])*extrudemultiply/100.0; if ( block->steps_x <= dropsegments && block->steps_y <= dropsegments && block->steps_z <= dropsegments ) { block->millimeters = fabs(delta_mm[E_AXIS]); } else { block->millimeters = sqrt(square(delta_mm[X_AXIS]) + square(delta_mm[Y_AXIS]) + square(delta_mm[Z_AXIS])); } float inverse_millimeters = 1.0/block->millimeters; // Inverse millimeters to remove multiple divides // Calculate speed in mm/second for each axis. No divide by zero due to previous checks. float inverse_second = feed_rate * inverse_millimeters; block->nominal_speed = block->millimeters * inverse_second; // (mm/sec) Always > 0 block->nominal_rate = ceil(block->step_event_count * inverse_second); // (step/sec) Always > 0 /* // segment time im micro seconds long segment_time = lround(1000000.0/inverse_second); if ((blockcount>0) && (blockcount < (BLOCK_BUFFER_SIZE - 4))) { if (segment_time max_feedrate[i]) speed_factor = min(speed_factor, max_feedrate[i] / fabs(current_speed[i])); } current_speed[E_AXIS] = delta_mm[E_AXIS] * inverse_second; if(fabs(current_speed[E_AXIS]) > max_E_feedrate_calc) speed_factor = min(speed_factor, max_E_feedrate_calc / fabs(current_speed[E_AXIS])); // Correct the speed if( speed_factor < 1.0) { for(unsigned char i=0; i < 4; i++) { current_speed[i] *= speed_factor; } block->nominal_speed *= speed_factor; block->nominal_rate *= speed_factor; } // Compute and limit the acceleration rate for the trapezoid generator. float steps_per_mm = block->step_event_count/block->millimeters; if(block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0) { block->acceleration_st = ceil(retract_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2 } else { block->acceleration_st = ceil(move_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2 // Limit acceleration per axis if(((float)block->acceleration_st * (float)block->steps_x / (float)block->step_event_count) > axis_steps_per_sqr_second[X_AXIS]) block->acceleration_st = axis_steps_per_sqr_second[X_AXIS]; if(((float)block->acceleration_st * (float)block->steps_y / (float)block->step_event_count) > axis_steps_per_sqr_second[Y_AXIS]) block->acceleration_st = axis_steps_per_sqr_second[Y_AXIS]; if(((float)block->acceleration_st * (float)block->steps_e / (float)block->step_event_count) > axis_steps_per_sqr_second[E_AXIS]) block->acceleration_st = axis_steps_per_sqr_second[E_AXIS]; if(((float)block->acceleration_st * (float)block->steps_z / (float)block->step_event_count ) > axis_steps_per_sqr_second[Z_AXIS]) block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS]; } block->acceleration = block->acceleration_st / steps_per_mm; block->acceleration_rate = (long)((float)block->acceleration_st * 8.388608); #if 0 // Use old jerk for now // Compute path unit vector double unit_vec[3]; unit_vec[X_AXIS] = delta_mm[X_AXIS]*inverse_millimeters; unit_vec[Y_AXIS] = delta_mm[Y_AXIS]*inverse_millimeters; unit_vec[Z_AXIS] = delta_mm[Z_AXIS]*inverse_millimeters; // Compute maximum allowable entry speed at junction by centripetal acceleration approximation. // Let a circle be tangent to both previous and current path line segments, where the junction // deviation is defined as the distance from the junction to the closest edge of the circle, // colinear with the circle center. The circular segment joining the two paths represents the // path of centripetal acceleration. Solve for max velocity based on max acceleration about the // radius of the circle, defined indirectly by junction deviation. This may be also viewed as // path width or max_jerk in the previous grbl version. This approach does not actually deviate // from path, but used as a robust way to compute cornering speeds, as it takes into account the // nonlinearities of both the junction angle and junction velocity. double vmax_junction = MINIMUM_PLANNER_SPEED; // Set default max junction speed // Skip first block or when previous_nominal_speed is used as a flag for homing and offset cycles. if ((block_buffer_head != block_buffer_tail) && (previous_nominal_speed > 0.0)) { // Compute cosine of angle between previous and current path. (prev_unit_vec is negative) // NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity. double cos_theta = - previous_unit_vec[X_AXIS] * unit_vec[X_AXIS] - previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS] - previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] ; // Skip and use default max junction speed for 0 degree acute junction. if (cos_theta < 0.95) { vmax_junction = min(previous_nominal_speed,block->nominal_speed); // Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds. if (cos_theta > -0.95) { // Compute maximum junction velocity based on maximum acceleration and junction deviation double sin_theta_d2 = sqrt(0.5*(1.0-cos_theta)); // Trig half angle identity. Always positive. vmax_junction = min(vmax_junction, sqrt(block->acceleration * junction_deviation * sin_theta_d2/(1.0-sin_theta_d2)) ); } } } #endif // Start with a safe speed float vmax_junction = max_xy_jerk/2; float vmax_junction_factor = 1.0; if(fabs(current_speed[Z_AXIS]) > max_z_jerk/2) vmax_junction = min(vmax_junction, max_z_jerk/2); if(fabs(current_speed[E_AXIS]) > max_e_jerk/2) vmax_junction = min(vmax_junction, max_e_jerk/2); if(G92_reset_previous_speed == 1) { vmax_junction = 0.1; G92_reset_previous_speed = 0; } vmax_junction = min(vmax_junction, block->nominal_speed); float safe_speed = vmax_junction; if ((moves_queued > 1) && (previous_nominal_speed > 0.0001)) { float jerk = sqrt(pow((current_speed[X_AXIS]-previous_speed[X_AXIS]), 2)+pow((current_speed[Y_AXIS]-previous_speed[Y_AXIS]), 2)); // if((fabs(previous_speed[X_AXIS]) > 0.0001) || (fabs(previous_speed[Y_AXIS]) > 0.0001)) { vmax_junction = block->nominal_speed; // } if (jerk > max_xy_jerk) { vmax_junction_factor = (max_xy_jerk/jerk); } if(fabs(current_speed[Z_AXIS] - previous_speed[Z_AXIS]) > max_z_jerk) { vmax_junction_factor= min(vmax_junction_factor, (max_z_jerk/fabs(current_speed[Z_AXIS] - previous_speed[Z_AXIS]))); } if(fabs(current_speed[E_AXIS] - previous_speed[E_AXIS]) > max_e_jerk) { vmax_junction_factor = min(vmax_junction_factor, (max_e_jerk/fabs(current_speed[E_AXIS] - previous_speed[E_AXIS]))); } vmax_junction = min(previous_nominal_speed, vmax_junction * vmax_junction_factor); // Limit speed to max previous speed } block->max_entry_speed = vmax_junction; // Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED. double v_allowable = max_allowable_speed(-block->acceleration,MINIMUM_PLANNER_SPEED,block->millimeters); block->entry_speed = min(vmax_junction, v_allowable); // Initialize planner efficiency flags // Set flag if block will always reach maximum junction speed regardless of entry/exit speeds. // If a block can de/ac-celerate from nominal speed to zero within the length of the block, then // the current block and next block junction speeds are guaranteed to always be at their maximum // junction speeds in deceleration and acceleration, respectively. This is due to how the current // block nominal speed limits both the current and next maximum junction speeds. Hence, in both // the reverse and forward planners, the corresponding block junction speed will always be at the // the maximum junction speed and may always be ignored for any speed reduction checks. if (block->nominal_speed <= v_allowable) { block->nominal_length_flag = true; } else { block->nominal_length_flag = false; } block->recalculate_flag = true; // Always calculate trapezoid for new block // Update previous path unit_vector and nominal speed memcpy(previous_speed, current_speed, sizeof(previous_speed)); // previous_speed[] = current_speed[] previous_nominal_speed = block->nominal_speed; #ifdef ADVANCE // Calculate advance rate if((block->steps_e == 0) || (block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0)) { block->advance_rate = 0; block->advance = 0; } else { long acc_dist = estimate_acceleration_distance(0, block->nominal_rate, block->acceleration_st); float advance = (STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K) * (current_speed[E_AXIS] * current_speed[E_AXIS] * EXTRUTION_AREA * EXTRUTION_AREA)*256; block->advance = advance; if(acc_dist == 0) { block->advance_rate = 0; } else { block->advance_rate = advance / (float)acc_dist; } } #endif // ADVANCE calculate_trapezoid_for_block(block, block->entry_speed/block->nominal_speed, safe_speed/block->nominal_speed); // Move buffer head block_buffer_head = next_buffer_head; // Update position memcpy(position, target, sizeof(target)); // position[] = target[] planner_recalculate(); #ifdef AUTOTEMP getHighESpeed(); #endif st_wake_up(); } int calc_plannerpuffer_fill(void) { int moves_queued=(block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1); return(moves_queued); } void plan_set_position(float x, float y, float z, float e) { position[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]); position[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]); position[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]); position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]); virtual_steps_x = 0; virtual_steps_y = 0; virtual_steps_z = 0; previous_nominal_speed = 0.0; // Resets planner junction speeds. Assumes start from rest. previous_speed[0] = 0.0; previous_speed[1] = 0.0; previous_speed[2] = 0.0; previous_speed[3] = 0.0; G92_reset_previous_speed = 1; } #ifdef AUTOTEMP void getHighESpeed() { static float oldt=0; if(!autotemp_enabled) return; if((target_temp+2) < autotemp_min) //probably temperature set to zero. return; //do nothing float high=0.0; uint8_t block_index = block_buffer_tail; while(block_index != block_buffer_head) { if((block_buffer[block_index].steps_x != 0) || (block_buffer[block_index].steps_y != 0) || (block_buffer[block_index].steps_z != 0)) { float se=(float(block_buffer[block_index].steps_e)/float(block_buffer[block_index].step_event_count))*block_buffer[block_index].nominal_speed; //se; units steps/sec; if(se>high) { high=se; } } block_index = (block_index+1) & (BLOCK_BUFFER_SIZE - 1); } float t=autotemp_min+high*autotemp_factor; if(tautotemp_max) t=autotemp_max; if(oldt>t) { t=AUTOTEMP_OLDWEIGHT*oldt+(1-AUTOTEMP_OLDWEIGHT)*t; } oldt=t; autotemp_setpoint = (int)t; } #endif // Stepper // intRes = intIn1 * intIn2 >> 16 // uses: // r26 to store 0 // r27 to store the byte 1 of the 24 bit result #define MultiU16X8toH16(intRes, charIn1, intIn2) \ asm volatile ( \ "clr r26 \n\t" \ "mul %A1, %B2 \n\t" \ "movw %A0, r0 \n\t" \ "mul %A1, %A2 \n\t" \ "add %A0, r1 \n\t" \ "adc %B0, r26 \n\t" \ "lsr r0 \n\t" \ "adc %A0, r26 \n\t" \ "adc %B0, r26 \n\t" \ "clr r1 \n\t" \ : \ "=&r" (intRes) \ : \ "d" (charIn1), \ "d" (intIn2) \ : \ "r26" \ ) // intRes = longIn1 * longIn2 >> 24 // uses: // r26 to store 0 // r27 to store the byte 1 of the 48bit result #define MultiU24X24toH16(intRes, longIn1, longIn2) \ asm volatile ( \ "clr r26 \n\t" \ "mul %A1, %B2 \n\t" \ "mov r27, r1 \n\t" \ "mul %B1, %C2 \n\t" \ "movw %A0, r0 \n\t" \ "mul %C1, %C2 \n\t" \ "add %B0, r0 \n\t" \ "mul %C1, %B2 \n\t" \ "add %A0, r0 \n\t" \ "adc %B0, r1 \n\t" \ "mul %A1, %C2 \n\t" \ "add r27, r0 \n\t" \ "adc %A0, r1 \n\t" \ "adc %B0, r26 \n\t" \ "mul %B1, %B2 \n\t" \ "add r27, r0 \n\t" \ "adc %A0, r1 \n\t" \ "adc %B0, r26 \n\t" \ "mul %C1, %A2 \n\t" \ "add r27, r0 \n\t" \ "adc %A0, r1 \n\t" \ "adc %B0, r26 \n\t" \ "mul %B1, %A2 \n\t" \ "add r27, r1 \n\t" \ "adc %A0, r26 \n\t" \ "adc %B0, r26 \n\t" \ "lsr r27 \n\t" \ "adc %A0, r26 \n\t" \ "adc %B0, r26 \n\t" \ "clr r1 \n\t" \ : \ "=&r" (intRes) \ : \ "d" (longIn1), \ "d" (longIn2) \ : \ "r26" , "r27" \ ) // Some useful constants #define ENABLE_STEPPER_DRIVER_INTERRUPT() TIMSK1 |= (1< // // The trapezoid is the shape of the speed curve over time. It starts at block->initial_rate, accelerates // first block->accelerate_until step_events_completed, then keeps going at constant speed until // step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset. // The slope of acceleration is calculated with the leib ramp alghorithm. void st_wake_up() { // TCNT1 = 0; if(busy == false) ENABLE_STEPPER_DRIVER_INTERRUPT(); } FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) { unsigned short timer; if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY; if(step_rate > 20000) { // If steprate > 20kHz >> step 4 times step_rate = (step_rate >> 2)&0x3fff; step_loops = 4; } else if(step_rate > 10000) { // If steprate > 10kHz >> step 2 times step_rate = (step_rate >> 1)&0x7fff; step_loops = 2; } else { step_loops = 1; } if(step_rate < (F_CPU/500000)) step_rate = (F_CPU/500000); step_rate -= (F_CPU/500000); // Correct for minimal speed if(step_rate >= (8*256)) // higher step rate { // higher step rate unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0]; unsigned char tmp_step_rate = (step_rate & 0x00ff); unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2); MultiU16X8toH16(timer, tmp_step_rate, gain); timer = (unsigned short)pgm_read_word_near(table_address) - timer; } else { // lower step rates unsigned short table_address = (unsigned short)&speed_lookuptable_slow[0][0]; table_address += ((step_rate)>>1) & 0xfffc; timer = (unsigned short)pgm_read_word_near(table_address); timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3); } if(timer < 100) { timer = 100; }//(20kHz this should never happen) return timer; } // Initializes the trapezoid generator from the current block. Called whenever a new // block begins. FORCE_INLINE void trapezoid_generator_reset() { #ifdef ADVANCE advance = current_block->initial_advance; final_advance = current_block->final_advance; // Do E steps + advance steps e_steps += ((advance >>8) - old_advance); old_advance = advance >>8; #endif deceleration_time = 0; // step_rate to timer interval acc_step_rate = current_block->initial_rate; acceleration_time = calc_timer(acc_step_rate); OCR1A = acceleration_time; OCR1A_nominal = calc_timer(current_block->nominal_rate); } // "The Stepper Driver Interrupt" - This timer interrupt is the workhorse. // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. ISR(TIMER1_COMPA_vect) { // If there is no current block, attempt to pop one from the buffer if (current_block == NULL) { // Anything in the buffer? current_block = plan_get_current_block(); if (current_block != NULL) { trapezoid_generator_reset(); counter_x = -(current_block->step_event_count >> 1); counter_y = counter_x; counter_z = counter_x; counter_e = counter_x; step_events_completed = 0; // #ifdef ADVANCE // e_steps = 0; // #endif } else { OCR1A=2000; // 1kHz. } } if (current_block != NULL) { // Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt out_bits = current_block->direction_bits; // Set direction and check limit switches if ((out_bits & (1< -1 bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOP_INVERT); if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) { if(!is_homing) endstop_x_hit=true; else step_events_completed = current_block->step_event_count; } else { endstop_x_hit=false; } old_x_min_endstop = x_min_endstop; #else endstop_x_hit=false; #endif } } else { // +direction WRITE(X_DIR_PIN,!INVERT_X_DIR); CHECK_ENDSTOPS { #if X_MAX_PIN > -1 bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOP_INVERT); if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){ if(!is_homing) endstop_x_hit=true; else step_events_completed = current_block->step_event_count; } else { endstop_x_hit=false; } old_x_max_endstop = x_max_endstop; #else endstop_x_hit=false; #endif } } if ((out_bits & (1< -1 bool y_min_endstop=(READ(Y_MIN_PIN) != Y_ENDSTOP_INVERT); if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) { if(!is_homing) endstop_y_hit=true; else step_events_completed = current_block->step_event_count; } else { endstop_y_hit=false; } old_y_min_endstop = y_min_endstop; #else endstop_y_hit=false; #endif } } else { // +direction WRITE(Y_DIR_PIN,!INVERT_Y_DIR); CHECK_ENDSTOPS { #if Y_MAX_PIN > -1 bool y_max_endstop=(READ(Y_MAX_PIN) != Y_ENDSTOP_INVERT); if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){ if(!is_homing) endstop_y_hit=true; else step_events_completed = current_block->step_event_count; } else { endstop_y_hit=false; } old_y_max_endstop = y_max_endstop; #else endstop_y_hit=false; #endif } } if ((out_bits & (1< -1 bool z_min_endstop=(READ(Z_MIN_PIN) != Z_ENDSTOP_INVERT); if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) { if(!is_homing) endstop_z_hit=true; else step_events_completed = current_block->step_event_count; } else { endstop_z_hit=false; } old_z_min_endstop = z_min_endstop; #else endstop_z_hit=false; #endif } } else { // +direction WRITE(Z_DIR_PIN,!INVERT_Z_DIR); CHECK_ENDSTOPS { #if Z_MAX_PIN > -1 bool z_max_endstop=(READ(Z_MAX_PIN) != Z_ENDSTOP_INVERT); if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) { if(!is_homing) endstop_z_hit=true; else step_events_completed = current_block->step_event_count; } else { endstop_z_hit=false; } old_z_max_endstop = z_max_endstop; #else endstop_z_hit=false; #endif } } #ifndef ADVANCE if ((out_bits & (1<steps_e; if (counter_e > 0) { counter_e -= current_block->step_event_count; if ((out_bits & (1<steps_x; if (counter_x > 0) { if(!endstop_x_hit) { if(virtual_steps_x) virtual_steps_x--; else WRITE(X_STEP_PIN, HIGH); } else virtual_steps_x++; counter_x -= current_block->step_event_count; WRITE(X_STEP_PIN, LOW); } counter_y += current_block->steps_y; if (counter_y > 0) { if(!endstop_y_hit) { if(virtual_steps_y) virtual_steps_y--; else WRITE(Y_STEP_PIN, HIGH); } else virtual_steps_y++; counter_y -= current_block->step_event_count; WRITE(Y_STEP_PIN, LOW); } counter_z += current_block->steps_z; if (counter_z > 0) { if(!endstop_z_hit) { if(virtual_steps_z) virtual_steps_z--; else WRITE(Z_STEP_PIN, HIGH); } else virtual_steps_z++; counter_z -= current_block->step_event_count; WRITE(Z_STEP_PIN, LOW); } #ifndef ADVANCE counter_e += current_block->steps_e; if (counter_e > 0) { WRITE(E_STEP_PIN, HIGH); counter_e -= current_block->step_event_count; WRITE(E_STEP_PIN, LOW); } #endif //!ADVANCE step_events_completed += 1; if(step_events_completed >= current_block->step_event_count) break; } // Calculare new timer value unsigned short timer; unsigned short step_rate; if (step_events_completed <= (unsigned long int)current_block->accelerate_until) { MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate); acc_step_rate += current_block->initial_rate; // upper limit if(acc_step_rate > current_block->nominal_rate) acc_step_rate = current_block->nominal_rate; // step_rate to timer interval timer = calc_timer(acc_step_rate); OCR1A = timer; acceleration_time += timer; #ifdef ADVANCE for(int8_t i=0; i < step_loops; i++) { advance += advance_rate; } //if(advance > current_block->advance) advance = current_block->advance; // Do E steps + advance steps e_steps += ((advance >>8) - old_advance); old_advance = advance >>8; #endif } else if (step_events_completed > (unsigned long int)current_block->decelerate_after) { MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate); if(step_rate > acc_step_rate) { // Check step_rate stays positive step_rate = current_block->final_rate; } else { step_rate = acc_step_rate - step_rate; // Decelerate from aceleration end point. } // lower limit if(step_rate < current_block->final_rate) step_rate = current_block->final_rate; // step_rate to timer interval timer = calc_timer(step_rate); OCR1A = timer; deceleration_time += timer; #ifdef ADVANCE for(int8_t i=0; i < step_loops; i++) { advance -= advance_rate; } if(advance < final_advance) advance = final_advance; // Do E steps + advance steps e_steps += ((advance >>8) - old_advance); old_advance = advance >>8; #endif //ADVANCE } else { OCR1A = OCR1A_nominal; } // If current block is finished, reset pointer if (step_events_completed >= current_block->step_event_count) { current_block = NULL; plan_discard_current_block(); } } } #ifdef ADVANCE unsigned char old_OCR0A; // Timer interrupt for E. e_steps is set in the main routine; // Timer 0 is shared with millies ISR(TIMER0_COMPA_vect) { old_OCR0A += 52; // ~10kHz interrupt (250000 / 26 = 9615kHz) OCR0A = old_OCR0A; // Set E direction (Depends on E direction + advance) for(unsigned char i=0; i<4;i++) { if (e_steps != 0) { WRITE(E0_STEP_PIN, LOW); if (e_steps < 0) { WRITE(E0_DIR_PIN, INVERT_E0_DIR); e_steps++; WRITE(E0_STEP_PIN, HIGH); } else if (e_steps > 0) { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); e_steps--; WRITE(E0_STEP_PIN, HIGH); } } } } #endif // ADVANCE void st_init() { // waveform generation = 0100 = CTC TCCR1B &= ~(1< 0) manage_fan_start_speed(); #endif } } #ifdef DEBUG void log_message(char* message) { Serial.print("DEBUG"); Serial.println(message); } void log_bool(char* message, bool value) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value); } void log_int(char* message, int value) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value); } void log_long(char* message, long value) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value); } void log_float(char* message, float value) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value); } void log_uint(char* message, unsigned int value) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value); } void log_ulong(char* message, unsigned long value) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": "); Serial.println(value); } void log_int_array(char* message, int value[], int array_lenght) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": {"); for(int i=0; i < array_lenght; i++){ Serial.print(value[i]); if(i != array_lenght-1) Serial.print(", "); } Serial.println("}"); } void log_long_array(char* message, long value[], int array_lenght) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": {"); for(int i=0; i < array_lenght; i++){ Serial.print(value[i]); if(i != array_lenght-1) Serial.print(", "); } Serial.println("}"); } void log_float_array(char* message, float value[], int array_lenght) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": {"); for(int i=0; i < array_lenght; i++){ Serial.print(value[i]); if(i != array_lenght-1) Serial.print(", "); } Serial.println("}"); } void log_uint_array(char* message, unsigned int value[], int array_lenght) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": {"); for(int i=0; i < array_lenght; i++){ Serial.print(value[i]); if(i != array_lenght-1) Serial.print(", "); } Serial.println("}"); } void log_ulong_array(char* message, unsigned long value[], int array_lenght) { Serial.print("DEBUG"); Serial.print(message); Serial.print(": {"); for(int i=0; i < array_lenght; i++){ Serial.print(value[i]); if(i != array_lenght-1) Serial.print(", "); } Serial.println("}"); } #endif ================================================ FILE: Sprinter/arc_func.cpp ================================================ /* arc_func.c - high level interface for issuing motion commands Part of Grbl Copyright (c) 2009-2011 Simen Svale Skogsrud Copyright (c) 2011 Sungeun K. Jeon Grbl is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. Grbl is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with Grbl. If not, see . */ #include #include #include "Configuration.h" #include "Sprinter.h" #ifdef USE_ARC_FUNCTION // The arc is approximated by generating a huge number of tiny, linear segments. The length of each // segment is configured in settings.mm_per_arc_segment. void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, float feed_rate, float radius, uint8_t isclockwise) { // int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled(); // plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc float center_axis0 = position[axis_0] + offset[axis_0]; float center_axis1 = position[axis_1] + offset[axis_1]; float linear_travel = target[axis_linear] - position[axis_linear]; float extruder_travel = target[E_AXIS] - position[E_AXIS]; float r_axis0 = -offset[axis_0]; // Radius vector from center to current location float r_axis1 = -offset[axis_1]; float rt_axis0 = target[axis_0] - center_axis0; float rt_axis1 = target[axis_1] - center_axis1; // CCW angle between position and target from circle center. Only one atan2() trig computation required. float angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1); if (angular_travel < 0) { angular_travel += 2*M_PI; } if (isclockwise) { angular_travel -= 2*M_PI; } float millimeters_of_travel = hypot(angular_travel*radius, fabs(linear_travel)); if (millimeters_of_travel < 0.001) { return; } uint16_t segments = floor(millimeters_of_travel/MM_PER_ARC_SEGMENT); if(segments == 0) segments = 1; /* // Multiply inverse feed_rate to compensate for the fact that this movement is approximated // by a number of discrete segments. The inverse feed_rate should be correct for the sum of // all segments. if (invert_feed_rate) { feed_rate *= segments; } */ float theta_per_segment = angular_travel/segments; float linear_per_segment = linear_travel/segments; float extruder_per_segment = extruder_travel/segments; /* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, and phi is the angle of rotation. Based on the solution approach by Jens Geisler. r_T = [cos(phi) -sin(phi); sin(phi) cos(phi] * r ; For arc generation, the center of the circle is the axis of rotation and the radius vector is defined from the circle center to the initial position. Each line segment is formed by successive vector rotations. This requires only two cos() and sin() computations to form the rotation matrix for the duration of the entire arc. Error may accumulate from numerical round-off, since all double numbers are single precision on the Arduino. (True double precision will not have round off issues for CNC applications.) Single precision error can accumulate to be greater than tool precision in some cases. Therefore, arc path correction is implemented. Small angle approximation may be used to reduce computation overhead further. This approximation holds for everything, but very small circles and large mm_per_arc_segment values. In other words, theta_per_segment would need to be greater than 0.1 rad and N_ARC_CORRECTION would need to be large to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for numerical drift error. N_ARC_CORRECTION may be on the order a hundred(s) before error becomes an issue for CNC machines with the single precision Arduino calculations. This approximation also allows mc_arc to immediately insert a line segment into the planner without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied a correction, the planner should have caught up to the lag caused by the initial mc_arc overhead. This is important when there are successive arc motions. */ // Vector rotation matrix values float cos_T = 1-0.5*theta_per_segment*theta_per_segment; // Small angle approximation float sin_T = theta_per_segment; float arc_target[4]; float sin_Ti; float cos_Ti; float r_axisi; uint16_t i; int8_t count = 0; // Initialize the linear axis arc_target[axis_linear] = position[axis_linear]; // Initialize the extruder axis arc_target[E_AXIS] = position[E_AXIS]; for (i = 1; i. */ #ifndef arc_func_h #define arc_func_h // Execute an arc in offset mode format. position == current xyz, target == target xyz, // offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is // the direction of helical travel, radius == circle radius, isclockwise boolean. Used // for vector transformation direction. void mc_arc(float *position, float *target, float *offset, unsigned char axis_0, unsigned char axis_1, unsigned char axis_linear, float feed_rate, float radius, unsigned char isclockwise); #endif ================================================ FILE: Sprinter/createTemperatureLookup.py ================================================ #!/usr/bin/python # # Creates a C code lookup table for doing ADC to temperature conversion # on a microcontroller # based on: http://hydraraptor.blogspot.com/2007/10/measuring-temperature-easy-way.html """Thermistor Value Lookup Table Generator Generates lookup to temperature values for use in a microcontroller in C format based on: http://hydraraptor.blogspot.com/2007/10/measuring-temperature-easy-way.html The main use is for Arduino programs that read data from the circuit board described here: http://make.rrrf.org/ts-1.0 Usage: python createTemperatureLookup.py [options] Options: -h, --help show this help --r0=... thermistor rating where # is the ohm rating of the thermistor at t0 (eg: 10K = 10000) --t0=... thermistor temp rating where # is the temperature in Celsuis to get r0 (from your datasheet) --beta=... thermistor beta rating. see http://reprap.org/bin/view/Main/MeasuringThermistorBeta --r1=... R1 rating where # is the ohm rating of R1 (eg: 10K = 10000) --r2=... R2 rating where # is the ohm rating of R2 (eg: 10K = 10000) --num-temps=... the number of temperature points to calculate (default: 20) --max-adc=... the max ADC reading to use. if you use R1, it limits the top value for the thermistor circuit, and thus the possible range of ADC values """ from math import * import sys import getopt class Thermistor: "Class to do the thermistor maths" def __init__(self, r0, t0, beta, r1, r2): self.r0 = r0 # stated resistance, e.g. 10K self.t0 = t0 + 273.15 # temperature at stated resistance, e.g. 25C self.beta = beta # stated beta, e.g. 3500 self.vadc = 5.0 # ADC reference self.vcc = 5.0 # supply voltage to potential divider self.k = r0 * exp(-beta / self.t0) # constant part of calculation if r1 > 0: self.vs = r1 * self.vcc / (r1 + r2) # effective bias voltage self.rs = r1 * r2 / (r1 + r2) # effective bias impedance else: self.vs = self.vcc # effective bias voltage self.rs = r2 # effective bias impedance def temp(self,adc): "Convert ADC reading into a temperature in Celcius" v = adc * self.vadc / 1024 # convert the 10 bit ADC value to a voltage r = self.rs * v / (self.vs - v) # resistance of thermistor return (self.beta / log(r / self.k)) - 273.15 # temperature def setting(self, t): "Convert a temperature into a ADC value" r = self.r0 * exp(self.beta * (1 / (t + 273.15) - 1 / self.t0)) # resistance of the thermistor v = self.vs * r / (self.rs + r) # the voltage at the potential divider return round(v / self.vadc * 1024) # the ADC reading def main(argv): r0 = 10000; t0 = 25; beta = 3947; r1 = 680; r2 = 1600; num_temps = int(20); try: opts, args = getopt.getopt(argv, "h", ["help", "r0=", "t0=", "beta=", "r1=", "r2="]) except getopt.GetoptError: usage() sys.exit(2) for opt, arg in opts: if opt in ("-h", "--help"): usage() sys.exit() elif opt == "--r0": r0 = int(arg) elif opt == "--t0": t0 = int(arg) elif opt == "--beta": beta = int(arg) elif opt == "--r1": r1 = int(arg) elif opt == "--r2": r2 = int(arg) if r1: max_adc = int(1023 * r1 / (r1 + r2)); else: max_adc = 1023 increment = int(max_adc/(num_temps-1)); t = Thermistor(r0, t0, beta, r1, r2) adcs = range(1, max_adc, increment); # adcs = [1, 20, 25, 30, 35, 40, 45, 50, 60, 70, 80, 90, 100, 110, 130, 150, 190, 220, 250, 300] first = 1 print "// Thermistor lookup table for RepRap Temperature Sensor Boards (http://make.rrrf.org/ts)" print "// Made with createTemperatureLookup.py (http://svn.reprap.org/trunk/reprap/firmware/Arduino/utilities/createTemperatureLookup.py)" print "// ./createTemperatureLookup.py --r0=%s --t0=%s --r1=%s --r2=%s --beta=%s --max-adc=%s" % (r0, t0, r1, r2, beta, max_adc) print "// r0: %s" % (r0) print "// t0: %s" % (t0) print "// r1: %s" % (r1) print "// r2: %s" % (r2) print "// beta: %s" % (beta) print "// max adc: %s" % (max_adc) print "#define NUMTEMPS %s" % (len(adcs)) print "short temptable[NUMTEMPS][2] = {" counter = 0 for adc in adcs: counter = counter +1 if counter == len(adcs): print " {%s, %s}" % (adc, int(t.temp(adc))) else: print " {%s, %s}," % (adc, int(t.temp(adc))) print "};" def usage(): print __doc__ if __name__ == "__main__": main(sys.argv[1:]) ================================================ FILE: Sprinter/fastio.h ================================================ /* 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 */ #ifndef _ARDUINO_H #define _ARDUINO_H #include /* utility functions */ #ifndef MASK /// MASKING- returns \f$2^PIN\f$ #define MASK(PIN) (1 << PIN) #endif /* magic I/O routines now you can simply SET_OUTPUT(STEP); WRITE(STEP, 1); WRITE(STEP, 0); */ /// Read a pin #define _READ(IO) ((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN))) /// write to a pin #define _WRITE(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) /// set pin as input #define _SET_INPUT(IO) do {DIO ## IO ## _DDR &= ~MASK(DIO ## IO ## _PIN); } while (0) /// set pin as output #define _SET_OUTPUT(IO) do {DIO ## IO ## _DDR |= MASK(DIO ## IO ## _PIN); } while (0) /// check if pin is an input #define _GET_INPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) == 0) /// check if pin is an output #define _GET_OUTPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) != 0) // why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html /// Read a pin wrapper #define READ(IO) _READ(IO) /// Write to a pin wrapper #define WRITE(IO, v) _WRITE(IO, v) /// toggle a pin wrapper #define TOGGLE(IO) _TOGGLE(IO) /// set pin as input wrapper #define SET_INPUT(IO) _SET_INPUT(IO) /// set pin as output wrapper #define SET_OUTPUT(IO) _SET_OUTPUT(IO) /// check if pin is an input wrapper #define GET_INPUT(IO) _GET_INPUT(IO) /// check if pin is an output wrapper #define GET_OUTPUT(IO) _GET_OUTPUT(IO) /* ports and functions added as necessary or if I feel like it- not a comprehensive list! */ #if defined (__AVR_ATmega168__) || defined (__AVR_ATmega328__) || defined (__AVR_ATmega328P__) // UART #define RXD DIO0 #define TXD DIO1 // SPI #define SCK DIO13 #define MISO DIO12 #define MOSI DIO11 #define SS DIO10 // TWI (I2C) #define SCL AIO5 #define SDA AIO4 // timers and PWM #define OC0A DIO6 #define OC0B DIO5 #define OC1A DIO9 #define OC1B DIO10 #define OC2A DIO11 #define OC2B DIO3 #define DEBUG_LED AIO5 /* pins */ #define DIO0_PIN PIND0 #define DIO0_RPORT PIND #define DIO0_WPORT PORTD #define DIO0_DDR DDRD #define DIO0_PWM NULL #define DIO1_PIN PIND1 #define DIO1_RPORT PIND #define DIO1_WPORT PORTD #define DIO1_DDR DDRD #define DIO1_PWM NULL #define DIO2_PIN PIND2 #define DIO2_RPORT PIND #define DIO2_WPORT PORTD #define DIO2_DDR DDRD #define DIO2_PWM NULL #define DIO3_PIN PIND3 #define DIO3_RPORT PIND #define DIO3_WPORT PORTD #define DIO3_DDR DDRD #define DIO3_PWM &OCR2B #define DIO4_PIN PIND4 #define DIO4_RPORT PIND #define DIO4_WPORT PORTD #define DIO4_DDR DDRD #define DIO4_PWM NULL #define DIO5_PIN PIND5 #define DIO5_RPORT PIND #define DIO5_WPORT PORTD #define DIO5_DDR DDRD #define DIO5_PWM &OCR0B #define DIO6_PIN PIND6 #define DIO6_RPORT PIND #define DIO6_WPORT PORTD #define DIO6_DDR DDRD #define DIO6_PWM &OCR0A #define DIO7_PIN PIND7 #define DIO7_RPORT PIND #define DIO7_WPORT PORTD #define DIO7_DDR DDRD #define DIO7_PWM NULL #define DIO8_PIN PINB0 #define DIO8_RPORT PINB #define DIO8_WPORT PORTB #define DIO8_DDR DDRB #define DIO8_PWM NULL #define DIO9_PIN PINB1 #define DIO9_RPORT PINB #define DIO9_WPORT PORTB #define DIO9_DDR DDRB #define DIO9_PWM NULL #define DIO10_PIN PINB2 #define DIO10_RPORT PINB #define DIO10_WPORT PORTB #define DIO10_DDR DDRB #define DIO10_PWM NULL #define DIO11_PIN PINB3 #define DIO11_RPORT PINB #define DIO11_WPORT PORTB #define DIO11_DDR DDRB #define DIO11_PWM &OCR2A #define DIO12_PIN PINB4 #define DIO12_RPORT PINB #define DIO12_WPORT PORTB #define DIO12_DDR DDRB #define DIO12_PWM NULL #define DIO13_PIN PINB5 #define DIO13_RPORT PINB #define DIO13_WPORT PORTB #define DIO13_DDR DDRB #define DIO13_PWM NULL #define DIO14_PIN PINC0 #define DIO14_RPORT PINC #define DIO14_WPORT PORTC #define DIO14_DDR DDRC #define DIO14_PWM NULL #define DIO15_PIN PINC1 #define DIO15_RPORT PINC #define DIO15_WPORT PORTC #define DIO15_DDR DDRC #define DIO15_PWM NULL #define DIO16_PIN PINC2 #define DIO16_RPORT PINC #define DIO16_WPORT PORTC #define DIO16_DDR DDRC #define DIO16_PWM NULL #define DIO17_PIN PINC3 #define DIO17_RPORT PINC #define DIO17_WPORT PORTC #define DIO17_DDR DDRC #define DIO17_PWM NULL #define DIO18_PIN PINC4 #define DIO18_RPORT PINC #define DIO18_WPORT PORTC #define DIO18_DDR DDRC #define DIO18_PWM NULL #define DIO19_PIN PINC5 #define DIO19_RPORT PINC #define DIO19_WPORT PORTC #define DIO19_DDR DDRC #define DIO19_PWM NULL #define DIO20_PIN PINC6 #define DIO20_RPORT PINC #define DIO20_WPORT PORTC #define DIO20_DDR DDRC #define DIO20_PWM NULL #define DIO21_PIN PINC7 #define DIO21_RPORT PINC #define DIO21_WPORT PORTC #define DIO21_DDR DDRC #define DIO21_PWM NULL #undef PB0 #define PB0_PIN PINB0 #define PB0_RPORT PINB #define PB0_WPORT PORTB #define PB0_DDR DDRB #define PB0_PWM NULL #undef PB1 #define PB1_PIN PINB1 #define PB1_RPORT PINB #define PB1_WPORT PORTB #define PB1_DDR DDRB #define PB1_PWM NULL #undef PB2 #define PB2_PIN PINB2 #define PB2_RPORT PINB #define PB2_WPORT PORTB #define PB2_DDR DDRB #define PB2_PWM NULL #undef PB3 #define PB3_PIN PINB3 #define PB3_RPORT PINB #define PB3_WPORT PORTB #define PB3_DDR DDRB #define PB3_PWM &OCR2A #undef PB4 #define PB4_PIN PINB4 #define PB4_RPORT PINB #define PB4_WPORT PORTB #define PB4_DDR DDRB #define PB4_PWM NULL #undef PB5 #define PB5_PIN PINB5 #define PB5_RPORT PINB #define PB5_WPORT PORTB #define PB5_DDR DDRB #define PB5_PWM NULL #undef PB6 #define PB6_PIN PINB6 #define PB6_RPORT PINB #define PB6_WPORT PORTB #define PB6_DDR DDRB #define PB6_PWM NULL #undef PB7 #define PB7_PIN PINB7 #define PB7_RPORT PINB #define PB7_WPORT PORTB #define PB7_DDR DDRB #define PB7_PWM NULL #undef PC0 #define PC0_PIN PINC0 #define PC0_RPORT PINC #define PC0_WPORT PORTC #define PC0_DDR DDRC #define PC0_PWM NULL #undef PC1 #define PC1_PIN PINC1 #define PC1_RPORT PINC #define PC1_WPORT PORTC #define PC1_DDR DDRC #define PC1_PWM NULL #undef PC2 #define PC2_PIN PINC2 #define PC2_RPORT PINC #define PC2_WPORT PORTC #define PC2_DDR DDRC #define PC2_PWM NULL #undef PC3 #define PC3_PIN PINC3 #define PC3_RPORT PINC #define PC3_WPORT PORTC #define PC3_DDR DDRC #define PC3_PWM NULL #undef PC4 #define PC4_PIN PINC4 #define PC4_RPORT PINC #define PC4_WPORT PORTC #define PC4_DDR DDRC #define PC4_PWM NULL #undef PC5 #define PC5_PIN PINC5 #define PC5_RPORT PINC #define PC5_WPORT PORTC #define PC5_DDR DDRC #define PC5_PWM NULL #undef PC6 #define PC6_PIN PINC6 #define PC6_RPORT PINC #define PC6_WPORT PORTC #define PC6_DDR DDRC #define PC6_PWM NULL #undef PC7 #define PC7_PIN PINC7 #define PC7_RPORT PINC #define PC7_WPORT PORTC #define PC7_DDR DDRC #define PC7_PWM NULL #undef PD0 #define PD0_PIN PIND0 #define PD0_RPORT PIND #define PD0_WPORT PORTD #define PD0_DDR DDRD #define PD0_PWM NULL #undef PD1 #define PD1_PIN PIND1 #define PD1_RPORT PIND #define PD1_WPORT PORTD #define PD1_DDR DDRD #define PD1_PWM NULL #undef PD2 #define PD2_PIN PIND2 #define PD2_RPORT PIND #define PD2_WPORT PORTD #define PD2_DDR DDRD #define PD2_PWM NULL #undef PD3 #define PD3_PIN PIND3 #define PD3_RPORT PIND #define PD3_WPORT PORTD #define PD3_DDR DDRD #define PD3_PWM &OCR2B #undef PD4 #define PD4_PIN PIND4 #define PD4_RPORT PIND #define PD4_WPORT PORTD #define PD4_DDR DDRD #define PD4_PWM NULL #undef PD5 #define PD5_PIN PIND5 #define PD5_RPORT PIND #define PD5_WPORT PORTD #define PD5_DDR DDRD #define PD5_PWM &OCR0B #undef PD6 #define PD6_PIN PIND6 #define PD6_RPORT PIND #define PD6_WPORT PORTD #define PD6_DDR DDRD #define PD6_PWM &OCR0A #undef PD7 #define PD7_PIN PIND7 #define PD7_RPORT PIND #define PD7_WPORT PORTD #define PD7_DDR DDRD #define PD7_PWM NULL #endif /* _AVR_ATmega{168,328,328P}__ */ #if defined (__AVR_ATmega644__) || defined (__AVR_ATmega644P__) || defined (__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) // UART #define RXD DIO8 #define TXD DIO9 #define RXD0 DIO8 #define TXD0 DIO9 #define RXD1 DIO10 #define TXD1 DIO11 // SPI #define SCK DIO7 #define MISO DIO6 #define MOSI DIO5 #define SS DIO4 // TWI (I2C) #define SCL DIO16 #define SDA DIO17 // timers and PWM #define OC0A DIO3 #define OC0B DIO4 #define OC1A DIO13 #define OC1B DIO12 #define OC2A DIO15 #define OC2B DIO14 #define DEBUG_LED DIO0 /* pins */ #define DIO0_PIN PINB0 #define DIO0_RPORT PINB #define DIO0_WPORT PORTB #define DIO0_DDR DDRB #define DIO0_PWM NULL #define DIO1_PIN PINB1 #define DIO1_RPORT PINB #define DIO1_WPORT PORTB #define DIO1_DDR DDRB #define DIO1_PWM NULL #define DIO2_PIN PINB2 #define DIO2_RPORT PINB #define DIO2_WPORT PORTB #define DIO2_DDR DDRB #define DIO2_PWM NULL #define DIO3_PIN PINB3 #define DIO3_RPORT PINB #define DIO3_WPORT PORTB #define DIO3_DDR DDRB #define DIO3_PWM &OCR0A #define DIO4_PIN PINB4 #define DIO4_RPORT PINB #define DIO4_WPORT PORTB #define DIO4_DDR DDRB #define DIO4_PWM &OCR0B #define DIO5_PIN PINB5 #define DIO5_RPORT PINB #define DIO5_WPORT PORTB #define DIO5_DDR DDRB #define DIO5_PWM NULL #define DIO6_PIN PINB6 #define DIO6_RPORT PINB #define DIO6_WPORT PORTB #define DIO6_DDR DDRB #define DIO6_PWM NULL #define DIO7_PIN PINB7 #define DIO7_RPORT PINB #define DIO7_WPORT PORTB #define DIO7_DDR DDRB #define DIO7_PWM NULL #define DIO8_PIN PIND0 #define DIO8_RPORT PIND #define DIO8_WPORT PORTD #define DIO8_DDR DDRD #define DIO8_PWM NULL #define DIO9_PIN PIND1 #define DIO9_RPORT PIND #define DIO9_WPORT PORTD #define DIO9_DDR DDRD #define DIO9_PWM NULL #define DIO10_PIN PIND2 #define DIO10_RPORT PIND #define DIO10_WPORT PORTD #define DIO10_DDR DDRD #define DIO10_PWM NULL #define DIO11_PIN PIND3 #define DIO11_RPORT PIND #define DIO11_WPORT PORTD #define DIO11_DDR DDRD #define DIO11_PWM NULL #define DIO12_PIN PIND4 #define DIO12_RPORT PIND #define DIO12_WPORT PORTD #define DIO12_DDR DDRD #define DIO12_PWM NULL #define DIO13_PIN PIND5 #define DIO13_RPORT PIND #define DIO13_WPORT PORTD #define DIO13_DDR DDRD #define DIO13_PWM NULL #define DIO14_PIN PIND6 #define DIO14_RPORT PIND #define DIO14_WPORT PORTD #define DIO14_DDR DDRD #define DIO14_PWM &OCR2B #define DIO15_PIN PIND7 #define DIO15_RPORT PIND #define DIO15_WPORT PORTD #define DIO15_DDR DDRD #define DIO15_PWM &OCR2A #define DIO16_PIN PINC0 #define DIO16_RPORT PINC #define DIO16_WPORT PORTC #define DIO16_DDR DDRC #define DIO16_PWM NULL #define DIO17_PIN PINC1 #define DIO17_RPORT PINC #define DIO17_WPORT PORTC #define DIO17_DDR DDRC #define DIO17_PWM NULL #define DIO18_PIN PINC2 #define DIO18_RPORT PINC #define DIO18_WPORT PORTC #define DIO18_DDR DDRC #define DIO18_PWM NULL #define DIO19_PIN PINC3 #define DIO19_RPORT PINC #define DIO19_WPORT PORTC #define DIO19_DDR DDRC #define DIO19_PWM NULL #define DIO20_PIN PINC4 #define DIO20_RPORT PINC #define DIO20_WPORT PORTC #define DIO20_DDR DDRC #define DIO20_PWM NULL #define DIO21_PIN PINC5 #define DIO21_RPORT PINC #define DIO21_WPORT PORTC #define DIO21_DDR DDRC #define DIO21_PWM NULL #define DIO22_PIN PINC6 #define DIO22_RPORT PINC #define DIO22_WPORT PORTC #define DIO22_DDR DDRC #define DIO22_PWM NULL #define DIO23_PIN PINC7 #define DIO23_RPORT PINC #define DIO23_WPORT PORTC #define DIO23_DDR DDRC #define DIO23_PWM NULL #define DIO24_PIN PINA7 #define DIO24_RPORT PINA #define DIO24_WPORT PORTA #define DIO24_DDR DDRA #define DIO24_PWM NULL #define DIO25_PIN PINA6 #define DIO25_RPORT PINA #define DIO25_WPORT PORTA #define DIO25_DDR DDRA #define DIO25_PWM NULL #define DIO26_PIN PINA5 #define DIO26_RPORT PINA #define DIO26_WPORT PORTA #define DIO26_DDR DDRA #define DIO26_PWM NULL #define DIO27_PIN PINA4 #define DIO27_RPORT PINA #define DIO27_WPORT PORTA #define DIO27_DDR DDRA #define DIO27_PWM NULL #define DIO28_PIN PINA3 #define DIO28_RPORT PINA #define DIO28_WPORT PORTA #define DIO28_DDR DDRA #define DIO28_PWM NULL #define DIO29_PIN PINA2 #define DIO29_RPORT PINA #define DIO29_WPORT PORTA #define DIO29_DDR DDRA #define DIO29_PWM NULL #define DIO30_PIN PINA1 #define DIO30_RPORT PINA #define DIO30_WPORT PORTA #define DIO30_DDR DDRA #define DIO30_PWM NULL #define DIO31_PIN PINA0 #define DIO31_RPORT PINA #define DIO31_WPORT PORTA #define DIO31_DDR DDRA #define DIO31_PWM NULL #define AIO0_PIN PINA0 #define AIO0_RPORT PINA #define AIO0_WPORT PORTA #define AIO0_DDR DDRA #define AIO0_PWM NULL #define AIO1_PIN PINA1 #define AIO1_RPORT PINA #define AIO1_WPORT PORTA #define AIO1_DDR DDRA #define AIO1_PWM NULL #define AIO2_PIN PINA2 #define AIO2_RPORT PINA #define AIO2_WPORT PORTA #define AIO2_DDR DDRA #define AIO2_PWM NULL #define AIO3_PIN PINA3 #define AIO3_RPORT PINA #define AIO3_WPORT PORTA #define AIO3_DDR DDRA #define AIO3_PWM NULL #define AIO4_PIN PINA4 #define AIO4_RPORT PINA #define AIO4_WPORT PORTA #define AIO4_DDR DDRA #define AIO4_PWM NULL #define AIO5_PIN PINA5 #define AIO5_RPORT PINA #define AIO5_WPORT PORTA #define AIO5_DDR DDRA #define AIO5_PWM NULL #define AIO6_PIN PINA6 #define AIO6_RPORT PINA #define AIO6_WPORT PORTA #define AIO6_DDR DDRA #define AIO6_PWM NULL #define AIO7_PIN PINA7 #define AIO7_RPORT PINA #define AIO7_WPORT PORTA #define AIO7_DDR DDRA #define AIO7_PWM NULL #undef PA0 #define PA0_PIN PINA0 #define PA0_RPORT PINA #define PA0_WPORT PORTA #define PA0_DDR DDRA #define PA0_PWM NULL #undef PA1 #define PA1_PIN PINA1 #define PA1_RPORT PINA #define PA1_WPORT PORTA #define PA1_DDR DDRA #define PA1_PWM NULL #undef PA2 #define PA2_PIN PINA2 #define PA2_RPORT PINA #define PA2_WPORT PORTA #define PA2_DDR DDRA #define PA2_PWM NULL #undef PA3 #define PA3_PIN PINA3 #define PA3_RPORT PINA #define PA3_WPORT PORTA #define PA3_DDR DDRA #define PA3_PWM NULL #undef PA4 #define PA4_PIN PINA4 #define PA4_RPORT PINA #define PA4_WPORT PORTA #define PA4_DDR DDRA #define PA4_PWM NULL #undef PA5 #define PA5_PIN PINA5 #define PA5_RPORT PINA #define PA5_WPORT PORTA #define PA5_DDR DDRA #define PA5_PWM NULL #undef PA6 #define PA6_PIN PINA6 #define PA6_RPORT PINA #define PA6_WPORT PORTA #define PA6_DDR DDRA #define PA6_PWM NULL #undef PA7 #define PA7_PIN PINA7 #define PA7_RPORT PINA #define PA7_WPORT PORTA #define PA7_DDR DDRA #define PA7_PWM NULL #undef PB0 #define PB0_PIN PINB0 #define PB0_RPORT PINB #define PB0_WPORT PORTB #define PB0_DDR DDRB #define PB0_PWM NULL #undef PB1 #define PB1_PIN PINB1 #define PB1_RPORT PINB #define PB1_WPORT PORTB #define PB1_DDR DDRB #define PB1_PWM NULL #undef PB2 #define PB2_PIN PINB2 #define PB2_RPORT PINB #define PB2_WPORT PORTB #define PB2_DDR DDRB #define PB2_PWM NULL #undef PB3 #define PB3_PIN PINB3 #define PB3_RPORT PINB #define PB3_WPORT PORTB #define PB3_DDR DDRB #define PB3_PWM &OCR0A #undef PB4 #define PB4_PIN PINB4 #define PB4_RPORT PINB #define PB4_WPORT PORTB #define PB4_DDR DDRB #define PB4_PWM &OCR0B #undef PB5 #define PB5_PIN PINB5 #define PB5_RPORT PINB #define PB5_WPORT PORTB #define PB5_DDR DDRB #define PB5_PWM NULL #undef PB6 #define PB6_PIN PINB6 #define PB6_RPORT PINB #define PB6_WPORT PORTB #define PB6_DDR DDRB #define PB6_PWM NULL #undef PB7 #define PB7_PIN PINB7 #define PB7_RPORT PINB #define PB7_WPORT PORTB #define PB7_DDR DDRB #define PB7_PWM NULL #undef PC0 #define PC0_PIN PINC0 #define PC0_RPORT PINC #define PC0_WPORT PORTC #define PC0_DDR DDRC #define PC0_PWM NULL #undef PC1 #define PC1_PIN PINC1 #define PC1_RPORT PINC #define PC1_WPORT PORTC #define PC1_DDR DDRC #define PC1_PWM NULL #undef PC2 #define PC2_PIN PINC2 #define PC2_RPORT PINC #define PC2_WPORT PORTC #define PC2_DDR DDRC #define PC2_PWM NULL #undef PC3 #define PC3_PIN PINC3 #define PC3_RPORT PINC #define PC3_WPORT PORTC #define PC3_DDR DDRC #define PC3_PWM NULL #undef PC4 #define PC4_PIN PINC4 #define PC4_RPORT PINC #define PC4_WPORT PORTC #define PC4_DDR DDRC #define PC4_PWM NULL #undef PC5 #define PC5_PIN PINC5 #define PC5_RPORT PINC #define PC5_WPORT PORTC #define PC5_DDR DDRC #define PC5_PWM NULL #undef PC6 #define PC6_PIN PINC6 #define PC6_RPORT PINC #define PC6_WPORT PORTC #define PC6_DDR DDRC #define PC6_PWM NULL #undef PC7 #define PC7_PIN PINC7 #define PC7_RPORT PINC #define PC7_WPORT PORTC #define PC7_DDR DDRC #define PC7_PWM NULL #undef PD0 #define PD0_PIN PIND0 #define PD0_RPORT PIND #define PD0_WPORT PORTD #define PD0_DDR DDRD #define PD0_PWM NULL #undef PD1 #define PD1_PIN PIND1 #define PD1_RPORT PIND #define PD1_WPORT PORTD #define PD1_DDR DDRD #define PD1_PWM NULL #undef PD2 #define PD2_PIN PIND2 #define PD2_RPORT PIND #define PD2_WPORT PORTD #define PD2_DDR DDRD #define PD2_PWM NULL #undef PD3 #define PD3_PIN PIND3 #define PD3_RPORT PIND #define PD3_WPORT PORTD #define PD3_DDR DDRD #define PD3_PWM NULL #undef PD4 #define PD4_PIN PIND4 #define PD4_RPORT PIND #define PD4_WPORT PORTD #define PD4_DDR DDRD #define PD4_PWM NULL #undef PD5 #define PD5_PIN PIND5 #define PD5_RPORT PIND #define PD5_WPORT PORTD #define PD5_DDR DDRD #define PD5_PWM NULL #undef PD6 #define PD6_PIN PIND6 #define PD6_RPORT PIND #define PD6_WPORT PORTD #define PD6_DDR DDRD #define PD6_PWM &OCR2B #undef PD7 #define PD7_PIN PIND7 #define PD7_RPORT PIND #define PD7_WPORT PORTD #define PD7_DDR DDRD #define PD7_PWM &OCR2A #endif /* _AVR_ATmega{644,644P,644PA,1284P}__ */ #if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__) // UART #define RXD DIO0 #define TXD DIO1 // SPI #define SCK DIO52 #define MISO DIO50 #define MOSI DIO51 #define SS DIO53 // TWI (I2C) #define SCL DIO21 #define SDA DIO20 // timers and PWM #define OC0A DIO13 #define OC0B DIO4 #define OC1A DIO11 #define OC1B DIO12 #define OC2A DIO10 #define OC2B DIO9 #define OC3A DIO5 #define OC3B DIO2 #define OC3C DIO3 #define OC4A DIO6 #define OC4B DIO7 #define OC4C DIO8 #define OC5A DIO46 #define OC5B DIO45 #define OC5C DIO44 // change for your board #define DEBUG_LED DIO21 /* pins */ #define DIO0_PIN PINE0 #define DIO0_RPORT PINE #define DIO0_WPORT PORTE #define DIO0_DDR DDRE #define DIO0_PWM NULL #define DIO1_PIN PINE1 #define DIO1_RPORT PINE #define DIO1_WPORT PORTE #define DIO1_DDR DDRE #define DIO1_PWM NULL #define DIO2_PIN PINE4 #define DIO2_RPORT PINE #define DIO2_WPORT PORTE #define DIO2_DDR DDRE #define DIO2_PWM &OCR3BL #define DIO3_PIN PINE5 #define DIO3_RPORT PINE #define DIO3_WPORT PORTE #define DIO3_DDR DDRE #define DIO3_PWM &OCR3CL #define DIO4_PIN PING5 #define DIO4_RPORT PING #define DIO4_WPORT PORTG #define DIO4_DDR DDRG #define DIO4_PWM &OCR0B #define DIO5_PIN PINE3 #define DIO5_RPORT PINE #define DIO5_WPORT PORTE #define DIO5_DDR DDRE #define DIO5_PWM &OCR3AL #define DIO6_PIN PINH3 #define DIO6_RPORT PINH #define DIO6_WPORT PORTH #define DIO6_DDR DDRH #define DIO6_PWM &OCR4AL #define DIO7_PIN PINH4 #define DIO7_RPORT PINH #define DIO7_WPORT PORTH #define DIO7_DDR DDRH #define DIO7_PWM &OCR4BL #define DIO8_PIN PINH5 #define DIO8_RPORT PINH #define DIO8_WPORT PORTH #define DIO8_DDR DDRH #define DIO8_PWM &OCR4CL #define DIO9_PIN PINH6 #define DIO9_RPORT PINH #define DIO9_WPORT PORTH #define DIO9_DDR DDRH #define DIO9_PWM &OCR2B #define DIO10_PIN PINB4 #define DIO10_RPORT PINB #define DIO10_WPORT PORTB #define DIO10_DDR DDRB #define DIO10_PWM &OCR2A #define DIO11_PIN PINB5 #define DIO11_RPORT PINB #define DIO11_WPORT PORTB #define DIO11_DDR DDRB #define DIO11_PWM NULL #define DIO12_PIN PINB6 #define DIO12_RPORT PINB #define DIO12_WPORT PORTB #define DIO12_DDR DDRB #define DIO12_PWM NULL #define DIO13_PIN PINB7 #define DIO13_RPORT PINB #define DIO13_WPORT PORTB #define DIO13_DDR DDRB #define DIO13_PWM &OCR0A #define DIO14_PIN PINJ1 #define DIO14_RPORT PINJ #define DIO14_WPORT PORTJ #define DIO14_DDR DDRJ #define DIO14_PWM NULL #define DIO15_PIN PINJ0 #define DIO15_RPORT PINJ #define DIO15_WPORT PORTJ #define DIO15_DDR DDRJ #define DIO15_PWM NULL #define DIO16_PIN PINH1 #define DIO16_RPORT PINH #define DIO16_WPORT PORTH #define DIO16_DDR DDRH #define DIO16_PWM NULL #define DIO17_PIN PINH0 #define DIO17_RPORT PINH #define DIO17_WPORT PORTH #define DIO17_DDR DDRH #define DIO17_PWM NULL #define DIO18_PIN PIND3 #define DIO18_RPORT PIND #define DIO18_WPORT PORTD #define DIO18_DDR DDRD #define DIO18_PWM NULL #define DIO19_PIN PIND2 #define DIO19_RPORT PIND #define DIO19_WPORT PORTD #define DIO19_DDR DDRD #define DIO19_PWM NULL #define DIO20_PIN PIND1 #define DIO20_RPORT PIND #define DIO20_WPORT PORTD #define DIO20_DDR DDRD #define DIO20_PWM NULL #define DIO21_PIN PIND0 #define DIO21_RPORT PIND #define DIO21_WPORT PORTD #define DIO21_DDR DDRD #define DIO21_PWM NULL #define DIO22_PIN PINA0 #define DIO22_RPORT PINA #define DIO22_WPORT PORTA #define DIO22_DDR DDRA #define DIO22_PWM NULL #define DIO23_PIN PINA1 #define DIO23_RPORT PINA #define DIO23_WPORT PORTA #define DIO23_DDR DDRA #define DIO23_PWM NULL #define DIO24_PIN PINA2 #define DIO24_RPORT PINA #define DIO24_WPORT PORTA #define DIO24_DDR DDRA #define DIO24_PWM NULL #define DIO25_PIN PINA3 #define DIO25_RPORT PINA #define DIO25_WPORT PORTA #define DIO25_DDR DDRA #define DIO25_PWM NULL #define DIO26_PIN PINA4 #define DIO26_RPORT PINA #define DIO26_WPORT PORTA #define DIO26_DDR DDRA #define DIO26_PWM NULL #define DIO27_PIN PINA5 #define DIO27_RPORT PINA #define DIO27_WPORT PORTA #define DIO27_DDR DDRA #define DIO27_PWM NULL #define DIO28_PIN PINA6 #define DIO28_RPORT PINA #define DIO28_WPORT PORTA #define DIO28_DDR DDRA #define DIO28_PWM NULL #define DIO29_PIN PINA7 #define DIO29_RPORT PINA #define DIO29_WPORT PORTA #define DIO29_DDR DDRA #define DIO29_PWM NULL #define DIO30_PIN PINC7 #define DIO30_RPORT PINC #define DIO30_WPORT PORTC #define DIO30_DDR DDRC #define DIO30_PWM NULL #define DIO31_PIN PINC6 #define DIO31_RPORT PINC #define DIO31_WPORT PORTC #define DIO31_DDR DDRC #define DIO31_PWM NULL #define DIO32_PIN PINC5 #define DIO32_RPORT PINC #define DIO32_WPORT PORTC #define DIO32_DDR DDRC #define DIO32_PWM NULL #define DIO33_PIN PINC4 #define DIO33_RPORT PINC #define DIO33_WPORT PORTC #define DIO33_DDR DDRC #define DIO33_PWM NULL #define DIO34_PIN PINC3 #define DIO34_RPORT PINC #define DIO34_WPORT PORTC #define DIO34_DDR DDRC #define DIO34_PWM NULL #define DIO35_PIN PINC2 #define DIO35_RPORT PINC #define DIO35_WPORT PORTC #define DIO35_DDR DDRC #define DIO35_PWM NULL #define DIO36_PIN PINC1 #define DIO36_RPORT PINC #define DIO36_WPORT PORTC #define DIO36_DDR DDRC #define DIO36_PWM NULL #define DIO37_PIN PINC0 #define DIO37_RPORT PINC #define DIO37_WPORT PORTC #define DIO37_DDR DDRC #define DIO37_PWM NULL #define DIO38_PIN PIND7 #define DIO38_RPORT PIND #define DIO38_WPORT PORTD #define DIO38_DDR DDRD #define DIO38_PWM NULL #define DIO39_PIN PING2 #define DIO39_RPORT PING #define DIO39_WPORT PORTG #define DIO39_DDR DDRG #define DIO39_PWM NULL #define DIO40_PIN PING1 #define DIO40_RPORT PING #define DIO40_WPORT PORTG #define DIO40_DDR DDRG #define DIO40_PWM NULL #define DIO41_PIN PING0 #define DIO41_RPORT PING #define DIO41_WPORT PORTG #define DIO41_DDR DDRG #define DIO41_PWM NULL #define DIO42_PIN PINL7 #define DIO42_RPORT PINL #define DIO42_WPORT PORTL #define DIO42_DDR DDRL #define DIO42_PWM NULL #define DIO43_PIN PINL6 #define DIO43_RPORT PINL #define DIO43_WPORT PORTL #define DIO43_DDR DDRL #define DIO43_PWM NULL #define DIO44_PIN PINL5 #define DIO44_RPORT PINL #define DIO44_WPORT PORTL #define DIO44_DDR DDRL #define DIO44_PWM &OCR5CL #define DIO45_PIN PINL4 #define DIO45_RPORT PINL #define DIO45_WPORT PORTL #define DIO45_DDR DDRL #define DIO45_PWM &OCR5BL #define DIO46_PIN PINL3 #define DIO46_RPORT PINL #define DIO46_WPORT PORTL #define DIO46_DDR DDRL #define DIO46_PWM &OCR5AL #define DIO47_PIN PINL2 #define DIO47_RPORT PINL #define DIO47_WPORT PORTL #define DIO47_DDR DDRL #define DIO47_PWM NULL #define DIO48_PIN PINL1 #define DIO48_RPORT PINL #define DIO48_WPORT PORTL #define DIO48_DDR DDRL #define DIO48_PWM NULL #define DIO49_PIN PINL0 #define DIO49_RPORT PINL #define DIO49_WPORT PORTL #define DIO49_DDR DDRL #define DIO49_PWM NULL #define DIO50_PIN PINB3 #define DIO50_RPORT PINB #define DIO50_WPORT PORTB #define DIO50_DDR DDRB #define DIO50_PWM NULL #define DIO51_PIN PINB2 #define DIO51_RPORT PINB #define DIO51_WPORT PORTB #define DIO51_DDR DDRB #define DIO51_PWM NULL #define DIO52_PIN PINB1 #define DIO52_RPORT PINB #define DIO52_WPORT PORTB #define DIO52_DDR DDRB #define DIO52_PWM NULL #define DIO53_PIN PINB0 #define DIO53_RPORT PINB #define DIO53_WPORT PORTB #define DIO53_DDR DDRB #define DIO53_PWM NULL #define DIO54_PIN PINF0 #define DIO54_RPORT PINF #define DIO54_WPORT PORTF #define DIO54_DDR DDRF #define DIO54_PWM NULL #define DIO55_PIN PINF1 #define DIO55_RPORT PINF #define DIO55_WPORT PORTF #define DIO55_DDR DDRF #define DIO55_PWM NULL #define DIO56_PIN PINF2 #define DIO56_RPORT PINF #define DIO56_WPORT PORTF #define DIO56_DDR DDRF #define DIO56_PWM NULL #define DIO57_PIN PINF3 #define DIO57_RPORT PINF #define DIO57_WPORT PORTF #define DIO57_DDR DDRF #define DIO57_PWM NULL #define DIO58_PIN PINF4 #define DIO58_RPORT PINF #define DIO58_WPORT PORTF #define DIO58_DDR DDRF #define DIO58_PWM NULL #define DIO59_PIN PINF5 #define DIO59_RPORT PINF #define DIO59_WPORT PORTF #define DIO59_DDR DDRF #define DIO59_PWM NULL #define DIO60_PIN PINF6 #define DIO60_RPORT PINF #define DIO60_WPORT PORTF #define DIO60_DDR DDRF #define DIO60_PWM NULL #define DIO61_PIN PINF7 #define DIO61_RPORT PINF #define DIO61_WPORT PORTF #define DIO61_DDR DDRF #define DIO61_PWM NULL #define DIO62_PIN PINK0 #define DIO62_RPORT PINK #define DIO62_WPORT PORTK #define DIO62_DDR DDRK #define DIO62_PWM NULL #define DIO63_PIN PINK1 #define DIO63_RPORT PINK #define DIO63_WPORT PORTK #define DIO63_DDR DDRK #define DIO63_PWM NULL #define DIO64_PIN PINK2 #define DIO64_RPORT PINK #define DIO64_WPORT PORTK #define DIO64_DDR DDRK #define DIO64_PWM NULL #define DIO65_PIN PINK3 #define DIO65_RPORT PINK #define DIO65_WPORT PORTK #define DIO65_DDR DDRK #define DIO65_PWM NULL #define DIO66_PIN PINK4 #define DIO66_RPORT PINK #define DIO66_WPORT PORTK #define DIO66_DDR DDRK #define DIO66_PWM NULL #define DIO67_PIN PINK5 #define DIO67_RPORT PINK #define DIO67_WPORT PORTK #define DIO67_DDR DDRK #define DIO67_PWM NULL #define DIO68_PIN PINK6 #define DIO68_RPORT PINK #define DIO68_WPORT PORTK #define DIO68_DDR DDRK #define DIO68_PWM NULL #define DIO69_PIN PINK7 #define DIO69_RPORT PINK #define DIO69_WPORT PORTK #define DIO69_DDR DDRK #define DIO69_PWM NULL #undef PA0 #define PA0_PIN PINA0 #define PA0_RPORT PINA #define PA0_WPORT PORTA #define PA0_DDR DDRA #define PA0_PWM NULL #undef PA1 #define PA1_PIN PINA1 #define PA1_RPORT PINA #define PA1_WPORT PORTA #define PA1_DDR DDRA #define PA1_PWM NULL #undef PA2 #define PA2_PIN PINA2 #define PA2_RPORT PINA #define PA2_WPORT PORTA #define PA2_DDR DDRA #define PA2_PWM NULL #undef PA3 #define PA3_PIN PINA3 #define PA3_RPORT PINA #define PA3_WPORT PORTA #define PA3_DDR DDRA #define PA3_PWM NULL #undef PA4 #define PA4_PIN PINA4 #define PA4_RPORT PINA #define PA4_WPORT PORTA #define PA4_DDR DDRA #define PA4_PWM NULL #undef PA5 #define PA5_PIN PINA5 #define PA5_RPORT PINA #define PA5_WPORT PORTA #define PA5_DDR DDRA #define PA5_PWM NULL #undef PA6 #define PA6_PIN PINA6 #define PA6_RPORT PINA #define PA6_WPORT PORTA #define PA6_DDR DDRA #define PA6_PWM NULL #undef PA7 #define PA7_PIN PINA7 #define PA7_RPORT PINA #define PA7_WPORT PORTA #define PA7_DDR DDRA #define PA7_PWM NULL #undef PB0 #define PB0_PIN PINB0 #define PB0_RPORT PINB #define PB0_WPORT PORTB #define PB0_DDR DDRB #define PB0_PWM NULL #undef PB1 #define PB1_PIN PINB1 #define PB1_RPORT PINB #define PB1_WPORT PORTB #define PB1_DDR DDRB #define PB1_PWM NULL #undef PB2 #define PB2_PIN PINB2 #define PB2_RPORT PINB #define PB2_WPORT PORTB #define PB2_DDR DDRB #define PB2_PWM NULL #undef PB3 #define PB3_PIN PINB3 #define PB3_RPORT PINB #define PB3_WPORT PORTB #define PB3_DDR DDRB #define PB3_PWM NULL #undef PB4 #define PB4_PIN PINB4 #define PB4_RPORT PINB #define PB4_WPORT PORTB #define PB4_DDR DDRB #define PB4_PWM &OCR2A #undef PB5 #define PB5_PIN PINB5 #define PB5_RPORT PINB #define PB5_WPORT PORTB #define PB5_DDR DDRB #define PB5_PWM NULL #undef PB6 #define PB6_PIN PINB6 #define PB6_RPORT PINB #define PB6_WPORT PORTB #define PB6_DDR DDRB #define PB6_PWM NULL #undef PB7 #define PB7_PIN PINB7 #define PB7_RPORT PINB #define PB7_WPORT PORTB #define PB7_DDR DDRB #define PB7_PWM &OCR0A #undef PC0 #define PC0_PIN PINC0 #define PC0_RPORT PINC #define PC0_WPORT PORTC #define PC0_DDR DDRC #define PC0_PWM NULL #undef PC1 #define PC1_PIN PINC1 #define PC1_RPORT PINC #define PC1_WPORT PORTC #define PC1_DDR DDRC #define PC1_PWM NULL #undef PC2 #define PC2_PIN PINC2 #define PC2_RPORT PINC #define PC2_WPORT PORTC #define PC2_DDR DDRC #define PC2_PWM NULL #undef PC3 #define PC3_PIN PINC3 #define PC3_RPORT PINC #define PC3_WPORT PORTC #define PC3_DDR DDRC #define PC3_PWM NULL #undef PC4 #define PC4_PIN PINC4 #define PC4_RPORT PINC #define PC4_WPORT PORTC #define PC4_DDR DDRC #define PC4_PWM NULL #undef PC5 #define PC5_PIN PINC5 #define PC5_RPORT PINC #define PC5_WPORT PORTC #define PC5_DDR DDRC #define PC5_PWM NULL #undef PC6 #define PC6_PIN PINC6 #define PC6_RPORT PINC #define PC6_WPORT PORTC #define PC6_DDR DDRC #define PC6_PWM NULL #undef PC7 #define PC7_PIN PINC7 #define PC7_RPORT PINC #define PC7_WPORT PORTC #define PC7_DDR DDRC #define PC7_PWM NULL #undef PD0 #define PD0_PIN PIND0 #define PD0_RPORT PIND #define PD0_WPORT PORTD #define PD0_DDR DDRD #define PD0_PWM NULL #undef PD1 #define PD1_PIN PIND1 #define PD1_RPORT PIND #define PD1_WPORT PORTD #define PD1_DDR DDRD #define PD1_PWM NULL #undef PD2 #define PD2_PIN PIND2 #define PD2_RPORT PIND #define PD2_WPORT PORTD #define PD2_DDR DDRD #define PD2_PWM NULL #undef PD3 #define PD3_PIN PIND3 #define PD3_RPORT PIND #define PD3_WPORT PORTD #define PD3_DDR DDRD #define PD3_PWM NULL #undef PD4 #define PD4_PIN PIND4 #define PD4_RPORT PIND #define PD4_WPORT PORTD #define PD4_DDR DDRD #define PD4_PWM NULL #undef PD5 #define PD5_PIN PIND5 #define PD5_RPORT PIND #define PD5_WPORT PORTD #define PD5_DDR DDRD #define PD5_PWM NULL #undef PD6 #define PD6_PIN PIND6 #define PD6_RPORT PIND #define PD6_WPORT PORTD #define PD6_DDR DDRD #define PD6_PWM NULL #undef PD7 #define PD7_PIN PIND7 #define PD7_RPORT PIND #define PD7_WPORT PORTD #define PD7_DDR DDRD #define PD7_PWM NULL #undef PE0 #define PE0_PIN PINE0 #define PE0_RPORT PINE #define PE0_WPORT PORTE #define PE0_DDR DDRE #define PE0_PWM NULL #undef PE1 #define PE1_PIN PINE1 #define PE1_RPORT PINE #define PE1_WPORT PORTE #define PE1_DDR DDRE #define PE1_PWM NULL #undef PE2 #define PE2_PIN PINE2 #define PE2_RPORT PINE #define PE2_WPORT PORTE #define PE2_DDR DDRE #define PE2_PWM NULL #undef PE3 #define PE3_PIN PINE3 #define PE3_RPORT PINE #define PE3_WPORT PORTE #define PE3_DDR DDRE #define PE3_PWM &OCR3AL #undef PE4 #define PE4_PIN PINE4 #define PE4_RPORT PINE #define PE4_WPORT PORTE #define PE4_DDR DDRE #define PE4_PWM &OCR3BL #undef PE5 #define PE5_PIN PINE5 #define PE5_RPORT PINE #define PE5_WPORT PORTE #define PE5_DDR DDRE #define PE5_PWM &OCR3CL #undef PE6 #define PE6_PIN PINE6 #define PE6_RPORT PINE #define PE6_WPORT PORTE #define PE6_DDR DDRE #define PE6_PWM NULL #undef PE7 #define PE7_PIN PINE7 #define PE7_RPORT PINE #define PE7_WPORT PORTE #define PE7_DDR DDRE #define PE7_PWM NULL #undef PF0 #define PF0_PIN PINF0 #define PF0_RPORT PINF #define PF0_WPORT PORTF #define PF0_DDR DDRF #define PF0_PWM NULL #undef PF1 #define PF1_PIN PINF1 #define PF1_RPORT PINF #define PF1_WPORT PORTF #define PF1_DDR DDRF #define PF1_PWM NULL #undef PF2 #define PF2_PIN PINF2 #define PF2_RPORT PINF #define PF2_WPORT PORTF #define PF2_DDR DDRF #define PF2_PWM NULL #undef PF3 #define PF3_PIN PINF3 #define PF3_RPORT PINF #define PF3_WPORT PORTF #define PF3_DDR DDRF #define PF3_PWM NULL #undef PF4 #define PF4_PIN PINF4 #define PF4_RPORT PINF #define PF4_WPORT PORTF #define PF4_DDR DDRF #define PF4_PWM NULL #undef PF5 #define PF5_PIN PINF5 #define PF5_RPORT PINF #define PF5_WPORT PORTF #define PF5_DDR DDRF #define PF5_PWM NULL #undef PF6 #define PF6_PIN PINF6 #define PF6_RPORT PINF #define PF6_WPORT PORTF #define PF6_DDR DDRF #define PF6_PWM NULL #undef PF7 #define PF7_PIN PINF7 #define PF7_RPORT PINF #define PF7_WPORT PORTF #define PF7_DDR DDRF #define PF7_PWM NULL #undef PG0 #define PG0_PIN PING0 #define PG0_RPORT PING #define PG0_WPORT PORTG #define PG0_DDR DDRG #define PG0_PWM NULL #undef PG1 #define PG1_PIN PING1 #define PG1_RPORT PING #define PG1_WPORT PORTG #define PG1_DDR DDRG #define PG1_PWM NULL #undef PG2 #define PG2_PIN PING2 #define PG2_RPORT PING #define PG2_WPORT PORTG #define PG2_DDR DDRG #define PG2_PWM NULL #undef PG3 #define PG3_PIN PING3 #define PG3_RPORT PING #define PG3_WPORT PORTG #define PG3_DDR DDRG #define PG3_PWM NULL #undef PG4 #define PG4_PIN PING4 #define PG4_RPORT PING #define PG4_WPORT PORTG #define PG4_DDR DDRG #define PG4_PWM NULL #undef PG5 #define PG5_PIN PING5 #define PG5_RPORT PING #define PG5_WPORT PORTG #define PG5_DDR DDRG #define PG5_PWM &OCR0B #undef PG6 #define PG6_PIN PING6 #define PG6_RPORT PING #define PG6_WPORT PORTG #define PG6_DDR DDRG #define PG6_PWM NULL #undef PG7 #define PG7_PIN PING7 #define PG7_RPORT PING #define PG7_WPORT PORTG #define PG7_DDR DDRG #define PG7_PWM NULL #undef PH0 #define PH0_PIN PINH0 #define PH0_RPORT PINH #define PH0_WPORT PORTH #define PH0_DDR DDRH #define PH0_PWM NULL #undef PH1 #define PH1_PIN PINH1 #define PH1_RPORT PINH #define PH1_WPORT PORTH #define PH1_DDR DDRH #define PH1_PWM NULL #undef PH2 #define PH2_PIN PINH2 #define PH2_RPORT PINH #define PH2_WPORT PORTH #define PH2_DDR DDRH #define PH2_PWM NULL #undef PH3 #define PH3_PIN PINH3 #define PH3_RPORT PINH #define PH3_WPORT PORTH #define PH3_DDR DDRH #define PH3_PWM &OCR4AL #undef PH4 #define PH4_PIN PINH4 #define PH4_RPORT PINH #define PH4_WPORT PORTH #define PH4_DDR DDRH #define PH4_PWM &OCR4BL #undef PH5 #define PH5_PIN PINH5 #define PH5_RPORT PINH #define PH5_WPORT PORTH #define PH5_DDR DDRH #define PH5_PWM &OCR4CL #undef PH6 #define PH6_PIN PINH6 #define PH6_RPORT PINH #define PH6_WPORT PORTH #define PH6_DDR DDRH #define PH6_PWM &OCR2B #undef PH7 #define PH7_PIN PINH7 #define PH7_RPORT PINH #define PH7_WPORT PORTH #define PH7_DDR DDRH #define PH7_PWM NULL #undef PJ0 #define PJ0_PIN PINJ0 #define PJ0_RPORT PINJ #define PJ0_WPORT PORTJ #define PJ0_DDR DDRJ #define PJ0_PWM NULL #undef PJ1 #define PJ1_PIN PINJ1 #define PJ1_RPORT PINJ #define PJ1_WPORT PORTJ #define PJ1_DDR DDRJ #define PJ1_PWM NULL #undef PJ2 #define PJ2_PIN PINJ2 #define PJ2_RPORT PINJ #define PJ2_WPORT PORTJ #define PJ2_DDR DDRJ #define PJ2_PWM NULL #undef PJ3 #define PJ3_PIN PINJ3 #define PJ3_RPORT PINJ #define PJ3_WPORT PORTJ #define PJ3_DDR DDRJ #define PJ3_PWM NULL #undef PJ4 #define PJ4_PIN PINJ4 #define PJ4_RPORT PINJ #define PJ4_WPORT PORTJ #define PJ4_DDR DDRJ #define PJ4_PWM NULL #undef PJ5 #define PJ5_PIN PINJ5 #define PJ5_RPORT PINJ #define PJ5_WPORT PORTJ #define PJ5_DDR DDRJ #define PJ5_PWM NULL #undef PJ6 #define PJ6_PIN PINJ6 #define PJ6_RPORT PINJ #define PJ6_WPORT PORTJ #define PJ6_DDR DDRJ #define PJ6_PWM NULL #undef PJ7 #define PJ7_PIN PINJ7 #define PJ7_RPORT PINJ #define PJ7_WPORT PORTJ #define PJ7_DDR DDRJ #define PJ7_PWM NULL #undef PK0 #define PK0_PIN PINK0 #define PK0_RPORT PINK #define PK0_WPORT PORTK #define PK0_DDR DDRK #define PK0_PWM NULL #undef PK1 #define PK1_PIN PINK1 #define PK1_RPORT PINK #define PK1_WPORT PORTK #define PK1_DDR DDRK #define PK1_PWM NULL #undef PK2 #define PK2_PIN PINK2 #define PK2_RPORT PINK #define PK2_WPORT PORTK #define PK2_DDR DDRK #define PK2_PWM NULL #undef PK3 #define PK3_PIN PINK3 #define PK3_RPORT PINK #define PK3_WPORT PORTK #define PK3_DDR DDRK #define PK3_PWM NULL #undef PK4 #define PK4_PIN PINK4 #define PK4_RPORT PINK #define PK4_WPORT PORTK #define PK4_DDR DDRK #define PK4_PWM NULL #undef PK5 #define PK5_PIN PINK5 #define PK5_RPORT PINK #define PK5_WPORT PORTK #define PK5_DDR DDRK #define PK5_PWM NULL #undef PK6 #define PK6_PIN PINK6 #define PK6_RPORT PINK #define PK6_WPORT PORTK #define PK6_DDR DDRK #define PK6_PWM NULL #undef PK7 #define PK7_PIN PINK7 #define PK7_RPORT PINK #define PK7_WPORT PORTK #define PK7_DDR DDRK #define PK7_PWM NULL #undef PL0 #define PL0_PIN PINL0 #define PL0_RPORT PINL #define PL0_WPORT PORTL #define PL0_DDR DDRL #define PL0_PWM NULL #undef PL1 #define PL1_PIN PINL1 #define PL1_RPORT PINL #define PL1_WPORT PORTL #define PL1_DDR DDRL #define PL1_PWM NULL #undef PL2 #define PL2_PIN PINL2 #define PL2_RPORT PINL #define PL2_WPORT PORTL #define PL2_DDR DDRL #define PL2_PWM NULL #undef PL3 #define PL3_PIN PINL3 #define PL3_RPORT PINL #define PL3_WPORT PORTL #define PL3_DDR DDRL #define PL3_PWM &OCR5AL #undef PL4 #define PL4_PIN PINL4 #define PL4_RPORT PINL #define PL4_WPORT PORTL #define PL4_DDR DDRL #define PL4_PWM &OCR5BL #undef PL5 #define PL5_PIN PINL5 #define PL5_RPORT PINL #define PL5_WPORT PORTL #define PL5_DDR DDRL #define PL5_PWM &OCR5CL #undef PL6 #define PL6_PIN PINL6 #define PL6_RPORT PINL #define PL6_WPORT PORTL #define PL6_DDR DDRL #define PL6_PWM NULL #undef PL7 #define PL7_PIN PINL7 #define PL7_RPORT PINL #define PL7_WPORT PORTL #define PL7_DDR DDRL #define PL7_PWM NULL #endif #if defined (__AVR_AT90USB646__) // SPI #define SCK DIO9 #define MISO DIO11 #define MOSI DIO10 #define SS DIO8 // change for your board #define DEBUG_LED DIO31 /* led D5 red */ /* pins */ #define DIO0_PIN PINA0 #define DIO0_RPORT PINA #define DIO0_WPORT PORTA #define DIO0_PWM NULL #define DIO0_DDR DDRA #define DIO1_PIN PINA1 #define DIO1_RPORT PINA #define DIO1_WPORT PORTA #define DIO1_PWM NULL #define DIO1_DDR DDRA #define DIO2_PIN PINA2 #define DIO2_RPORT PINA #define DIO2_WPORT PORTA #define DIO2_PWM NULL #define DIO2_DDR DDRA #define DIO3_PIN PINA3 #define DIO3_RPORT PINA #define DIO3_WPORT PORTA #define DIO3_PWM NULL #define DIO3_DDR DDRA #define DIO4_PIN PINA4 #define DIO4_RPORT PINA #define DIO4_WPORT PORTA #define DIO4_PWM NULL #define DIO4_DDR DDRA #define DIO5_PIN PINA5 #define DIO5_RPORT PINA #define DIO5_WPORT PORTA #define DIO5_PWM NULL #define DIO5_DDR DDRA #define DIO6_PIN PINA6 #define DIO6_RPORT PINA #define DIO6_WPORT PORTA #define DIO6_PWM NULL #define DIO6_DDR DDRA #define DIO7_PIN PINA7 #define DIO7_RPORT PINA #define DIO7_WPORT PORTA #define DIO7_PWM NULL #define DIO7_DDR DDRA #define DIO8_PIN PINB0 #define DIO8_RPORT PINB #define DIO8_WPORT PORTB #define DIO8_PWM NULL #define DIO8_DDR DDRB #define DIO9_PIN PINB1 #define DIO9_RPORT PINB #define DIO9_WPORT PORTB #define DIO9_PWM NULL #define DIO9_DDR DDRB #define DIO10_PIN PINB2 #define DIO10_RPORT PINB #define DIO10_WPORT PORTB #define DIO10_PWM NULL #define DIO10_DDR DDRB #define DIO11_PIN PINB3 #define DIO11_RPORT PINB #define DIO11_WPORT PORTB #define DIO11_PWM NULL #define DIO11_DDR DDRB #define DIO12_PIN PINB4 #define DIO12_RPORT PINB #define DIO12_WPORT PORTB #define DIO12_PWM NULL #define DIO12_DDR DDRB #define DIO13_PIN PINB5 #define DIO13_RPORT PINB #define DIO13_WPORT PORTB #define DIO13_PWM NULL #define DIO13_DDR DDRB #define DIO14_PIN PINB6 #define DIO14_RPORT PINB #define DIO14_WPORT PORTB #define DIO14_PWM NULL #define DIO14_DDR DDRB #define DIO15_PIN PINB7 #define DIO15_RPORT PINB #define DIO15_WPORT PORTB #define DIO15_PWM NULL #define DIO15_DDR DDRB #define DIO16_PIN PINC0 #define DIO16_RPORT PINC #define DIO16_WPORT PORTC #define DIO16_PWM NULL #define DIO16_DDR DDRC #define DIO17_PIN PINC1 #define DIO17_RPORT PINC #define DIO17_WPORT PORTC #define DIO17_PWM NULL #define DIO17_DDR DDRC #define DIO18_PIN PINC2 #define DIO18_RPORT PINC #define DIO18_WPORT PORTC #define DIO18_PWM NULL #define DIO18_DDR DDRC #define DIO19_PIN PINC3 #define DIO19_RPORT PINC #define DIO19_WPORT PORTC #define DIO19_PWM NULL #define DIO19_DDR DDRC #define DIO20_PIN PINC4 #define DIO20_RPORT PINC #define DIO20_WPORT PORTC #define DIO20_PWM NULL #define DIO20_DDR DDRC #define DIO21_PIN PINC5 #define DIO21_RPORT PINC #define DIO21_WPORT PORTC #define DIO21_PWM NULL #define DIO21_DDR DDRC #define DIO22_PIN PINC6 #define DIO22_RPORT PINC #define DIO22_WPORT PORTC #define DIO22_PWM NULL #define DIO22_DDR DDRC #define DIO23_PIN PINC7 #define DIO23_RPORT PINC #define DIO23_WPORT PORTC #define DIO23_PWM NULL #define DIO23_DDR DDRC #define DIO24_PIN PIND0 #define DIO24_RPORT PIND #define DIO24_WPORT PORTD #define DIO24_PWM NULL #define DIO24_DDR DDRD #define DIO25_PIN PIND1 #define DIO25_RPORT PIND #define DIO25_WPORT PORTD #define DIO25_PWM NULL #define DIO25_DDR DDRD #define DIO26_PIN PIND2 #define DIO26_RPORT PIND #define DIO26_WPORT PORTD #define DIO26_PWM NULL #define DIO26_DDR DDRD #define DIO27_PIN PIND3 #define DIO27_RPORT PIND #define DIO27_WPORT PORTD #define DIO27_PWM NULL #define DIO27_DDR DDRD #define DIO28_PIN PIND4 #define DIO28_RPORT PIND #define DIO28_WPORT PORTD #define DIO28_PWM NULL #define DIO28_DDR DDRD #define DIO29_PIN PIND5 #define DIO29_RPORT PIND #define DIO29_WPORT PORTD #define DIO29_PWM NULL #define DIO29_DDR DDRD #define DIO30_PIN PIND6 #define DIO30_RPORT PIND #define DIO30_WPORT PORTD #define DIO30_PWM NULL #define DIO30_DDR DDRD #define DIO31_PIN PIND7 #define DIO31_RPORT PIND #define DIO31_WPORT PORTD #define DIO31_PWM NULL #define DIO31_DDR DDRD #define DIO32_PIN PINE0 #define DIO32_RPORT PINE #define DIO32_WPORT PORTE #define DIO32_PWM NULL #define DIO32_DDR DDRE #define DIO33_PIN PINE1 #define DIO33_RPORT PINE #define DIO33_WPORT PORTE #define DIO33_PWM NULL #define DIO33_DDR DDRE #define DIO34_PIN PINE2 #define DIO34_RPORT PINE #define DIO34_WPORT PORTE #define DIO34_PWM NULL #define DIO34_DDR DDRE #define DIO35_PIN PINE3 #define DIO35_RPORT PINE #define DIO35_WPORT PORTE #define DIO35_PWM NULL #define DIO35_DDR DDRE #define DIO36_PIN PINE4 #define DIO36_RPORT PINE #define DIO36_WPORT PORTE #define DIO36_PWM NULL #define DIO36_DDR DDRE #define DIO37_PIN PINE5 #define DIO37_RPORT PINE #define DIO37_WPORT PORTE #define DIO37_PWM NULL #define DIO37_DDR DDRE #define DIO38_PIN PINE6 #define DIO38_RPORT PINE #define DIO38_WPORT PORTE #define DIO38_PWM NULL #define DIO38_DDR DDRE #define DIO39_PIN PINE7 #define DIO39_RPORT PINE #define DIO39_WPORT PORTE #define DIO39_PWM NULL #define DIO39_DDR DDRE #define AIO0_PIN PINF0 #define AIO0_RPORT PINF #define AIO0_WPORT PORTF #define AIO0_PWM NULL #define AIO0_DDR DDRF #define AIO1_PIN PINF1 #define AIO1_RPORT PINF #define AIO1_WPORT PORTF #define AIO1_PWM NULL #define AIO1_DDR DDRF #define AIO2_PIN PINF2 #define AIO2_RPORT PINF #define AIO2_WPORT PORTF #define AIO2_PWM NULL #define AIO2_DDR DDRF #define AIO3_PIN PINF3 #define AIO3_RPORT PINF #define AIO3_WPORT PORTF #define AIO3_PWM NULL #define AIO3_DDR DDRF #define AIO4_PIN PINF4 #define AIO4_RPORT PINF #define AIO4_WPORT PORTF #define AIO4_PWM NULL #define AIO4_DDR DDRF #define AIO5_PIN PINF5 #define AIO5_RPORT PINF #define AIO5_WPORT PORTF #define AIO5_PWM NULL #define AIO5_DDR DDRF #define AIO6_PIN PINF6 #define AIO6_RPORT PINF #define AIO6_WPORT PORTF #define AIO6_PWM NULL #define AIO6_DDR DDRF #define AIO7_PIN PINF7 #define AIO7_RPORT PINF #define AIO7_WPORT PORTF #define AIO7_PWM NULL #define AIO7_DDR DDRF #define DIO40_PIN PINF0 #define DIO40_RPORT PINF #define DIO40_WPORT PORTF #define DIO40_PWM NULL #define DIO40_DDR DDRF #define DIO41_PIN PINF1 #define DIO41_RPORT PINF #define DIO41_WPORT PORTF #define DIO41_PWM NULL #define DIO41_DDR DDRF #define DIO42_PIN PINF2 #define DIO42_RPORT PINF #define DIO42_WPORT PORTF #define DIO42_PWM NULL #define DIO42_DDR DDRF #define DIO43_PIN PINF3 #define DIO43_RPORT PINF #define DIO43_WPORT PORTF #define DIO43_PWM NULL #define DIO43_DDR DDRF #define DIO44_PIN PINF4 #define DIO44_RPORT PINF #define DIO44_WPORT PORTF #define DIO44_PWM NULL #define DIO44_DDR DDRF #define DIO45_PIN PINF5 #define DIO45_RPORT PINF #define DIO45_WPORT PORTF #define DIO45_PWM NULL #define DIO45_DDR DDRF #define DIO46_PIN PINF6 #define DIO46_RPORT PINF #define DIO46_WPORT PORTF #define DIO46_PWM NULL #define DIO46_DDR DDRF #define DIO47_PIN PINF7 #define DIO47_RPORT PINF #define DIO47_WPORT PORTF #define DIO47_PWM NULL #define DIO47_DDR DDRF #undef PA0 #define PA0_PIN PINA0 #define PA0_RPORT PINA #define PA0_WPORT PORTA #define PA0_PWM NULL #define PA0_DDR DDRA #undef PA1 #define PA1_PIN PINA1 #define PA1_RPORT PINA #define PA1_WPORT PORTA #define PA1_PWM NULL #define PA1_DDR DDRA #undef PA2 #define PA2_PIN PINA2 #define PA2_RPORT PINA #define PA2_WPORT PORTA #define PA2_PWM NULL #define PA2_DDR DDRA #undef PA3 #define PA3_PIN PINA3 #define PA3_RPORT PINA #define PA3_WPORT PORTA #define PA3_PWM NULL #define PA3_DDR DDRA #undef PA4 #define PA4_PIN PINA4 #define PA4_RPORT PINA #define PA4_WPORT PORTA #define PA4_PWM NULL #define PA4_DDR DDRA #undef PA5 #define PA5_PIN PINA5 #define PA5_RPORT PINA #define PA5_WPORT PORTA #define PA5_PWM NULL #define PA5_DDR DDRA #undef PA6 #define PA6_PIN PINA6 #define PA6_RPORT PINA #define PA6_WPORT PORTA #define PA6_PWM NULL #define PA6_DDR DDRA #undef PA7 #define PA7_PIN PINA7 #define PA7_RPORT PINA #define PA7_WPORT PORTA #define PA7_PWM NULL #define PA7_DDR DDRA #undef PB0 #define PB0_PIN PINB0 #define PB0_RPORT PINB #define PB0_WPORT PORTB #define PB0_PWM NULL #define PB0_DDR DDRB #undef PB1 #define PB1_PIN PINB1 #define PB1_RPORT PINB #define PB1_WPORT PORTB #define PB1_PWM NULL #define PB1_DDR DDRB #undef PB2 #define PB2_PIN PINB2 #define PB2_RPORT PINB #define PB2_WPORT PORTB #define PB2_PWM NULL #define PB2_DDR DDRB #undef PB3 #define PB3_PIN PINB3 #define PB3_RPORT PINB #define PB3_WPORT PORTB #define PB3_PWM NULL #define PB3_DDR DDRB #undef PB4 #define PB4_PIN PINB4 #define PB4_RPORT PINB #define PB4_WPORT PORTB #define PB4_PWM NULL #define PB4_DDR DDRB #undef PB5 #define PB5_PIN PINB5 #define PB5_RPORT PINB #define PB5_WPORT PORTB #define PB5_PWM NULL #define PB5_DDR DDRB #undef PB6 #define PB6_PIN PINB6 #define PB6_RPORT PINB #define PB6_WPORT PORTB #define PB6_PWM NULL #define PB6_DDR DDRB #undef PB7 #define PB7_PIN PINB7 #define PB7_RPORT PINB #define PB7_WPORT PORTB #define PB7_PWM NULL #define PB7_DDR DDRB #undef PC0 #define PC0_PIN PINC0 #define PC0_RPORT PINC #define PC0_WPORT PORTC #define PC0_PWM NULL #define PC0_DDR DDRC #undef PC1 #define PC1_PIN PINC1 #define PC1_RPORT PINC #define PC1_WPORT PORTC #define PC1_PWM NULL #define PC1_DDR DDRC #undef PC2 #define PC2_PIN PINC2 #define PC2_RPORT PINC #define PC2_WPORT PORTC #define PC2_PWM NULL #define PC2_DDR DDRC #undef PC3 #define PC3_PIN PINC3 #define PC3_RPORT PINC #define PC3_WPORT PORTC #define PC3_PWM NULL #define PC3_DDR DDRC #undef PC4 #define PC4_PIN PINC4 #define PC4_RPORT PINC #define PC4_WPORT PORTC #define PC4_PWM NULL #define PC4_DDR DDRC #undef PC5 #define PC5_PIN PINC5 #define PC5_RPORT PINC #define PC5_WPORT PORTC #define PC5_PWM NULL #define PC5_DDR DDRC #undef PC6 #define PC6_PIN PINC6 #define PC6_RPORT PINC #define PC6_WPORT PORTC #define PC6_PWM NULL #define PC6_DDR DDRC #undef PC7 #define PC7_PIN PINC7 #define PC7_RPORT PINC #define PC7_WPORT PORTC #define PC7_PWM NULL #define PC7_DDR DDRC #undef PD0 #define PD0_PIN PIND0 #define PD0_RPORT PIND #define PD0_WPORT PORTD #define PD0_PWM NULL #define PD0_DDR DDRD #undef PD1 #define PD1_PIN PIND1 #define PD1_RPORT PIND #define PD1_WPORT PORTD #define PD1_PWM NULL #define PD1_DDR DDRD #undef PD2 #define PD2_PIN PIND2 #define PD2_RPORT PIND #define PD2_WPORT PORTD #define PD2_PWM NULL #define PD2_DDR DDRD #undef PD3 #define PD3_PIN PIND3 #define PD3_RPORT PIND #define PD3_WPORT PORTD #define PD3_PWM NULL #define PD3_DDR DDRD #undef PD4 #define PD4_PIN PIND4 #define PD4_RPORT PIND #define PD4_WPORT PORTD #define PD4_PWM NULL #define PD4_DDR DDRD #undef PD5 #define PD5_PIN PIND5 #define PD5_RPORT PIND #define PD5_WPORT PORTD #define PD5_PWM NULL #define PD5_DDR DDRD #undef PD6 #define PD6_PIN PIND6 #define PD6_RPORT PIND #define PD6_WPORT PORTD #define PD6_PWM NULL #define PD6_DDR DDRD #undef PD7 #define PD7_PIN PIND7 #define PD7_RPORT PIND #define PD7_WPORT PORTD #define PD7_PWM NULL #define PD7_DDR DDRD #undef PE0 #define PE0_PIN PINE0 #define PE0_RPORT PINE #define PE0_WPORT PORTE #define PE0_PWM NULL #define PE0_DDR DDRE #undef PE1 #define PE1_PIN PINE1 #define PE1_RPORT PINE #define PE1_WPORT PORTE #define PE1_PWM NULL #define PE1_DDR DDRE #undef PE2 #define PE2_PIN PINE2 #define PE2_RPORT PINE #define PE2_WPORT PORTE #define PE2_PWM NULL #define PE2_DDR DDRE #undef PE3 #define PE3_PIN PINE3 #define PE3_RPORT PINE #define PE3_WPORT PORTE #define PE3_PWM NULL #define PE3_DDR DDRE #undef PE4 #define PE4_PIN PINE4 #define PE4_RPORT PINE #define PE4_WPORT PORTE #define PE4_PWM NULL #define PE4_DDR DDRE #undef PE5 #define PE5_PIN PINE5 #define PE5_RPORT PINE #define PE5_WPORT PORTE #define PE5_PWM NULL #define PE5_DDR DDRE #undef PE6 #define PE6_PIN PINE6 #define PE6_RPORT PINE #define PE6_WPORT PORTE #define PE6_PWM NULL #define PE6_DDR DDRE #undef PE7 #define PE7_PIN PINE7 #define PE7_RPORT PINE #define PE7_WPORT PORTE #define PE7_PWM NULL #define PE7_DDR DDRE #undef PF0 #define PF0_PIN PINF0 #define PF0_RPORT PINF #define PF0_WPORT PORTF #define PF0_PWM NULL #define PF0_DDR DDRF #undef PF1 #define PF1_PIN PINF1 #define PF1_RPORT PINF #define PF1_WPORT PORTF #define PF1_PWM NULL #define PF1_DDR DDRF #undef PF2 #define PF2_PIN PINF2 #define PF2_RPORT PINF #define PF2_WPORT PORTF #define PF2_PWM NULL #define PF2_DDR DDRF #undef PF3 #define PF3_PIN PINF3 #define PF3_RPORT PINF #define PF3_WPORT PORTF #define PF3_PWM NULL #define PF3_DDR DDRF #undef PF4 #define PF4_PIN PINF4 #define PF4_RPORT PINF #define PF4_WPORT PORTF #define PF4_PWM NULL #define PF4_DDR DDRF #undef PF5 #define PF5_PIN PINF5 #define PF5_RPORT PINF #define PF5_WPORT PORTF #define PF5_PWM NULL #define PF5_DDR DDRF #undef PF6 #define PF6_PIN PINF6 #define PF6_RPORT PINF #define PF6_WPORT PORTF #define PF6_PWM NULL #define PF6_DDR DDRF #undef PF7 #define PF7_PIN PINF7 #define PF7_RPORT PINF #define PF7_WPORT PORTF #define PF7_PWM NULL #define PF7_DDR DDRF #endif #if defined (__AVR_AT90USB1287__) || defined (__AVR_AT90USB1286__) // SPI #define SCK DIO9 #define MISO DIO11 #define MOSI DIO10 #define SS DIO8 // change for your board #define DEBUG_LED DIO31 /* led D5 red */ /* pins */ #define DIO0_PIN PIND0 #define DIO0_RPORT PIND #define DIO0_WPORT PORTD #define DIO0_PWM NULL #define DIO0_DDR DDRD #define DIO1_PIN PIND1 #define DIO1_RPORT PIND #define DIO1_WPORT PORTD #define DIO1_PWM NULL #define DIO1_DDR DDRD #define DIO2_PIN PIND2 #define DIO2_RPORT PIND #define DIO2_WPORT PORTD #define DIO2_PWM NULL #define DIO2_DDR DDRD #define DIO3_PIN PIND3 #define DIO3_RPORT PIND #define DIO3_WPORT PORTD #define DIO3_PWM NULL #define DIO3_DDR DDRD #define DIO4_PIN PIND4 #define DIO4_RPORT PIND #define DIO4_WPORT PORTD #define DIO4_PWM NULL #define DIO4_DDR DDRD #define DIO5_PIN PIND5 #define DIO5_RPORT PIND #define DIO5_WPORT PORTD #define DIO5_PWM NULL #define DIO5_DDR DDRD #define DIO6_PIN PIND6 #define DIO6_RPORT PIND #define DIO6_WPORT PORTD #define DIO6_PWM NULL #define DIO6_DDR DDRD #define DIO7_PIN PIND7 #define DIO7_RPORT PIND #define DIO7_WPORT PORTD #define DIO7_PWM NULL #define DIO7_DDR DDRD #define DIO8_PIN PINE0 #define DIO8_RPORT PINE #define DIO8_WPORT PORTE #define DIO8_PWM NULL #define DIO8_DDR DDRE #define DIO9_PIN PINE1 #define DIO9_RPORT PINE #define DIO9_WPORT PORTE #define DIO9_PWM NULL #define DIO9_DDR DDRE #define DIO10_PIN PINC0 #define DIO10_RPORT PINC #define DIO10_WPORT PORTC #define DIO10_PWM NULL #define DIO10_DDR DDRC #define DIO11_PIN PINC1 #define DIO11_RPORT PINC #define DIO11_WPORT PORTC #define DIO11_PWM NULL #define DIO11_DDR DDRC #define DIO12_PIN PINC2 #define DIO12_RPORT PINC #define DIO12_WPORT PORTC #define DIO12_PWM NULL #define DIO12_DDR DDRC #define DIO13_PIN PINC3 #define DIO13_RPORT PINC #define DIO13_WPORT PORTC #define DIO13_PWM NULL #define DIO13_DDR DDRC #define DIO14_PIN PINC4 #define DIO14_RPORT PINC #define DIO14_WPORT PORTC #define DIO14_PWM NULL #define DIO14_DDR DDRC #define DIO15_PIN PINC5 #define DIO15_RPORT PINC #define DIO15_WPORT PORTC #define DIO15_PWM NULL #define DIO15_DDR DDRC #define DIO16_PIN PINC6 #define DIO16_RPORT PINC #define DIO16_WPORT PORTC #define DIO16_PWM NULL #define DIO16_DDR DDRC #define DIO17_PIN PINC7 #define DIO17_RPORT PINC #define DIO17_WPORT PORTC #define DIO17_PWM NULL #define DIO17_DDR DDRC #define DIO18_PIN PINE6 #define DIO18_RPORT PINE #define DIO18_WPORT PORTE #define DIO18_PWM NULL #define DIO18_DDR DDRE #define DIO19_PIN PINE7 #define DIO19_RPORT PINE #define DIO19_WPORT PORTE #define DIO19_PWM NULL #define DIO19_DDR DDRE #define DIO20_PIN PINB0 #define DIO20_RPORT PINB #define DIO20_WPORT PORTB #define DIO20_PWM NULL #define DIO20_DDR DDRB #define DIO21_PIN PINB1 #define DIO21_RPORT PINB #define DIO21_WPORT PORTB #define DIO21_PWM NULL #define DIO21_DDR DDRB #define DIO22_PIN PINB2 #define DIO22_RPORT PINB #define DIO22_WPORT PORTB #define DIO22_PWM NULL #define DIO22_DDR DDRB #define DIO23_PIN PINB3 #define DIO23_RPORT PINB #define DIO23_WPORT PORTB #define DIO23_PWM NULL #define DIO23_DDR DDRB #define DIO24_PIN PINB4 #define DIO24_RPORT PINB #define DIO24_WPORT PORTB #define DIO24_PWM NULL #define DIO24_DDR DDRB #define DIO25_PIN PINB5 #define DIO25_RPORT PINB #define DIO25_WPORT PORTB #define DIO25_PWM NULL #define DIO25_DDR DDRB #define DIO26_PIN PINB6 #define DIO26_RPORT PINB #define DIO26_WPORT PORTB #define DIO26_PWM NULL #define DIO26_DDR DDRB #define DIO27_PIN PINB7 #define DIO27_RPORT PINB #define DIO27_WPORT PORTB #define DIO27_PWM NULL #define DIO27_DDR DDRB #define DIO28_PIN PINA0 #define DIO28_RPORT PINA #define DIO28_WPORT PORTA #define DIO28_PWM NULL #define DIO28_DDR DDRA #define DIO29_PIN PINA1 #define DIO29_RPORT PINA #define DIO29_WPORT PORTA #define DIO29_PWM NULL #define DIO29_DDR DDRA #define DIO30_PIN PINA2 #define DIO30_RPORT PINA #define DIO30_WPORT PORTA #define DIO30_PWM NULL #define DIO30_DDR DDRA #define DIO31_PIN PINA3 #define DIO31_RPORT PINA #define DIO31_WPORT PORTA #define DIO31_PWM NULL #define DIO31_DDR DDRA #define DIO32_PIN PINA4 #define DIO32_RPORT PINA #define DIO32_WPORT PORTA #define DIO32_PWM NULL #define DIO32_DDR DDRA #define DIO33_PIN PINA5 #define DIO33_RPORT PINA #define DIO33_WPORT PORTA #define DIO33_PWM NULL #define DIO33_DDR DDRA #define DIO34_PIN PINA6 #define DIO34_RPORT PINA #define DIO34_WPORT PORTA #define DIO34_PWM NULL #define DIO34_DDR DDRA #define DIO35_PIN PINA7 #define DIO35_RPORT PINA #define DIO35_WPORT PORTA #define DIO35_PWM NULL #define DIO35_DDR DDRA #define DIO36_PIN PINE4 #define DIO36_RPORT PINE #define DIO36_WPORT PORTE #define DIO36_PWM NULL #define DIO36_DDR DDRE #define DIO37_PIN PINE5 #define DIO37_RPORT PINE #define DIO37_WPORT PORTE #define DIO37_PWM NULL #define DIO37_DDR DDRE #define DIO38_PIN PINF0 #define DIO38_RPORT PINF #define DIO38_WPORT PORTF #define DIO38_PWM NULL #define DIO38_DDR DDRF #define DIO39_PIN PINF1 #define DIO39_RPORT PINF #define DIO39_WPORT PORTF #define DIO39_PWM NULL #define DIO39_DDR DDRF #define DIO40_PIN PINF2 #define DIO40_RPORT PINF #define DIO40_WPORT PORTF #define DIO40_PWM NULL #define DIO40_DDR DDRF #define DIO41_PIN PINF3 #define DIO41_RPORT PINF #define DIO41_WPORT PORTF #define DIO41_PWM NULL #define DIO41_DDR DDRF #define DIO42_PIN PINF4 #define DIO42_RPORT PINF #define DIO42_WPORT PORTF #define DIO42_PWM NULL #define DIO42_DDR DDRF #define DIO43_PIN PINF5 #define DIO43_RPORT PINF #define DIO43_WPORT PORTF #define DIO43_PWM NULL #define DIO43_DDR DDRF #define DIO44_PIN PINF6 #define DIO44_RPORT PINF #define DIO44_WPORT PORTF #define DIO44_PWM NULL #define DIO44_DDR DDRF #define DIO45_PIN PINF7 #define DIO45_RPORT PINF #define DIO45_WPORT PORTF #define DIO45_PWM NULL #define DIO45_DDR DDRF #define AIO0_PIN PINF0 #define AIO0_RPORT PINF #define AIO0_WPORT PORTF #define AIO0_PWM NULL #define AIO0_DDR DDRF #define AIO1_PIN PINF1 #define AIO1_RPORT PINF #define AIO1_WPORT PORTF #define AIO1_PWM NULL #define AIO1_DDR DDRF #define AIO2_PIN PINF2 #define AIO2_RPORT PINF #define AIO2_WPORT PORTF #define AIO2_PWM NULL #define AIO2_DDR DDRF #define AIO3_PIN PINF3 #define AIO3_RPORT PINF #define AIO3_WPORT PORTF #define AIO3_PWM NULL #define AIO3_DDR DDRF #define AIO4_PIN PINF4 #define AIO4_RPORT PINF #define AIO4_WPORT PORTF #define AIO4_PWM NULL #define AIO4_DDR DDRF #define AIO5_PIN PINF5 #define AIO5_RPORT PINF #define AIO5_WPORT PORTF #define AIO5_PWM NULL #define AIO5_DDR DDRF #define AIO6_PIN PINF6 #define AIO6_RPORT PINF #define AIO6_WPORT PORTF #define AIO6_PWM NULL #define AIO6_DDR DDRF #define AIO7_PIN PINF7 #define AIO7_RPORT PINF #define AIO7_WPORT PORTF #define AIO7_PWM NULL #define AIO7_DDR DDRF //-- Begin not supported by Teensyduino //-- don't use Arduino functions on these pins pinMode/digitalWrite/etc #define DIO46_PIN PINE2 #define DIO46_RPORT PINE #define DIO46_WPORT PORTE #define DIO46_PWM NULL #define DIO46_DDR DDRE #define DIO47_PIN PINE3 #define DIO47_RPORT PINE #define DIO47_WPORT PORTE #define DIO47_PWM NULL #define DIO47_DDR DDRE //-- end not supported by Teensyduino #undef PA0 #define PA0_PIN PINA0 #define PA0_RPORT PINA #define PA0_WPORT PORTA #define PA0_PWM NULL #define PA0_DDR DDRA #undef PA1 #define PA1_PIN PINA1 #define PA1_RPORT PINA #define PA1_WPORT PORTA #define PA1_PWM NULL #define PA1_DDR DDRA #undef PA2 #define PA2_PIN PINA2 #define PA2_RPORT PINA #define PA2_WPORT PORTA #define PA2_PWM NULL #define PA2_DDR DDRA #undef PA3 #define PA3_PIN PINA3 #define PA3_RPORT PINA #define PA3_WPORT PORTA #define PA3_PWM NULL #define PA3_DDR DDRA #undef PA4 #define PA4_PIN PINA4 #define PA4_RPORT PINA #define PA4_WPORT PORTA #define PA4_PWM NULL #define PA4_DDR DDRA #undef PA5 #define PA5_PIN PINA5 #define PA5_RPORT PINA #define PA5_WPORT PORTA #define PA5_PWM NULL #define PA5_DDR DDRA #undef PA6 #define PA6_PIN PINA6 #define PA6_RPORT PINA #define PA6_WPORT PORTA #define PA6_PWM NULL #define PA6_DDR DDRA #undef PA7 #define PA7_PIN PINA7 #define PA7_RPORT PINA #define PA7_WPORT PORTA #define PA7_PWM NULL #define PA7_DDR DDRA #undef PB0 #define PB0_PIN PINB0 #define PB0_RPORT PINB #define PB0_WPORT PORTB #define PB0_PWM NULL #define PB0_DDR DDRB #undef PB1 #define PB1_PIN PINB1 #define PB1_RPORT PINB #define PB1_WPORT PORTB #define PB1_PWM NULL #define PB1_DDR DDRB #undef PB2 #define PB2_PIN PINB2 #define PB2_RPORT PINB #define PB2_WPORT PORTB #define PB2_PWM NULL #define PB2_DDR DDRB #undef PB3 #define PB3_PIN PINB3 #define PB3_RPORT PINB #define PB3_WPORT PORTB #define PB3_PWM NULL #define PB3_DDR DDRB #undef PB4 #define PB4_PIN PINB4 #define PB4_RPORT PINB #define PB4_WPORT PORTB #define PB4_PWM NULL #define PB4_DDR DDRB #undef PB5 #define PB5_PIN PINB5 #define PB5_RPORT PINB #define PB5_WPORT PORTB #define PB5_PWM NULL #define PB5_DDR DDRB #undef PB6 #define PB6_PIN PINB6 #define PB6_RPORT PINB #define PB6_WPORT PORTB #define PB6_PWM NULL #define PB6_DDR DDRB #undef PB7 #define PB7_PIN PINB7 #define PB7_RPORT PINB #define PB7_WPORT PORTB #define PB7_PWM NULL #define PB7_DDR DDRB #undef PC0 #define PC0_PIN PINC0 #define PC0_RPORT PINC #define PC0_WPORT PORTC #define PC0_PWM NULL #define PC0_DDR DDRC #undef PC1 #define PC1_PIN PINC1 #define PC1_RPORT PINC #define PC1_WPORT PORTC #define PC1_PWM NULL #define PC1_DDR DDRC #undef PC2 #define PC2_PIN PINC2 #define PC2_RPORT PINC #define PC2_WPORT PORTC #define PC2_PWM NULL #define PC2_DDR DDRC #undef PC3 #define PC3_PIN PINC3 #define PC3_RPORT PINC #define PC3_WPORT PORTC #define PC3_PWM NULL #define PC3_DDR DDRC #undef PC4 #define PC4_PIN PINC4 #define PC4_RPORT PINC #define PC4_WPORT PORTC #define PC4_PWM NULL #define PC4_DDR DDRC #undef PC5 #define PC5_PIN PINC5 #define PC5_RPORT PINC #define PC5_WPORT PORTC #define PC5_PWM NULL #define PC5_DDR DDRC #undef PC6 #define PC6_PIN PINC6 #define PC6_RPORT PINC #define PC6_WPORT PORTC #define PC6_PWM NULL #define PC6_DDR DDRC #undef PC7 #define PC7_PIN PINC7 #define PC7_RPORT PINC #define PC7_WPORT PORTC #define PC7_PWM NULL #define PC7_DDR DDRC #undef PD0 #define PD0_PIN PIND0 #define PD0_RPORT PIND #define PD0_WPORT PORTD #define PD0_PWM NULL #define PD0_DDR DDRD #undef PD1 #define PD1_PIN PIND1 #define PD1_RPORT PIND #define PD1_WPORT PORTD #define PD1_PWM NULL #define PD1_DDR DDRD #undef PD2 #define PD2_PIN PIND2 #define PD2_RPORT PIND #define PD2_WPORT PORTD #define PD2_PWM NULL #define PD2_DDR DDRD #undef PD3 #define PD3_PIN PIND3 #define PD3_RPORT PIND #define PD3_WPORT PORTD #define PD3_PWM NULL #define PD3_DDR DDRD #undef PD4 #define PD4_PIN PIND4 #define PD4_RPORT PIND #define PD4_WPORT PORTD #define PD4_PWM NULL #define PD4_DDR DDRD #undef PD5 #define PD5_PIN PIND5 #define PD5_RPORT PIND #define PD5_WPORT PORTD #define PD5_PWM NULL #define PD5_DDR DDRD #undef PD6 #define PD6_PIN PIND6 #define PD6_RPORT PIND #define PD6_WPORT PORTD #define PD6_PWM NULL #define PD6_DDR DDRD #undef PD7 #define PD7_PIN PIND7 #define PD7_RPORT PIND #define PD7_WPORT PORTD #define PD7_PWM NULL #define PD7_DDR DDRD #undef PE0 #define PE0_PIN PINE0 #define PE0_RPORT PINE #define PE0_WPORT PORTE #define PE0_PWM NULL #define PE0_DDR DDRE #undef PE1 #define PE1_PIN PINE1 #define PE1_RPORT PINE #define PE1_WPORT PORTE #define PE1_PWM NULL #define PE1_DDR DDRE #undef PE2 #define PE2_PIN PINE2 #define PE2_RPORT PINE #define PE2_WPORT PORTE #define PE2_PWM NULL #define PE2_DDR DDRE #undef PE3 #define PE3_PIN PINE3 #define PE3_RPORT PINE #define PE3_WPORT PORTE #define PE3_PWM NULL #define PE3_DDR DDRE #undef PE4 #define PE4_PIN PINE4 #define PE4_RPORT PINE #define PE4_WPORT PORTE #define PE4_PWM NULL #define PE4_DDR DDRE #undef PE5 #define PE5_PIN PINE5 #define PE5_RPORT PINE #define PE5_WPORT PORTE #define PE5_PWM NULL #define PE5_DDR DDRE #undef PE6 #define PE6_PIN PINE6 #define PE6_RPORT PINE #define PE6_WPORT PORTE #define PE6_PWM NULL #define PE6_DDR DDRE #undef PE7 #define PE7_PIN PINE7 #define PE7_RPORT PINE #define PE7_WPORT PORTE #define PE7_PWM NULL #define PE7_DDR DDRE #undef PF0 #define PF0_PIN PINF0 #define PF0_RPORT PINF #define PF0_WPORT PORTF #define PF0_PWM NULL #define PF0_DDR DDRF #undef PF1 #define PF1_PIN PINF1 #define PF1_RPORT PINF #define PF1_WPORT PORTF #define PF1_PWM NULL #define PF1_DDR DDRF #undef PF2 #define PF2_PIN PINF2 #define PF2_RPORT PINF #define PF2_WPORT PORTF #define PF2_PWM NULL #define PF2_DDR DDRF #undef PF3 #define PF3_PIN PINF3 #define PF3_RPORT PINF #define PF3_WPORT PORTF #define PF3_PWM NULL #define PF3_DDR DDRF #undef PF4 #define PF4_PIN PINF4 #define PF4_RPORT PINF #define PF4_WPORT PORTF #define PF4_PWM NULL #define PF4_DDR DDRF #undef PF5 #define PF5_PIN PINF5 #define PF5_RPORT PINF #define PF5_WPORT PORTF #define PF5_PWM NULL #define PF5_DDR DDRF #undef PF6 #define PF6_PIN PINF6 #define PF6_RPORT PINF #define PF6_WPORT PORTF #define PF6_PWM NULL #define PF6_DDR DDRF #undef PF7 #define PF7_PIN PINF7 #define PF7_RPORT PINF #define PF7_WPORT PORTF #define PF7_PWM NULL #define PF7_DDR DDRF #endif #ifndef DIO0_PIN #error pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please submit a pull request #endif #endif /* _ARDUINO_H */ ================================================ FILE: Sprinter/heater.cpp ================================================ /* Reprap heater funtions based on Sprinter This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ /* This softwarepart for Heatercontrol is based on Sprinter big thanks to kliment (https://github.com/kliment/Sprinter) */ #include #include "heater.h" #include "fastio.h" #include "pins.h" #include "Sprinter.h" #ifdef CONTROLLERFAN_PIN void controllerFan(void); #endif #ifdef EXTRUDERFAN_PIN void extruderFan(void); #endif // Manage heater variables. For a thermistor or AD595 thermocouple, raw values refer to the // reading from the analog pin. For a MAX6675 thermocouple, the raw value is the temperature in 0.25 // degree increments (i.e. 100=25 deg). int target_raw = 0; int target_temp = 0; int current_raw = 0; int current_raw_maxval = -32000; int current_raw_minval = 32000; int tt_maxval; int tt_minval; int target_bed_raw = 0; int current_bed_raw = 0; unsigned long previous_millis_heater, previous_millis_bed_heater, previous_millis_monitor; #ifdef PIDTEMP volatile unsigned char g_heater_pwm_val = 0; //unsigned char PWM_off_time = 0; //unsigned char PWM_out_on = 0; int temp_iState = 0; int temp_dState = 0; int prev_temp = 0; int pTerm; int iTerm; int dTerm; //int output; int error; int heater_duty = 0; int temp_iState_min = 256L * -PID_INTEGRAL_DRIVE_MAX / PID_IGAIN; int temp_iState_max = 256L * PID_INTEGRAL_DRIVE_MAX / PID_IGAIN; #endif #if defined(FAN_SOFT_PWM) && (FAN_PIN > -1) volatile unsigned char g_fan_pwm_val = 0; #endif #ifdef AUTOTEMP float autotemp_max=AUTO_TEMP_MAX; float autotemp_min=AUTO_TEMP_MIN; float autotemp_factor=AUTO_TEMP_FACTOR; int autotemp_setpoint=0; bool autotemp_enabled=true; #endif #ifndef HEATER_CURRENT #define HEATER_CURRENT 255 #endif #ifdef SMOOTHING uint32_t nma = 0; #endif #ifdef WATCHPERIOD int watch_raw = -1000; unsigned long watchmillis = 0; #endif #ifdef MINTEMP int minttemp = temp2analogh(MINTEMP); #endif #ifdef MAXTEMP int maxttemp = temp2analogh(MAXTEMP); #endif #define HEAT_INTERVAL 250 #ifdef HEATER_USES_MAX6675 unsigned long max6675_previous_millis = 0; int max6675_temp = 2000; int read_max6675() { if (millis() - max6675_previous_millis < HEAT_INTERVAL) return max6675_temp; max6675_previous_millis = millis(); max6675_temp = 0; #ifdef PRR PRR &= ~(1<> 3; } return max6675_temp; } #endif //------------------------------------------------------------------------ // Soft PWM for Heater and FAN //------------------------------------------------------------------------ #if defined(PID_SOFT_PWM) || (defined(FAN_SOFT_PWM) && (FAN_PIN > -1)) void init_Timer2_softpwm(void) { // This is a simple SOFT PWM with 500 Hz for Extruder Heating TIFR2 = (1 << TOV2); // clear interrupt flag TCCR2B = (1 << CS22) | (1 << CS20); // start timer (ck/128 prescalar) TCCR2A = 0;//(1 << WGM21); // Normal mode TIMSK2 |= (1 << TOIE2); #ifdef PID_SOFT_PWM OCR2A = 128; // We want to have at least 500Hz or else it gets choppy TIMSK2 |= (1 << OCIE2A); // enable timer2 output compare match interrupt #endif #if defined(FAN_SOFT_PWM) && (FAN_PIN > -1) OCR2B = 128; // We want to have at least 500Hz or else it gets choppy TIMSK2 |= (1 << OCIE2B); // enable timer2 output compare match interrupt #endif } #endif #if defined(PID_SOFT_PWM) || (defined(FAN_SOFT_PWM) && (FAN_PIN > -1)) ISR(TIMER2_OVF_vect) { //-------------------------------------- // Soft PWM, Heater, start PWM cycle //-------------------------------------- #ifdef PID_SOFT_PWM if(g_heater_pwm_val >= 2) { #if LED_PIN > -1 WRITE(LED_PIN,HIGH); #endif WRITE(HEATER_0_PIN,HIGH); if(g_heater_pwm_val <= 253) OCR2A = g_heater_pwm_val; else OCR2A = 192; } else { #if LED_PIN > -1 WRITE(LED_PIN,LOW); #endif WRITE(HEATER_0_PIN,LOW); OCR2A = 192; } #endif //-------------------------------------- // Soft PWM, Fan, start PWM cycle //-------------------------------------- #if defined(FAN_SOFT_PWM) && (FAN_PIN > -1) if(g_fan_pwm_val >= 2) { #if (FAN_PIN > -1) WRITE(FAN_PIN,HIGH); #endif if(g_fan_pwm_val <= 253) OCR2B = g_fan_pwm_val; else OCR2B = 128; } else { #if (FAN_PIN > -1) WRITE(FAN_PIN,LOW); #endif OCR2B = 128; } #endif } #endif #ifdef PID_SOFT_PWM ISR(TIMER2_COMPA_vect) { if(g_heater_pwm_val > 253) { #if LED_PIN > -1 WRITE(LED_PIN,HIGH); #endif WRITE(HEATER_0_PIN,HIGH); } else { #if LED_PIN > -1 WRITE(LED_PIN,LOW); #endif WRITE(HEATER_0_PIN,LOW); } } #endif #if defined(FAN_SOFT_PWM) && (FAN_PIN > -1) ISR(TIMER2_COMPB_vect) { if(g_fan_pwm_val > 253) { #if (FAN_PIN > -1) WRITE(FAN_PIN,HIGH); #endif } else { #if (FAN_PIN > -1) WRITE(FAN_PIN,LOW); #endif } } #endif //--------------------END SOFT PWM--------------------------- //-------------------- START PID AUTOTUNE --------------------------- // Based on PID relay test // Thanks to Erik van der Zalm for this idea to use it for Marlin // Some information see: // http://brettbeauregard.com/blog/2012/01/arduino-pid-autotune-library/ //------------------------------------------------------------------ #ifdef PID_AUTOTUNE void PID_autotune(int PIDAT_test_temp) { float PIDAT_input = 0; int PIDAT_input_help = 0; unsigned char PIDAT_count_input = 0; float PIDAT_max, PIDAT_min; unsigned char PIDAT_PWM_val = HEATER_CURRENT; unsigned char PIDAT_cycles=0; bool PIDAT_heating = true; unsigned long PIDAT_temp_millis = millis(); unsigned long PIDAT_t1=PIDAT_temp_millis; unsigned long PIDAT_t2=PIDAT_temp_millis; unsigned long PIDAT_T_check_AI_val = PIDAT_temp_millis; unsigned char PIDAT_cycle_cnt = 0; long PIDAT_t_high; long PIDAT_t_low; long PIDAT_bias= HEATER_CURRENT/2; long PIDAT_d = HEATER_CURRENT/2; float PIDAT_Ku, PIDAT_Tu; float PIDAT_Kp, PIDAT_Ki, PIDAT_Kd; #define PIDAT_TIME_FACTOR ((HEATER_CHECK_INTERVAL*256.0) / 1000.0) showString(PSTR("PID Autotune start\r\n")); target_temp = PIDAT_test_temp; #ifdef BED_USES_THERMISTOR WRITE(HEATER_1_PIN,LOW); #endif for(;;) { if((millis() - PIDAT_T_check_AI_val) > 100 ) { PIDAT_T_check_AI_val = millis(); PIDAT_cycle_cnt++; #ifdef HEATER_USES_THERMISTOR current_raw = analogRead(TEMP_0_PIN); current_raw = 1023 - current_raw; PIDAT_input_help += analog2temp(current_raw); PIDAT_count_input++; #elif defined HEATER_USES_AD595 current_raw = analogRead(TEMP_0_PIN); PIDAT_input_help += analog2temp(current_raw); PIDAT_count_input++; #elif defined HEATER_USES_MAX6675 current_raw = read_max6675(); PIDAT_input_help += analog2temp(current_raw); PIDAT_count_input++; #endif } if(PIDAT_cycle_cnt >= 10 ) { PIDAT_cycle_cnt = 0; PIDAT_input = (float)PIDAT_input_help / (float)PIDAT_count_input; PIDAT_input_help = 0; PIDAT_count_input = 0; PIDAT_max=max(PIDAT_max,PIDAT_input); PIDAT_min=min(PIDAT_min,PIDAT_input); if(PIDAT_heating == true && PIDAT_input > PIDAT_test_temp) { if(millis() - PIDAT_t2 > 5000) { PIDAT_heating = false; PIDAT_PWM_val = (PIDAT_bias - PIDAT_d); PIDAT_t1 = millis(); PIDAT_t_high = PIDAT_t1 - PIDAT_t2; PIDAT_max = PIDAT_test_temp; } } if(PIDAT_heating == false && PIDAT_input < PIDAT_test_temp) { if(millis() - PIDAT_t1 > 5000) { PIDAT_heating = true; PIDAT_t2 = millis(); PIDAT_t_low = PIDAT_t2 - PIDAT_t1; if(PIDAT_cycles > 0) { PIDAT_bias += (PIDAT_d*(PIDAT_t_high - PIDAT_t_low))/(PIDAT_t_low + PIDAT_t_high); PIDAT_bias = constrain(PIDAT_bias, 20 ,HEATER_CURRENT - 20); if(PIDAT_bias > (HEATER_CURRENT/2)) PIDAT_d = (HEATER_CURRENT - 1) - PIDAT_bias; else PIDAT_d = PIDAT_bias; showString(PSTR(" bias: ")); Serial.print(PIDAT_bias); showString(PSTR(" d: ")); Serial.print(PIDAT_d); showString(PSTR(" min: ")); Serial.print(PIDAT_min); showString(PSTR(" max: ")); Serial.println(PIDAT_max); if(PIDAT_cycles > 2) { PIDAT_Ku = (4.0*PIDAT_d)/(3.14159*(PIDAT_max-PIDAT_min)); PIDAT_Tu = ((float)(PIDAT_t_low + PIDAT_t_high)/1000.0); showString(PSTR(" Ku: ")); Serial.print(PIDAT_Ku); showString(PSTR(" Tu: ")); Serial.println(PIDAT_Tu); PIDAT_Kp = 0.60*PIDAT_Ku; PIDAT_Ki = 2*PIDAT_Kp/PIDAT_Tu; PIDAT_Kd = PIDAT_Kp*PIDAT_Tu/8; showString(PSTR(" Clasic PID \r\n")); //showString(PSTR(" Kp: ")); Serial.println(PIDAT_Kp); //showString(PSTR(" Ki: ")); Serial.println(PIDAT_Ki); //showString(PSTR(" Kd: ")); Serial.println(PIDAT_Kd); showString(PSTR(" CFG Kp: ")); Serial.println((unsigned int)(PIDAT_Kp*256)); showString(PSTR(" CFG Ki: ")); Serial.println((unsigned int)(PIDAT_Ki*PIDAT_TIME_FACTOR)); showString(PSTR(" CFG Kd: ")); Serial.println((unsigned int)(PIDAT_Kd*PIDAT_TIME_FACTOR)); PIDAT_Kp = 0.30*PIDAT_Ku; PIDAT_Ki = PIDAT_Kp/PIDAT_Tu; PIDAT_Kd = PIDAT_Kp*PIDAT_Tu/3; showString(PSTR(" Some overshoot \r\n")); showString(PSTR(" CFG Kp: ")); Serial.println((unsigned int)(PIDAT_Kp*256)); showString(PSTR(" CFG Ki: ")); Serial.println((unsigned int)(PIDAT_Ki*PIDAT_TIME_FACTOR)); showString(PSTR(" CFG Kd: ")); Serial.println((unsigned int)(PIDAT_Kd*PIDAT_TIME_FACTOR)); /* PIDAT_Kp = 0.20*PIDAT_Ku; PIDAT_Ki = 2*PIDAT_Kp/PIDAT_Tu; PIDAT_Kd = PIDAT_Kp*PIDAT_Tu/3; showString(PSTR(" No overshoot \r\n")); showString(PSTR(" CFG Kp: ")); Serial.println((unsigned int)(PIDAT_Kp*256)); showString(PSTR(" CFG Ki: ")); Serial.println((unsigned int)(PIDAT_Ki*PIDAT_TIME_FACTOR)); showString(PSTR(" CFG Kd: ")); Serial.println((unsigned int)(PIDAT_Kd*PIDAT_TIME_FACTOR)); */ } } PIDAT_PWM_val = (PIDAT_bias + PIDAT_d); PIDAT_cycles++; PIDAT_min = PIDAT_test_temp; } } #ifdef PID_SOFT_PWM g_heater_pwm_val = PIDAT_PWM_val; #else analogWrite_check(HEATER_0_PIN, PIDAT_PWM_val); #if LED_PIN>-1 analogWrite_check(LED_PIN, PIDAT_PWM_val); #endif #endif } if((PIDAT_input > (PIDAT_test_temp + 55)) || (PIDAT_input > 255)) { showString(PSTR("PID Autotune failed! Temperature to high\r\n")); target_temp = 0; return; } if(millis() - PIDAT_temp_millis > 2000) { PIDAT_temp_millis = millis(); showString(PSTR("ok T:")); Serial.print(PIDAT_input); showString(PSTR(" @:")); Serial.println((unsigned char)PIDAT_PWM_val*1); } if(((millis() - PIDAT_t1) + (millis() - PIDAT_t2)) > (10L*60L*1000L*2L)) { showString(PSTR("PID Autotune failed! timeout\r\n")); return; } if(PIDAT_cycles > 5) { showString(PSTR("PID Autotune finished ! Place the Kp, Ki and Kd constants in the configuration.h\r\n")); return; } } } #endif //---------------- END AUTOTUNE PID ------------------------------ void updatePID() { #ifdef PIDTEMP temp_iState_min = (256L * -PID_INTEGRAL_DRIVE_MAX) / PID_Ki; temp_iState_max = (256L * PID_INTEGRAL_DRIVE_MAX) / PID_Ki; #endif } void manage_heater() { //Temperatur Monitor for repetier if((millis() - previous_millis_monitor) > 250 ) { previous_millis_monitor = millis(); if(manage_monitor <= 1) { showString(PSTR("MTEMP:")); Serial.print(millis()); if(manage_monitor<1) { showString(PSTR(" ")); Serial.print(analog2temp(current_raw)); showString(PSTR(" ")); Serial.print(target_temp); showString(PSTR(" ")); #ifdef PIDTEMP Serial.println(heater_duty); #else #if (HEATER_0_PIN > -1) if(READ(HEATER_0_PIN)) Serial.println(255); else Serial.println(0); #else Serial.println(0); #endif #endif } #if THERMISTORBED!=0 else { showString(PSTR(" ")); Serial.print(analog2tempBed(current_bed_raw)); showString(PSTR(" ")); Serial.print(analog2tempBed(target_bed_raw)); showString(PSTR(" ")); #if (HEATER_1_PIN > -1) if(READ(HEATER_1_PIN)) Serial.println(255); else Serial.println(0); #else Serial.println(0); #endif } #endif } } // ENDE Temperatur Monitor for repetier if((millis() - previous_millis_heater) < HEATER_CHECK_INTERVAL ) return; previous_millis_heater = millis(); #ifdef HEATER_USES_THERMISTOR current_raw = analogRead(TEMP_0_PIN); #ifdef DEBUG_HEAT_MGMT log_int("_HEAT_MGMT - analogRead(TEMP_0_PIN)", current_raw); log_int("_HEAT_MGMT - NUMTEMPS", NUMTEMPS); #endif // When using thermistor, when the heater is colder than targer temp, we get a higher analog reading than target, // this switches it up so that the reading appears lower than target for the control logic. current_raw = 1023 - current_raw; #elif defined HEATER_USES_AD595 current_raw = analogRead(TEMP_0_PIN); #elif defined HEATER_USES_MAX6675 current_raw = read_max6675(); #endif //MIN / MAX save to display the jitter of Heaterbarrel if(current_raw > current_raw_maxval) current_raw_maxval = current_raw; if(current_raw < current_raw_minval) current_raw_minval = current_raw; #ifdef SMOOTHING if (!nma) nma = SMOOTHFACTOR * current_raw; nma = (nma + current_raw) - (nma / SMOOTHFACTOR); current_raw = nma / SMOOTHFACTOR; #endif #ifdef WATCHPERIOD if(watchmillis && millis() - watchmillis > WATCHPERIOD) { if(watch_raw + 1 >= current_raw) { target_temp = target_raw = 0; WRITE(HEATER_0_PIN,LOW); #ifdef PID_SOFT_PWM g_heater_pwm_val = 0; #else analogWrite(HEATER_0_PIN, 0); #if LED_PIN>-1 WRITE(LED_PIN,LOW); #endif #endif } else { watchmillis = 0; } } #endif //If tmp is lower then MINTEMP stop the Heater //or it os better to deaktivate the uutput PIN or PWM ? #ifdef MINTEMP if(current_raw <= minttemp) target_temp = target_raw = 0; #endif #ifdef MAXTEMP if(current_raw >= maxttemp) { target_temp = target_raw = 0; #if (ALARM_PIN > -1) WRITE(ALARM_PIN,HIGH); #endif } #endif #if (TEMP_0_PIN > -1) || defined (HEATER_USES_MAX6675) || defined (HEATER_USES_AD595) #ifdef PIDTEMP int current_temp = analog2temp(current_raw); error = target_temp - current_temp; int delta_temp = current_temp - prev_temp; prev_temp = current_temp; pTerm = ((long)PID_Kp * error) / 256; const int H0 = min(HEATER_DUTY_FOR_SETPOINT(target_temp),HEATER_CURRENT); heater_duty = H0 + pTerm; if(error < 30) { temp_iState += error; temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max); iTerm = ((long)PID_Ki * temp_iState) / 256; heater_duty += iTerm; } int prev_error = abs(target_temp - prev_temp); int log3 = 1; // discrete logarithm base 3, plus 1 if(prev_error > 81){ prev_error /= 81; log3 += 4; } if(prev_error > 9){ prev_error /= 9; log3 += 2; } if(prev_error > 3){ prev_error /= 3; log3 ++; } dTerm = ((long)PID_Kd * delta_temp) / (256*log3); heater_duty += dTerm; heater_duty = constrain(heater_duty, 0, HEATER_CURRENT); #ifdef PID_SOFT_PWM if(target_raw != 0) g_heater_pwm_val = (unsigned char)heater_duty; else g_heater_pwm_val = 0; #else if(target_raw != 0) analogWrite(HEATER_0_PIN, heater_duty); else analogWrite(HEATER_0_PIN, 0); #if LED_PIN>-1 if(target_raw != 0) analogWrite(LED_PIN, constrain(LED_PWM_FOR_BRIGHTNESS(heater_duty),0,255)); else analogWrite(LED_PIN, 0); #endif #endif #else if(current_raw >= target_raw) { WRITE(HEATER_0_PIN,LOW); #if LED_PIN>-1 WRITE(LED_PIN,LOW); #endif } else { if(target_raw != 0) { WRITE(HEATER_0_PIN,HIGH); #if LED_PIN > -1 WRITE(LED_PIN,HIGH); #endif } } #endif #endif if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL) return; previous_millis_bed_heater = millis(); #ifndef TEMP_1_PIN return; #endif #if TEMP_1_PIN == -1 return; #else #ifdef BED_USES_THERMISTOR current_bed_raw = analogRead(TEMP_1_PIN); #ifdef DEBUG_HEAT_MGMT log_int("_HEAT_MGMT - analogRead(TEMP_1_PIN)", current_bed_raw); log_int("_HEAT_MGMT - BNUMTEMPS", BNUMTEMPS); #endif // If using thermistor, when the heater is colder than targer temp, we get a higher analog reading than target, // this switches it up so that the reading appears lower than target for the control logic. current_bed_raw = 1023 - current_bed_raw; #elif defined BED_USES_AD595 current_bed_raw = analogRead(TEMP_1_PIN); #endif #ifdef MINTEMP if(current_bed_raw >= target_bed_raw || current_bed_raw < minttemp) #else if(current_bed_raw >= target_bed_raw) #endif { WRITE(HEATER_1_PIN,LOW); } else { WRITE(HEATER_1_PIN,HIGH); } #endif #ifdef CONTROLLERFAN_PIN controllerFan(); //Check if fan should be turned on to cool stepper drivers down #endif #ifdef EXTRUDERFAN_PIN extruderFan(); //Check if fan should be turned on to cool extruder down #endif } #if defined (HEATER_USES_THERMISTOR) || defined (BED_USES_THERMISTOR) int temp2analog_thermistor(int celsius, const short table[][2], int numtemps) { int raw = 0; byte i; for (i=1; i raw) { celsius = table[i-1][1] + (raw - table[i-1][0]) * (table[i][1] - table[i-1][1]) / (table[i][0] - table[i-1][0]); break; } } // Overflow: Set to last value in the table if (i == numtemps) celsius = table[i-1][1]; return celsius; } #endif #if defined (HEATER_USES_AD595) || defined (BED_USES_AD595) int analog2temp_ad595(int raw) { return (raw * 500.0) / 1024.0; } #endif #if defined (HEATER_USES_MAX6675) || defined (BED_USES_MAX6675) int analog2temp_max6675(int raw) { return raw / 4; } #endif #ifdef CONTROLLERFAN_PIN unsigned long lastMotor = 0; //Save the time for when a motor was turned on last unsigned long lastMotorCheck = 0; void controllerFan() { if ((millis() - lastMotorCheck) >= 2500) //Not a time critical function, so we only check every 2500ms { lastMotorCheck = millis(); if(!READ(X_ENABLE_PIN) || !READ(Y_ENABLE_PIN) || !READ(Z_ENABLE_PIN) || !READ(E_ENABLE_PIN)) //If any of the drivers are enabled... { lastMotor = millis(); //... set time to NOW so the fan will turn on } if ((millis() - lastMotor) >= (CONTROLLERFAN_SEC*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC... { WRITE(CONTROLLERFAN_PIN, LOW); //... turn the fan off } else { WRITE(CONTROLLERFAN_PIN, HIGH); //... turn the fan on } } } #endif #ifdef EXTRUDERFAN_PIN unsigned long lastExtruderCheck = 0; void extruderFan() { if ((millis() - lastExtruderCheck) >= 2500) //Not a time critical function, so we only check every 2500ms { lastExtruderCheck = millis(); if (analog2temp(current_raw) < EXTRUDERFAN_DEC) { WRITE(EXTRUDERFAN_PIN, LOW); //... turn the fan off } else { WRITE(EXTRUDERFAN_PIN, HIGH); //... turn the fan on } } } #endif ================================================ FILE: Sprinter/heater.h ================================================ /* Reprap heater funtions based on Sprinter This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ /* This softwarepart for Heatercontrol is based on Sprinter big thanks to kliment (https://github.com/kliment/Sprinter) */ #include "Configuration.h" #include "thermistortables.h" #if defined HEATER_USES_THERMISTOR #define temp2analogh( c ) temp2analog_thermistor(c,temptable,NUMTEMPS) #define analog2temp( c ) analog2temp_thermistor(c,temptable,NUMTEMPS) #elif defined HEATER_USES_AD595 #define temp2analogh( c ) temp2analog_ad595(c) #define analog2temp( c ) analog2temp_ad595(c) #elif defined HEATER_USES_MAX6675 #define temp2analogh( c ) temp2analog_max6675(c) #define analog2temp( c ) analog2temp_max6675(c) #endif #if defined BED_USES_THERMISTOR #define temp2analogBed( c ) temp2analog_thermistor((c),bedtemptable,BNUMTEMPS) #define analog2tempBed( c ) analog2temp_thermistor((c),bedtemptable,BNUMTEMPS) #elif defined BED_USES_AD595 #define temp2analogBed( c ) temp2analog_ad595(c) #define analog2tempBed( c ) analog2temp_ad595(c) #elif defined BED_USES_MAX6675 #define temp2analogBed( c ) temp2analog_max6675(c) #define analog2tempBed( c ) analog2temp_max6675(c) #endif #if defined (HEATER_USES_THERMISTOR) || defined (BED_USES_THERMISTOR) int temp2analog_thermistor(int celsius, const short table[][2], int numtemps); int analog2temp_thermistor(int raw,const short table[][2], int numtemps); #endif #if defined (HEATER_USES_AD595) || defined (BED_USES_AD595) int temp2analog_ad595(int celsius); int analog2temp_ad595(int raw); #endif #if defined (HEATER_USES_MAX6675) || defined (BED_USES_MAX6675) int temp2analog_max6675(int celsius); int analog2temp_max6675(int raw); #endif extern int target_raw; extern int target_temp; extern int current_raw; extern int current_raw_maxval; extern int current_raw_minval; extern int tt_maxval; extern int tt_minval; extern int target_bed_raw; extern int current_bed_raw; extern unsigned long previous_millis_heater, previous_millis_bed_heater; extern unsigned char manage_monitor; #ifdef PIDTEMP extern volatile unsigned char g_heater_pwm_val; extern unsigned char PWM_off_time; extern unsigned char PWM_out_on; extern int temp_iState; extern int temp_dState; extern int prev_temp; extern int pTerm; extern int iTerm; extern int dTerm; extern int error; extern int heater_duty; extern unsigned int PID_Kp, PID_Ki, PID_Kd; #endif #if defined(FAN_SOFT_PWM) && (FAN_PIN > -1) extern volatile unsigned char g_fan_pwm_val; #endif #ifdef AUTOTEMP extern float autotemp_max; extern float autotemp_min; extern float autotemp_factor; extern int autotemp_setpoint; extern bool autotemp_enabled; #endif #ifdef SMOOTHING extern uint32_t nma; #endif #ifdef WATCHPERIOD extern int watch_raw; extern unsigned long watchmillis; #endif #if defined(PID_SOFT_PWM) || (defined(FAN_SOFT_PWM) && (FAN_PIN > -1)) void init_Timer2_softpwm(void); #endif #ifdef PID_AUTOTUNE void PID_autotune(int PIDAT_test_temp); #endif #ifdef PIDTEMP void updatePID(); #endif void manage_heater(); ================================================ FILE: Sprinter/pins.h ================================================ #ifndef PINS_H #define PINS_H #define ALARM_PIN -1 /**************************************************************************************** * Arduino pin assignment * * ATMega168 * +-\/-+ * PC6 1| |28 PC5 (AI 5 / D19) * (D 0) PD0 2| |27 PC4 (AI 4 / D18) * (D 1) PD1 3| |26 PC3 (AI 3 / D17) * (D 2) PD2 4| |25 PC2 (AI 2 / D16) * PWM+ (D 3) PD3 5| |24 PC1 (AI 1 / D15) * (D 4) PD4 6| |23 PC0 (AI 0 / D14) * VCC 7| |22 GND * GND 8| |21 AREF * PB6 9| |20 AVCC * PB7 10| |19 PB5 (D 13) * PWM+ (D 5) PD5 11| |18 PB4 (D 12) * PWM+ (D 6) PD6 12| |17 PB3 (D 11) PWM * (D 7) PD7 13| |16 PB2 (D 10) PWM * (D 8) PB0 14| |15 PB1 (D 9) PWM * +----+ ****************************************************************************************/ #if MOTHERBOARD == 0 #define KNOWN_BOARD 1 #ifndef __AVR_ATmega168__ #error Oops! Make sure you have 'Arduino Diecimila' selected from the boards menu. #endif #define X_STEP_PIN 2 #define X_DIR_PIN 3 #define X_ENABLE_PIN -1 #define X_MIN_PIN 4 #define X_MAX_PIN 9 #define Y_STEP_PIN 10 #define Y_DIR_PIN 7 #define Y_ENABLE_PIN -1 #define Y_MIN_PIN 8 #define Y_MAX_PIN 13 #define Z_STEP_PIN 19 #define Z_DIR_PIN 18 #define Z_ENABLE_PIN 5 #define Z_MIN_PIN 17 #define Z_MAX_PIN 16 #define E_STEP_PIN 11 #define E_DIR_PIN 12 #define E_ENABLE_PIN -1 #define SDPOWER -1 #define SDSS -1 #define LED_PIN -1 #define FAN_PIN -1 #define PS_ON_PIN 15 #define KILL_PIN -1 #define ALARM_PIN -1 #define HEATER_0_PIN 6 #define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #endif /**************************************************************************************** * Sanguino/RepRap Motherboard with direct-drive extruders * * ATMega644P * * +---\/---+ * (D 0) PB0 1| |40 PA0 (AI 0 / D31) * (D 1) PB1 2| |39 PA1 (AI 1 / D30) * INT2 (D 2) PB2 3| |38 PA2 (AI 2 / D29) * PWM (D 3) PB3 4| |37 PA3 (AI 3 / D28) * PWM (D 4) PB4 5| |36 PA4 (AI 4 / D27) * MOSI (D 5) PB5 6| |35 PA5 (AI 5 / D26) * MISO (D 6) PB6 7| |34 PA6 (AI 6 / D25) * SCK (D 7) PB7 8| |33 PA7 (AI 7 / D24) * RST 9| |32 AREF * VCC 10| |31 GND * GND 11| |30 AVCC * XTAL2 12| |29 PC7 (D 23) * XTAL1 13| |28 PC6 (D 22) * RX0 (D 8) PD0 14| |27 PC5 (D 21) TDI * TX0 (D 9) PD1 15| |26 PC4 (D 20) TDO * INT0 RX1 (D 10) PD2 16| |25 PC3 (D 19) TMS * INT1 TX1 (D 11) PD3 17| |24 PC2 (D 18) TCK * PWM (D 12) PD4 18| |23 PC1 (D 17) SDA * PWM (D 13) PD5 19| |22 PC0 (D 16) SCL * PWM (D 14) PD6 20| |21 PD7 (D 15) PWM * +--------+ * **************************************************************************************** * * ATMega644P (SMD) * * +--------+ * MOSI (D 5) PB5 1| O |44 PB4 (D 4) PWM * MISO (D 6) PB6 2| |43 PB3 (D 3) PWM * SCK (D 7) PB7 3| |42 PB2 (D 2) INT2 * RST 4| |41 PB1 (D 1) * Vcc 5| |40 PB0 (D 0) * GND 6| |39 GND * XTAL2 7| |38 Vcc * XTAL1 8| |37 PA0 (AI 0 / D31) * RX0 (D 8) PD0 9| |36 PA1 (AI 1 / D30) * TX0 (D 9) PD1 10| |35 PA2 (AI 2 / D29) * INT0 RX1 (D 10) PD2 11| |34 PA3 (AI 3 / D28) * + + * INT1 TX1 (D 11) PD3 12| |33 PA4 (AI 4 / D27) * PWM (D 12) PD4 13| |32 PA5 (AI 5 / D26) * PWM (D 13) PD5 14| |31 PA6 (AI 6 / D25) * PWM (D 14) PD6 15| |30 PA7 (AI 7 / D24) * PWM (D 15) PD7 16| |29 AREF * Vcc 17| |28 GND * GND 18| |27 AVCC * (D 16) PC0 19| |26 PC7 (D 23) * (D 17) PC1 20| |25 PC6 (D 22) * (D 18) PC2 21| |24 PC5 (D 21) TDI * (D 19) PC3 22| |23 PC4 (D 20) TDO * +--------+ * ****************************************************************************************/ #if MOTHERBOARD == 1 #define KNOWN_BOARD 1 #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #endif #define X_STEP_PIN 15 #define X_DIR_PIN 18 #define X_ENABLE_PIN 19 #define X_MIN_PIN 20 #define X_MAX_PIN 21 #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 #define Y_ENABLE_PIN 19 #define Y_MIN_PIN 25 #define Y_MAX_PIN 26 #define Z_STEP_PIN 29 #define Z_DIR_PIN 30 #define Z_ENABLE_PIN 31 #define Z_MIN_PIN 2 #define Z_MAX_PIN 1 #define E_STEP_PIN 12 #define E_DIR_PIN 16 #define E_ENABLE_PIN 3 #define SDPOWER -1 #define SDSS -1 #define LED_PIN 0 #define FAN_PIN -1 #define PS_ON_PIN -1 #define KILL_PIN -1 #define ALARM_PIN -1 #define HEATER_0_PIN 14 #define TEMP_0_PIN 4 //D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! /* 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 /**************************************************************************************** * RepRap Motherboard ****---NOOOOOO RS485/EXTRUDER CONTROLLER!!!!!!!!!!!!!!!!!---******* * ****************************************************************************************/ #if MOTHERBOARD == 2 #define KNOWN_BOARD 1 #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) && !defined(__ATmega644P__) && !defined(__ATmega1284P__) #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #endif #define X_STEP_PIN 15 #define X_DIR_PIN 18 #define X_ENABLE_PIN 19 #define X_MIN_PIN 20 #define X_MAX_PIN 21 #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 #define Y_ENABLE_PIN 24 #define Y_MIN_PIN 25 #define Y_MAX_PIN 26 #define Z_STEP_PINN 27 #define Z_DIR_PINN 28 #define Z_ENABLE_PIN 29 #define Z_MIN_PIN 30 #define Z_MAX_PIN 31 #define E_STEP_PIN 17 #define E_DIR_PIN 16 #define E_ENABLE_PIN -1 #define SDPOWER -1 #define SDSS 4 #define LED_PIN 0 #define SD_CARD_WRITE 2 #define SD_CARD_DETECT 3 #define SD_CARD_SELECT 4 //our RS485 pins #define TX_ENABLE_PIN 12 #define RX_ENABLE_PIN 13 //pin for controlling the PSU. #define PS_ON_PIN 14 #define FAN_PIN -1 #define KILL_PIN -1 #define ALARM_PIN -1 #define HEATER_0_PIN -1 #define TEMP_0_PIN -1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #endif /**************************************************************************************** * Gen3 PLUS for RepRap Motherboard V1.2 * ****************************************************************************************/ #if MOTHERBOARD == 21 #define KNOWN_BOARD 1 #ifndef __AVR_ATmega644P__ #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #endif //x axis pins #define X_STEP_PIN 15 #define X_DIR_PIN 18 #define X_ENABLE_PIN 19 #define X_MIN_PIN 20 #define X_MAX_PIN -1 //y axis pins #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 #define Y_ENABLE_PIN 24 #define Y_MIN_PIN 25 #define Y_MAX_PIN -1 //z axis pins #define Z_STEP_PIN 27 #define Z_DIR_PIN 28 #define Z_ENABLE_PIN 29 #define Z_MIN_PIN 30 #define Z_MAX_PIN -1 #define E_DIR_PIN 21 #define E_STEP_PIN 17 #define E_ENABLE_PIN 13 //heaters //pin for hot end heater #define HEATER_0_PIN 12 //Pin for heated bed heater #define HEATER_1_PIN 16 //pin for debugging. #define DEBUG_PIN -1 //SD card pin #define SDSS 4 #define SDPOWER -1 #define FAN_PIN -1 #define TEMP_0_PIN 0 #define TEMP_1_PIN 5 #define LED_PIN -1 //pin for controlling the PSU. #define PS_ON_PIN 14 #endif /**************************************************************************************** * Gen3 Monolithic Electronics * ****************************************************************************************/ #if MOTHERBOARD == 22 #define KNOWN_BOARD 1 #ifndef __AVR_ATmega644P__ #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #endif #define DEBUG_PIN 0 // x axis #define X_STEP_PIN 15 #define X_DIR_PIN 18 #define X_MIN_PIN 20 #define X_ENABLE_PIN 24 //actually uses Y_enable_pin #define X_MAX_PIN -1 // y axes #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 #define Y_MIN_PIN 25 #define Y_ENABLE_PIN 24 //shared with X_enable_pin #define Y_MAX_PIN -1 // z axes #define Z_STEP_PIN 27 #define Z_DIR_PIN 28 #define Z_MIN_PIN 30 #define Z_ENABLE_PIN 29 #define Z_MAX_PIN -1 //extruder pins #define E_STEP_PIN 12 #define E_DIR_PIN 17 #define E_ENABLE_PIN 3 #define HEATER_0_PIN 16 #define TEMP_0_PIN 0 #define FAN_PIN -1 //bed pins #define HEATER_1_PIN -1 #define TEMP_1_PIN -1 #define SDSS -1 #define SDPOWER -1 #define LED_PIN -1 //pin for controlling the PSU. #define PS_ON_PIN 14 #endif /**************************************************************************************** * Gen3 PLUS for TechZone Gen3 Remix Motherboard * ****************************************************************************************/ #if MOTHERBOARD == 23 #define KNOWN_BOARD 1 #ifndef __AVR_ATmega644P__ #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #endif //x axis pins #define X_STEP_PIN 15 #define X_DIR_PIN 18 #define X_ENABLE_PIN 24 //same as E/Y_enable_pin #define X_MIN_PIN 20 #define X_MAX_PIN -1 //y axis pins #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 #define Y_ENABLE_PIN 24 //same as E/X_enable_pin #define Y_MIN_PIN 25 #define Y_MAX_PIN -1 //z axis pins #define Z_STEP_PIN 27 #define Z_DIR_PIN 28 #define Z_ENABLE_PIN 29 #define Z_MIN_PIN 30 #define Z_MAX_PIN -1 #define E_DIR_PIN 21 #define E_STEP_PIN 19 #define E_ENABLE_PIN 24 //same as X/Y_enable_pin //heaters //pin for hot end heater #define HEATER_0_PIN 16 //Pin for heated bed heater #define HEATER_1_PIN 17 //pin for debugging. #define DEBUG_PIN -1 //SD card pin #define SDSS 4 #define SDPOWER -1 #define FAN_PIN -1 #define TEMP_0_PIN 0 #define TEMP_1_PIN 5 #define LED_PIN -1 //pin for controlling the PSU. #define PS_ON_PIN 14 #endif /**************************************************************************************** * Arduino Mega pin assignment * ****************************************************************************************/ #if MOTHERBOARD == 33 #define MOTHERBOARD 3 #define RAMPS_V_1_3 #endif #if MOTHERBOARD == 3 #define KNOWN_BOARD 1 //////////////////FIX THIS////////////// #ifndef __AVR_ATmega1280__ #ifndef __AVR_ATmega2560__ #error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. #endif #endif // 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_0 #ifdef RAMPS_V_1_3 #define X_STEP_PIN 54 #define X_DIR_PIN 55 #define X_ENABLE_PIN 38 #define X_MIN_PIN 3 #define X_MAX_PIN -1 //2 //Max endstops default to disabled "-1", set to commented value to enable. #define Y_STEP_PIN 60 #define Y_DIR_PIN 61 #define Y_ENABLE_PIN 56 #define Y_MIN_PIN 14 #define Y_MAX_PIN -1 //15 #define Z_STEP_PIN 46 #define Z_DIR_PIN 48 #define Z_ENABLE_PIN 62 #define Z_MIN_PIN 18 #define Z_MAX_PIN -1 //19 #define E_STEP_PIN 26 #define E_DIR_PIN 28 #define E_ENABLE_PIN 24 #define E_1_STEP_PIN 36 #define E_1_DIR_PIN 34 #define E_1_ENABLE_PIN 30 #define SDPOWER -1 #define SDSS 53 #define LED_PIN 13 #define FAN_PIN 9 #define PS_ON_PIN 12 #define KILL_PIN -1 #define ALARM_PIN -1 #define HEATER_0_PIN 10 #define HEATER_1_PIN 8 #define TEMP_0_PIN 13 // ANALOG NUMBERING #define TEMP_1_PIN 14 // ANALOG NUMBERING #define TEMP_2_PIN 15 // ANALOG NUMBERING #else // RAMPS_V_1_1 or RAMPS_V_1_2 as default #define X_STEP_PIN 26 #define X_DIR_PIN 28 #define X_ENABLE_PIN 24 #define X_MIN_PIN 3 #define X_MAX_PIN -1 //2 #define Y_STEP_PIN 38 #define Y_DIR_PIN 40 #define Y_ENABLE_PIN 36 #define Y_MIN_PIN 16 #define Y_MAX_PIN -1 //17 #define Z_STEP_PIN 44 #define Z_DIR_PIN 46 #define Z_ENABLE_PIN 42 #define Z_MIN_PIN 18 #define Z_MAX_PIN -1 //19 #define E_STEP_PIN 32 #define E_DIR_PIN 34 #define E_ENABLE_PIN 30 #define SDPOWER 48 #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN -1 #define KILL_PIN -1 #define ALARM_PIN -1 #ifdef RAMPS_V_1_0 // RAMPS_V_1_0 #define HEATER_0_PIN 12 // RAMPS 1.0 #define HEATER_1_PIN -1 // RAMPS 1.0 #define FAN_PIN 11 // RAMPS 1.0 #else // RAMPS_V_1_1 or RAMPS_V_1_2 #define HEATER_0_PIN 10 // RAMPS 1.1 #define HEATER_1_PIN 8 // RAMPS 1.1 #define FAN_PIN 9 // RAMPS 1.1 #endif #define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #define TEMP_1_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #endif // SPI for Max6675 Thermocouple #ifndef SDSUPPORT // these pins are defined in the SD library if building with SD support #define SCK_PIN 52 #define MISO_PIN 50 #define MOSI_PIN 51 #define MAX6675_SS 53 #else #define MAX6675_SS 49 #endif #endif /**************************************************************************************** * Duemilanove w/ ATMega328P pin assignment * ****************************************************************************************/ #if MOTHERBOARD == 4 #define KNOWN_BOARD 1 #ifndef __AVR_ATmega328P__ #error Oops! Make sure you have 'Arduino Duemilanove w/ ATMega328' selected from the 'Tools -> Boards' menu. #endif #define X_STEP_PIN 19 #define X_DIR_PIN 18 #define X_ENABLE_PIN -1 #define X_MIN_PIN 17 #define X_MAX_PIN -1 #define Y_STEP_PIN 10 #define Y_DIR_PIN 7 #define Y_ENABLE_PIN -1 #define Y_MIN_PIN 8 #define Y_MAX_PIN -1 #define Z_STEP_PIN 13 #define Z_DIR_PIN 3 #define Z_ENABLE_PIN 2 #define Z_MIN_PIN 4 #define Z_MAX_PIN -1 #define E_STEP_PIN 11 #define E_DIR_PIN 12 #define E_ENABLE_PIN -1 #define SDPOWER -1 #define SDSS -1 #define LED_PIN -1 #define FAN_PIN 5 #define PS_ON_PIN -1 #define KILL_PIN -1 #define ALARM_PIN -1 #define HEATER_0_PIN 6 #define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! #endif /**************************************************************************************** * Gen6 pin assignment * ****************************************************************************************/ #if MOTHERBOARD == 51 #define MOTHERBOARD 5 #define GEN6_DELUXE #endif #if MOTHERBOARD == 5 #define KNOWN_BOARD 1 #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #endif //x axis pins #define X_STEP_PIN 15 #define X_DIR_PIN 18 #define X_ENABLE_PIN 19 #define X_MIN_PIN 20 #define X_MAX_PIN -1 //y axis pins #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 #define Y_ENABLE_PIN 24 #define Y_MIN_PIN 25 #define Y_MAX_PIN -1 //z axis pins #define Z_STEP_PIN 27 #define Z_DIR_PIN 28 #define Z_ENABLE_PIN 29 #define Z_MIN_PIN 30 #define Z_MAX_PIN -1 //extruder pins #define E_STEP_PIN 4 //Edited @ EJE Electronics 20100715 #define E_DIR_PIN 2 //Edited @ EJE Electronics 20100715 #define E_ENABLE_PIN 3 //Added @ EJE Electronics 20100715 #define TEMP_0_PIN 5 //changed @ rkoeppl 20110410 #define HEATER_0_PIN 14 //changed @ rkoeppl 20110410 #ifdef GEN6_DELUXE #define HEATER_1_PIN 1 #define TEMP_1_PIN 0 #else #define HEATER_1_PIN -1 #define TEMP_1_PIN -1 #endif #define SDPOWER -1 #define SDSS 17 #define LED_PIN -1 //changed @ rkoeppl 20110410 #define FAN_PIN -1 //changed @ rkoeppl 20110410 #define PS_ON_PIN -1 //changed @ rkoeppl 20110410 //our pin for debugging. #define DEBUG_PIN 0 //our RS485 pins #define TX_ENABLE_PIN 12 #define RX_ENABLE_PIN 13 #endif /**************************************************************************************** * Sanguinololu pin assignment * ****************************************************************************************/ #if MOTHERBOARD == 62 #define MOTHERBOARD 6 #define SANGUINOLOLU_V_1_2 #endif #if MOTHERBOARD == 6 #define KNOWN_BOARD 1 #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #endif #define X_STEP_PIN 15 #define X_DIR_PIN 21 #define X_MIN_PIN 18 #define X_MAX_PIN -2 #define Y_STEP_PIN 22 #define Y_DIR_PIN 23 #define Y_MIN_PIN 19 #define Y_MAX_PIN -1 #define Z_STEP_PIN 3 #define Z_DIR_PIN 2 #define Z_MIN_PIN 20 #define Z_MAX_PIN -1 #define E_STEP_PIN 1 #define E_DIR_PIN 0 #define LED_PIN -1 #define FAN_PIN -1 #define PS_ON_PIN -1 #define KILL_PIN -1 #define ALARM_PIN -1 #define HEATER_0_PIN 13 // (extruder) #ifdef SANGUINOLOLU_V_1_2 #define HEATER_1_PIN 12 // (bed) #define X_ENABLE_PIN 14 #define Y_ENABLE_PIN 14 #define Z_ENABLE_PIN 26 #define E_ENABLE_PIN 14 #else #define HEATER_1_PIN 14 // (bed) #define X_ENABLE_PIN -1 #define Y_ENABLE_PIN -1 #define Z_ENABLE_PIN -1 #define E_ENABLE_PIN -1 #endif #define TEMP_0_PIN 7 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) #define TEMP_1_PIN 6 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) #define SDPOWER -1 #define SDSS 31 #endif /**************************************************************************************** * Gen7 pin assignment * **************************************************************************************** * for Gen7 to work properly, you should reset your fuses to lfuse= 0xF7 ; hfuse = 0xD4 ; efuse = FD; * else you will always get a "brown out reset" loop resetting the firmware * you need a programmer to set the fuses **/ #if MOTHERBOARD == 71 //GEN7 with 20 Mhz #define MOTHERBOARD 7 #define QUARZ_20MHZ #endif #if MOTHERBOARD == 7 #define KNOWN_BOARD 1 #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) && !defined(__AVR_ATmega644__) #error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. #endif //x axis pins #define X_STEP_PIN 19 #define X_DIR_PIN 18 #define X_ENABLE_PIN 24 #define X_MIN_PIN 7 #define X_MAX_PIN -1 //X - Maxpin is 6 //y axis pins #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 #define Y_ENABLE_PIN 24 #define Y_MIN_PIN 5 #define Y_MAX_PIN -1 //Y - Maxpin is 2 //z axis pins #define Z_STEP_PIN 26 #define Z_DIR_PIN 25 #define Z_ENABLE_PIN 24 #define Z_MIN_PIN 1 #define Z_MAX_PIN -1 //Z - Maxpin is 0 //extruder pins #define E_STEP_PIN 28 #define E_DIR_PIN 27 #define E_ENABLE_PIN 24 #define TEMP_0_PIN 1 // Extruder #define HEATER_0_PIN 4 // Extruder #define HEATER_1_PIN 3 // Bed #define SDPOWER -1 #define SDSS -1 #define LED_PIN -1 #define TEMP_1_PIN 2 //Bed #define FAN_PIN -1 #define PS_ON_PIN 15 #endif /**************************************************************************************** * Teensylu 0.7 pin assingments (ATMEGA90USB) * Requires the Teensyduino software with Teensy2.0++ selected in arduino IDE! ****************************************************************************************/ #if MOTHERBOARD == 8 #define MOTHERBOARD 8 #define KNOWN_BOARD 1 #define X_STEP_PIN 28 #define X_DIR_PIN 29 #define X_ENABLE_PIN 19 #define X_MIN_PIN 25 #define X_MAX_PIN -1 #define Y_STEP_PIN 30 #define Y_DIR_PIN 31 #define Y_ENABLE_PIN 26 #define Y_MIN_PIN 20 #define Y_MAX_PIN -1 #define Z_STEP_PIN 32 #define Z_DIR_PIN 33 #define Z_ENABLE_PIN 17 #define Z_MIN_PIN 27 #define Z_MAX_PIN -1 #define E_STEP_PIN 34 #define E_DIR_PIN 35 #define E_ENABLE_PIN 13 #define HEATER_0_PIN 15 // Extruder #define HEATER_1_PIN 14 // Bed #define FAN_PIN 16 // Fan #define TEMP_0_PIN 7 // Extruder #define TEMP_1_PIN 6 // Bed #define SDPOWER -1 #define SDSS 20 #define LED_PIN -1 #define PS_ON_PIN -1 #define KILL_PIN -1 #define ALARM_PIN -1 #ifndef SDSUPPORT // these pins are defined in the SD library if building with SD support #define SCK_PIN 21 #define MISO_PIN 22 #define MOSI_PIN 23 #endif #endif /**************************************************************************************** * Printrboard Rev. B pin assingments (ATMEGA90USB1286) * Requires the Teensyduino software with Teensy2.0++ selected in arduino IDE! * See http://reprap.org/wiki/Printrboard for more info ****************************************************************************************/ #if MOTHERBOARD == 9 #define MOTHERBOARD 9 #define KNOWN_BOARD 1 #define X_STEP_PIN 28 #define X_DIR_PIN 29 #define X_ENABLE_PIN 19 #define X_MIN_PIN 47 #define X_MAX_PIN -1 #define Y_STEP_PIN 30 #define Y_DIR_PIN 31 #define Y_ENABLE_PIN 18 #define Y_MIN_PIN 20 #define Y_MAX_PIN -1 #define Z_STEP_PIN 32 #define Z_DIR_PIN 33 #define Z_ENABLE_PIN 17 #define Z_MIN_PIN 36 #define Z_MAX_PIN -1 #define E_STEP_PIN 34 #define E_DIR_PIN 35 #define E_ENABLE_PIN 13 #define HEATER_0_PIN 15 // Extruder #define HEATER_1_PIN 14 // Bed #define FAN_PIN 16 // Fan #define TEMP_0_PIN 1 // Extruder #define TEMP_1_PIN 0 // Bed #define SDPOWER -1 #define SDSS 2 #define LED_PIN -1 #define PS_ON_PIN -1 #define KILL_PIN -1 #ifndef SDSUPPORT // these pins are defined in the SD library if building with SD support #define SCK_PIN 21 #define MISO_PIN 22 #define MOSI_PIN 23 #endif #endif #ifndef KNOWN_BOARD #error Unknown MOTHERBOARD value in configuration.h #endif //List of pins which to ignore when asked to change by gcode, 0 and 1 are RX and TX, do not mess with those! const int sensitive_pins[] = {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, E_STEP_PIN, E_DIR_PIN, E_ENABLE_PIN, LED_PIN, PS_ON_PIN, HEATER_0_PIN, HEATER_1_PIN, FAN_PIN, TEMP_0_PIN, TEMP_1_PIN}; #endif ================================================ FILE: Sprinter/speed_lookuptable.h ================================================ #ifndef SPEED_LOOKUPTABLE_H #define SPEED_LOOKUPTABLE_H #include #if F_CPU == 16000000 const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {\ { 62500, 55556}, { 6944, 3268}, { 3676, 1176}, { 2500, 607}, { 1893, 369}, { 1524, 249}, { 1275, 179}, { 1096, 135}, { 961, 105}, { 856, 85}, { 771, 69}, { 702, 58}, { 644, 49}, { 595, 42}, { 553, 37}, { 516, 32}, { 484, 28}, { 456, 25}, { 431, 23}, { 408, 20}, { 388, 19}, { 369, 16}, { 353, 16}, { 337, 14}, { 323, 13}, { 310, 11}, { 299, 11}, { 288, 11}, { 277, 9}, { 268, 9}, { 259, 8}, { 251, 8}, { 243, 8}, { 235, 7}, { 228, 6}, { 222, 6}, { 216, 6}, { 210, 6}, { 204, 5}, { 199, 5}, { 194, 5}, { 189, 4}, { 185, 4}, { 181, 4}, { 177, 4}, { 173, 4}, { 169, 4}, { 165, 3}, { 162, 3}, { 159, 4}, { 155, 3}, { 152, 3}, { 149, 2}, { 147, 3}, { 144, 3}, { 141, 2}, { 139, 3}, { 136, 2}, { 134, 2}, { 132, 3}, { 129, 2}, { 127, 2}, { 125, 2}, { 123, 2}, { 121, 2}, { 119, 1}, { 118, 2}, { 116, 2}, { 114, 1}, { 113, 2}, { 111, 2}, { 109, 1}, { 108, 2}, { 106, 1}, { 105, 2}, { 103, 1}, { 102, 1}, { 101, 1}, { 100, 2}, { 98, 1}, { 97, 1}, { 96, 1}, { 95, 2}, { 93, 1}, { 92, 1}, { 91, 1}, { 90, 1}, { 89, 1}, { 88, 1}, { 87, 1}, { 86, 1}, { 85, 1}, { 84, 1}, { 83, 0}, { 83, 1}, { 82, 1}, { 81, 1}, { 80, 1}, { 79, 1}, { 78, 0}, { 78, 1}, { 77, 1}, { 76, 1}, { 75, 0}, { 75, 1}, { 74, 1}, { 73, 1}, { 72, 0}, { 72, 1}, { 71, 1}, { 70, 0}, { 70, 1}, { 69, 0}, { 69, 1}, { 68, 1}, { 67, 0}, { 67, 1}, { 66, 0}, { 66, 1}, { 65, 0}, { 65, 1}, { 64, 1}, { 63, 0}, { 63, 1}, { 62, 0}, { 62, 1}, { 61, 0}, { 61, 1}, { 60, 0}, { 60, 0}, { 60, 1}, { 59, 0}, { 59, 1}, { 58, 0}, { 58, 1}, { 57, 0}, { 57, 1}, { 56, 0}, { 56, 0}, { 56, 1}, { 55, 0}, { 55, 1}, { 54, 0}, { 54, 0}, { 54, 1}, { 53, 0}, { 53, 0}, { 53, 1}, { 52, 0}, { 52, 0}, { 52, 1}, { 51, 0}, { 51, 0}, { 51, 1}, { 50, 0}, { 50, 0}, { 50, 1}, { 49, 0}, { 49, 0}, { 49, 1}, { 48, 0}, { 48, 0}, { 48, 1}, { 47, 0}, { 47, 0}, { 47, 0}, { 47, 1}, { 46, 0}, { 46, 0}, { 46, 1}, { 45, 0}, { 45, 0}, { 45, 0}, { 45, 1}, { 44, 0}, { 44, 0}, { 44, 0}, { 44, 1}, { 43, 0}, { 43, 0}, { 43, 0}, { 43, 1}, { 42, 0}, { 42, 0}, { 42, 0}, { 42, 1}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 1}, { 40, 0}, { 40, 0}, { 40, 0}, { 40, 0}, { 40, 1}, { 39, 0}, { 39, 0}, { 39, 0}, { 39, 0}, { 39, 1}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 1}, { 37, 0}, { 37, 0}, { 37, 0}, { 37, 0}, { 37, 0}, { 37, 1}, { 36, 0}, { 36, 0}, { 36, 0}, { 36, 0}, { 36, 1}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 1}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 1}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 1}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0}, { 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0} }; const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {\ { 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894}, { 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657}, { 12500, 596}, { 11904, 541}, { 11363, 494}, { 10869, 453}, { 10416, 416}, { 10000, 385}, { 9615, 356}, { 9259, 331}, { 8928, 308}, { 8620, 287}, { 8333, 269}, { 8064, 252}, { 7812, 237}, { 7575, 223}, { 7352, 210}, { 7142, 198}, { 6944, 188}, { 6756, 178}, { 6578, 168}, { 6410, 160}, { 6250, 153}, { 6097, 145}, { 5952, 139}, { 5813, 132}, { 5681, 126}, { 5555, 121}, { 5434, 115}, { 5319, 111}, { 5208, 106}, { 5102, 102}, { 5000, 99}, { 4901, 94}, { 4807, 91}, { 4716, 87}, { 4629, 84}, { 4545, 81}, { 4464, 79}, { 4385, 75}, { 4310, 73}, { 4237, 71}, { 4166, 68}, { 4098, 66}, { 4032, 64}, { 3968, 62}, { 3906, 60}, { 3846, 59}, { 3787, 56}, { 3731, 55}, { 3676, 53}, { 3623, 52}, { 3571, 50}, { 3521, 49}, { 3472, 48}, { 3424, 46}, { 3378, 45}, { 3333, 44}, { 3289, 43}, { 3246, 41}, { 3205, 41}, { 3164, 39}, { 3125, 39}, { 3086, 38}, { 3048, 36}, { 3012, 36}, { 2976, 35}, { 2941, 35}, { 2906, 33}, { 2873, 33}, { 2840, 32}, { 2808, 31}, { 2777, 30}, { 2747, 30}, { 2717, 29}, { 2688, 29}, { 2659, 28}, { 2631, 27}, { 2604, 27}, { 2577, 26}, { 2551, 26}, { 2525, 25}, { 2500, 25}, { 2475, 25}, { 2450, 23}, { 2427, 24}, { 2403, 23}, { 2380, 22}, { 2358, 22}, { 2336, 22}, { 2314, 21}, { 2293, 21}, { 2272, 20}, { 2252, 20}, { 2232, 20}, { 2212, 20}, { 2192, 19}, { 2173, 18}, { 2155, 19}, { 2136, 18}, { 2118, 18}, { 2100, 17}, { 2083, 17}, { 2066, 17}, { 2049, 17}, { 2032, 16}, { 2016, 16}, { 2000, 16}, { 1984, 16}, { 1968, 15}, { 1953, 16}, { 1937, 14}, { 1923, 15}, { 1908, 15}, { 1893, 14}, { 1879, 14}, { 1865, 14}, { 1851, 13}, { 1838, 14}, { 1824, 13}, { 1811, 13}, { 1798, 13}, { 1785, 12}, { 1773, 13}, { 1760, 12}, { 1748, 12}, { 1736, 12}, { 1724, 12}, { 1712, 12}, { 1700, 11}, { 1689, 12}, { 1677, 11}, { 1666, 11}, { 1655, 11}, { 1644, 11}, { 1633, 10}, { 1623, 11}, { 1612, 10}, { 1602, 10}, { 1592, 10}, { 1582, 10}, { 1572, 10}, { 1562, 10}, { 1552, 9}, { 1543, 10}, { 1533, 9}, { 1524, 9}, { 1515, 9}, { 1506, 9}, { 1497, 9}, { 1488, 9}, { 1479, 9}, { 1470, 9}, { 1461, 8}, { 1453, 8}, { 1445, 9}, { 1436, 8}, { 1428, 8}, { 1420, 8}, { 1412, 8}, { 1404, 8}, { 1396, 8}, { 1388, 7}, { 1381, 8}, { 1373, 7}, { 1366, 8}, { 1358, 7}, { 1351, 7}, { 1344, 8}, { 1336, 7}, { 1329, 7}, { 1322, 7}, { 1315, 7}, { 1308, 6}, { 1302, 7}, { 1295, 7}, { 1288, 6}, { 1282, 7}, { 1275, 6}, { 1269, 7}, { 1262, 6}, { 1256, 6}, { 1250, 7}, { 1243, 6}, { 1237, 6}, { 1231, 6}, { 1225, 6}, { 1219, 6}, { 1213, 6}, { 1207, 6}, { 1201, 5}, { 1196, 6}, { 1190, 6}, { 1184, 5}, { 1179, 6}, { 1173, 5}, { 1168, 6}, { 1162, 5}, { 1157, 5}, { 1152, 6}, { 1146, 5}, { 1141, 5}, { 1136, 5}, { 1131, 5}, { 1126, 5}, { 1121, 5}, { 1116, 5}, { 1111, 5}, { 1106, 5}, { 1101, 5}, { 1096, 5}, { 1091, 5}, { 1086, 4}, { 1082, 5}, { 1077, 5}, { 1072, 4}, { 1068, 5}, { 1063, 4}, { 1059, 5}, { 1054, 4}, { 1050, 4}, { 1046, 5}, { 1041, 4}, { 1037, 4}, { 1033, 5}, { 1028, 4}, { 1024, 4}, { 1020, 4}, { 1016, 4}, { 1012, 4}, { 1008, 4}, { 1004, 4}, { 1000, 4}, { 996, 4}, { 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3} }; #else const uint16_t speed_lookuptable_fast[256][2] PROGMEM = { {62500, 54055}, {8445, 3917}, {4528, 1434}, {3094, 745}, {2349, 456}, {1893, 307}, {1586, 222}, {1364, 167}, {1197, 131}, {1066, 105}, {961, 86}, {875, 72}, {803, 61}, {742, 53}, {689, 45}, {644, 40}, {604, 35}, {569, 32}, {537, 28}, {509, 25}, {484, 23}, {461, 21}, {440, 19}, {421, 17}, {404, 16}, {388, 15}, {373, 14}, {359, 13}, {346, 12}, {334, 11}, {323, 10}, {313, 10}, {303, 9}, {294, 9}, {285, 8}, {277, 7}, {270, 8}, {262, 7}, {255, 6}, {249, 6}, {243, 6}, {237, 6}, {231, 5}, {226, 5}, {221, 5}, {216, 5}, {211, 4}, {207, 5}, {202, 4}, {198, 4}, {194, 4}, {190, 3}, {187, 4}, {183, 3}, {180, 3}, {177, 4}, {173, 3}, {170, 3}, {167, 2}, {165, 3}, {162, 3}, {159, 2}, {157, 3}, {154, 2}, {152, 3}, {149, 2}, {147, 2}, {145, 2}, {143, 2}, {141, 2}, {139, 2}, {137, 2}, {135, 2}, {133, 2}, {131, 2}, {129, 1}, {128, 2}, {126, 2}, {124, 1}, {123, 2}, {121, 1}, {120, 2}, {118, 1}, {117, 1}, {116, 2}, {114, 1}, {113, 1}, {112, 2}, {110, 1}, {109, 1}, {108, 1}, {107, 2}, {105, 1}, {104, 1}, {103, 1}, {102, 1}, {101, 1}, {100, 1}, {99, 1}, {98, 1}, {97, 1}, {96, 1}, {95, 1}, {94, 1}, {93, 1}, {92, 1}, {91, 0}, {91, 1}, {90, 1}, {89, 1}, {88, 1}, {87, 0}, {87, 1}, {86, 1}, {85, 1}, {84, 0}, {84, 1}, {83, 1}, {82, 1}, {81, 0}, {81, 1}, {80, 1}, {79, 0}, {79, 1}, {78, 0}, {78, 1}, {77, 1}, {76, 0}, {76, 1}, {75, 0}, {75, 1}, {74, 1}, {73, 0}, {73, 1}, {72, 0}, {72, 1}, {71, 0}, {71, 1}, {70, 0}, {70, 1}, {69, 0}, {69, 1}, {68, 0}, {68, 1}, {67, 0}, {67, 1}, {66, 0}, {66, 1}, {65, 0}, {65, 0}, {65, 1}, {64, 0}, {64, 1}, {63, 0}, {63, 1}, {62, 0}, {62, 0}, {62, 1}, {61, 0}, {61, 1}, {60, 0}, {60, 0}, {60, 1}, {59, 0}, {59, 0}, {59, 1}, {58, 0}, {58, 0}, {58, 1}, {57, 0}, {57, 0}, {57, 1}, {56, 0}, {56, 0}, {56, 1}, {55, 0}, {55, 0}, {55, 1}, {54, 0}, {54, 0}, {54, 1}, {53, 0}, {53, 0}, {53, 0}, {53, 1}, {52, 0}, {52, 0}, {52, 1}, {51, 0}, {51, 0}, {51, 0}, {51, 1}, {50, 0}, {50, 0}, {50, 0}, {50, 1}, {49, 0}, {49, 0}, {49, 0}, {49, 1}, {48, 0}, {48, 0}, {48, 0}, {48, 1}, {47, 0}, {47, 0}, {47, 0}, {47, 1}, {46, 0}, {46, 0}, {46, 0}, {46, 0}, {46, 1}, {45, 0}, {45, 0}, {45, 0}, {45, 1}, {44, 0}, {44, 0}, {44, 0}, {44, 0}, {44, 1}, {43, 0}, {43, 0}, {43, 0}, {43, 0}, {43, 1}, {42, 0}, {42, 0}, {42, 0}, {42, 0}, {42, 0}, {42, 1}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 1}, {40, 0}, {40, 0}, {40, 0}, {40, 0}, {40, 1}, {39, 0}, {39, 0}, {39, 0}, {39, 0}, {39, 0}, {39, 0}, {39, 1}, {38, 0}, {38, 0}, {38, 0}, {38, 0}, {38, 0}, }; const uint16_t speed_lookuptable_slow[256][2] PROGMEM = { {62500, 10417}, {52083, 7441}, {44642, 5580}, {39062, 4340}, {34722, 3472}, {31250, 2841}, {28409, 2368}, {26041, 2003}, {24038, 1717}, {22321, 1488}, {20833, 1302}, {19531, 1149}, {18382, 1021}, {17361, 914}, {16447, 822}, {15625, 745}, {14880, 676}, {14204, 618}, {13586, 566}, {13020, 520}, {12500, 481}, {12019, 445}, {11574, 414}, {11160, 385}, {10775, 359}, {10416, 336}, {10080, 315}, {9765, 296}, {9469, 278}, {9191, 263}, {8928, 248}, {8680, 235}, {8445, 222}, {8223, 211}, {8012, 200}, {7812, 191}, {7621, 181}, {7440, 173}, {7267, 165}, {7102, 158}, {6944, 151}, {6793, 145}, {6648, 138}, {6510, 133}, {6377, 127}, {6250, 123}, {6127, 118}, {6009, 113}, {5896, 109}, {5787, 106}, {5681, 101}, {5580, 98}, {5482, 95}, {5387, 91}, {5296, 88}, {5208, 86}, {5122, 82}, {5040, 80}, {4960, 78}, {4882, 75}, {4807, 73}, {4734, 70}, {4664, 69}, {4595, 67}, {4528, 64}, {4464, 63}, {4401, 61}, {4340, 60}, {4280, 58}, {4222, 56}, {4166, 55}, {4111, 53}, {4058, 52}, {4006, 51}, {3955, 49}, {3906, 48}, {3858, 48}, {3810, 45}, {3765, 45}, {3720, 44}, {3676, 43}, {3633, 42}, {3591, 40}, {3551, 40}, {3511, 39}, {3472, 38}, {3434, 38}, {3396, 36}, {3360, 36}, {3324, 35}, {3289, 34}, {3255, 34}, {3221, 33}, {3188, 32}, {3156, 31}, {3125, 31}, {3094, 31}, {3063, 30}, {3033, 29}, {3004, 28}, {2976, 28}, {2948, 28}, {2920, 27}, {2893, 27}, {2866, 26}, {2840, 25}, {2815, 25}, {2790, 25}, {2765, 24}, {2741, 24}, {2717, 24}, {2693, 23}, {2670, 22}, {2648, 22}, {2626, 22}, {2604, 22}, {2582, 21}, {2561, 21}, {2540, 20}, {2520, 20}, {2500, 20}, {2480, 20}, {2460, 19}, {2441, 19}, {2422, 19}, {2403, 18}, {2385, 18}, {2367, 18}, {2349, 17}, {2332, 18}, {2314, 17}, {2297, 16}, {2281, 17}, {2264, 16}, {2248, 16}, {2232, 16}, {2216, 16}, {2200, 15}, {2185, 15}, {2170, 15}, {2155, 15}, {2140, 15}, {2125, 14}, {2111, 14}, {2097, 14}, {2083, 14}, {2069, 14}, {2055, 13}, {2042, 13}, {2029, 13}, {2016, 13}, {2003, 13}, {1990, 13}, {1977, 12}, {1965, 12}, {1953, 13}, {1940, 11}, {1929, 12}, {1917, 12}, {1905, 12}, {1893, 11}, {1882, 11}, {1871, 11}, {1860, 11}, {1849, 11}, {1838, 11}, {1827, 11}, {1816, 10}, {1806, 11}, {1795, 10}, {1785, 10}, {1775, 10}, {1765, 10}, {1755, 10}, {1745, 9}, {1736, 10}, {1726, 9}, {1717, 10}, {1707, 9}, {1698, 9}, {1689, 9}, {1680, 9}, {1671, 9}, {1662, 9}, {1653, 9}, {1644, 8}, {1636, 9}, {1627, 8}, {1619, 9}, {1610, 8}, {1602, 8}, {1594, 8}, {1586, 8}, {1578, 8}, {1570, 8}, {1562, 8}, {1554, 7}, {1547, 8}, {1539, 8}, {1531, 7}, {1524, 8}, {1516, 7}, {1509, 7}, {1502, 7}, {1495, 7}, {1488, 7}, {1481, 7}, {1474, 7}, {1467, 7}, {1460, 7}, {1453, 7}, {1446, 6}, {1440, 7}, {1433, 7}, {1426, 6}, {1420, 6}, {1414, 7}, {1407, 6}, {1401, 6}, {1395, 7}, {1388, 6}, {1382, 6}, {1376, 6}, {1370, 6}, {1364, 6}, {1358, 6}, {1352, 6}, {1346, 5}, {1341, 6}, {1335, 6}, {1329, 5}, {1324, 6}, {1318, 5}, {1313, 6}, {1307, 5}, {1302, 6}, {1296, 5}, {1291, 5}, {1286, 6}, {1280, 5}, {1275, 5}, {1270, 5}, {1265, 5}, {1260, 5}, {1255, 5}, {1250, 5}, {1245, 5}, {1240, 5}, {1235, 5}, {1230, 5}, {1225, 5}, {1220, 5}, {1215, 4}, {1211, 5}, {1206, 5}, {1201, 5}, }; #endif #endif ================================================ FILE: Sprinter/store_eeprom.cpp ================================================ /* EEPROM routines to save Sprinter Settings This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ #include #include #include #include "Sprinter.h" #include "store_eeprom.h" #include "Configuration.h" #ifdef PIDTEMP extern unsigned int PID_Kp, PID_Ki, PID_Kd; #endif #ifdef USE_EEPROM_SETTINGS //====================================================================================== //========================= Read / Write EEPROM ======================================= template int EEPROM_write_setting(int address, const T& value) { const byte* p = (const byte*)(const void*)&value; int i; for (i = 0; i < (int)sizeof(value); i++) eeprom_write_byte((unsigned char *)address++, *p++); return i; } template int EEPROM_read_setting(int address, T& value) { byte* p = (byte*)(void*)&value; int i; for (i = 0; i < (int)sizeof(value); i++) *p++ = eeprom_read_byte((unsigned char *)address++); return i; } //====================================================================================== void EEPROM_StoreSettings() { char ver[4]= "000"; EEPROM_write_setting(EEPROM_OFFSET, ver); // invalidate data first EEPROM_write_setting(axis_steps_per_unit_address, axis_steps_per_unit); EEPROM_write_setting(max_feedrate_address, max_feedrate); EEPROM_write_setting(max_acceleration_units_per_sq_second_address, max_acceleration_units_per_sq_second); EEPROM_write_setting(move_acceleration_address, move_acceleration); EEPROM_write_setting(retract_acceleration_address, retract_acceleration); EEPROM_write_setting(minimumfeedrate_address, minimumfeedrate); EEPROM_write_setting(mintravelfeedrate_address, mintravelfeedrate); EEPROM_write_setting(min_seg_time_address, min_seg_time); //Min Segment Time, not used yet EEPROM_write_setting(max_xy_jerk_address, max_xy_jerk); EEPROM_write_setting(max_z_jerk_address, max_z_jerk); EEPROM_write_setting(max_e_jerk_address, max_e_jerk); //PID Settings #ifdef PIDTEMP EEPROM_write_setting(Kp_address, PID_Kp); //Kp EEPROM_write_setting(Ki_address, PID_Ki); //Ki EEPROM_write_setting(Kd_address, PID_Kd); //Kd #else EEPROM_write_setting(Kp_address, 2048); //Kp EEPROM_write_setting(Ki_address, 32); //Ki EEPROM_write_setting(Kd_address, 2048); //Kd #endif char ver2[4]=EEPROM_VERSION; EEPROM_write_setting(EEPROM_OFFSET, ver2); // validate data showString(PSTR("Settings Stored\r\n")); } void EEPROM_printSettings() { #ifdef PRINT_EEPROM_SETTING showString(PSTR("Steps per unit:\r\n")); showString(PSTR(" M92 X")); Serial.print(axis_steps_per_unit[0]); showString(PSTR(" Y")); Serial.print(axis_steps_per_unit[1]); showString(PSTR(" Z")); Serial.print(axis_steps_per_unit[2]); showString(PSTR(" E")); Serial.println(axis_steps_per_unit[3]); showString(PSTR("Maximum feedrates (mm/s):\r\n")); showString(PSTR(" M202 X")); Serial.print(max_feedrate[0]); showString(PSTR(" Y")); Serial.print(max_feedrate[1]); showString(PSTR(" Z")); Serial.print(max_feedrate[2]); showString(PSTR(" E")); Serial.println(max_feedrate[3]); showString(PSTR("Maximum Acceleration (mm/s2):\r\n")); showString(PSTR(" M201 X")); Serial.print(max_acceleration_units_per_sq_second[0] ); showString(PSTR(" Y")); Serial.print(max_acceleration_units_per_sq_second[1] ); showString(PSTR(" Z")); Serial.print(max_acceleration_units_per_sq_second[2] ); showString(PSTR(" E")); Serial.println(max_acceleration_units_per_sq_second[3]); showString(PSTR("Acceleration: S=acceleration, T=retract acceleration\r\n")); showString(PSTR(" M204 S")); Serial.print(move_acceleration ); showString(PSTR(" T")); Serial.println(retract_acceleration); showString(PSTR("Advanced variables (mm/s): S=Min feedrate, T=Min travel feedrate, X=max xY jerk, Z=max Z jerk, E=max E jerk\r\n")); showString(PSTR(" M205 S")); Serial.print(minimumfeedrate ); showString(PSTR(" T" )); Serial.print(mintravelfeedrate ); // showString(PSTR(" B")); // Serial.print(min_seg_time ); showString(PSTR(" X")); Serial.print(max_xy_jerk ); showString(PSTR(" Z")); Serial.print(max_z_jerk); showString(PSTR(" E")); Serial.println(max_e_jerk); #ifdef PIDTEMP showString(PSTR("PID settings:\r\n")); showString(PSTR(" M301 P")); Serial.print(PID_Kp); showString(PSTR(" I")); Serial.print(PID_Ki); showString(PSTR(" D")); Serial.println(PID_Kd); #endif #endif } void EEPROM_RetrieveSettings(bool def, bool printout) { // if def=true, the default values will be used int i=EEPROM_OFFSET; char stored_ver[4]; char ver[4]=EEPROM_VERSION; EEPROM_read_setting(EEPROM_OFFSET,stored_ver); //read stored version if ((!def)&&(strncmp(ver,stored_ver,3)==0)) { // version number match EEPROM_read_setting(axis_steps_per_unit_address, axis_steps_per_unit); EEPROM_read_setting(max_feedrate_address, max_feedrate); EEPROM_read_setting(max_acceleration_units_per_sq_second_address, max_acceleration_units_per_sq_second); EEPROM_read_setting(move_acceleration_address, move_acceleration); EEPROM_read_setting(retract_acceleration_address, retract_acceleration); EEPROM_read_setting(minimumfeedrate_address, minimumfeedrate); EEPROM_read_setting(mintravelfeedrate_address, mintravelfeedrate); EEPROM_read_setting(min_seg_time_address, min_seg_time); //min Segmenttime --> not used yet EEPROM_read_setting(max_xy_jerk_address, max_xy_jerk); EEPROM_read_setting(max_z_jerk_address, max_z_jerk); EEPROM_read_setting(max_e_jerk_address, max_e_jerk); #ifdef PIDTEMP EEPROM_read_setting(Kp_address, PID_Kp); EEPROM_read_setting(Ki_address, PID_Ki); EEPROM_read_setting(Kd_address, PID_Kd); #endif showString(PSTR("Stored settings retreived\r\n")); } else { float tmp1[]=_AXIS_STEP_PER_UNIT; float tmp2[]=_MAX_FEEDRATE; long tmp3[]=_MAX_ACCELERATION_UNITS_PER_SQ_SECOND; for (short i=0;i<4;i++) { axis_steps_per_unit[i]=tmp1[i]; max_feedrate[i]=tmp2[i]; max_acceleration_units_per_sq_second[i]=tmp3[i]; } move_acceleration=_ACCELERATION; retract_acceleration=_RETRACT_ACCELERATION; minimumfeedrate=DEFAULT_MINIMUMFEEDRATE; mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE; max_xy_jerk=_MAX_XY_JERK; max_z_jerk=_MAX_Z_JERK; max_e_jerk=_MAX_E_JERK; min_seg_time=_MIN_SEG_TIME; #ifdef PIDTEMP PID_Kp = PID_PGAIN; PID_Ki = PID_IGAIN; PID_Kd = PID_DGAIN; #endif showString(PSTR("Using Default settings\r\n")); } if(printout) { EEPROM_printSettings(); } } #endif ================================================ FILE: Sprinter/store_eeprom.h ================================================ /* EEPROM routines to save Sprinter Settings This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ #ifndef __EEPROMH #define __EEPROMH #define EEPROM_OFFSET 100 // IMPORTANT: Whenever there are changes made to the variables stored in EEPROM // in the functions below, also increment the version number. This makes sure that // the default values are used whenever there is a change to the data, to prevent // wrong data being written to the variables. // ALSO: always make sure the variables in the Store and retrieve sections are in the same order. #define EEPROM_VERSION "S03" extern float axis_steps_per_unit[4]; extern float max_feedrate[4]; extern long max_acceleration_units_per_sq_second[4]; extern float move_acceleration; extern float retract_acceleration; extern float mintravelfeedrate; extern float minimumfeedrate; extern float max_xy_jerk; extern float max_z_jerk; extern float max_e_jerk; extern unsigned long min_seg_time; #define axis_steps_per_unit_address (EEPROM_OFFSET + 4*sizeof(char)) #define max_feedrate_address (axis_steps_per_unit_address + 4*sizeof(float)) #define max_acceleration_units_per_sq_second_address (max_feedrate_address + 4*sizeof(float)) #define move_acceleration_address (max_acceleration_units_per_sq_second_address + 4*sizeof(long)) #define retract_acceleration_address (move_acceleration_address + sizeof(float)) #define mintravelfeedrate_address (retract_acceleration_address + sizeof(float)) #define minimumfeedrate_address (mintravelfeedrate_address + sizeof(float)) #define max_xy_jerk_address (minimumfeedrate_address + sizeof(float)) #define max_z_jerk_address (max_xy_jerk_address + sizeof(float)) #define max_e_jerk_address (max_z_jerk_address + sizeof(float)) #define min_seg_time_address (max_e_jerk_address + sizeof(float)) #define Kp_address (min_seg_time_address + sizeof(unsigned long)) #define Ki_address (Kp_address + sizeof(unsigned int)) #define Kd_address (Ki_address + sizeof(unsigned int)) extern void EEPROM_RetrieveSettings(bool def, bool printout ); extern void EEPROM_printSettings(); extern void EEPROM_StoreSettings(); #endif ================================================ FILE: Sprinter/thermistortables.h ================================================ #ifndef THERMISTORTABLES_H_ #define THERMISTORTABLES_H_ #if (THERMISTORHEATER == 1) || (THERMISTORBED == 1) //100k bed thermistor #define NUMTEMPS_1 61 const short temptable_1[NUMTEMPS_1][2] = { { 23 , 300 }, { 25 , 295 }, { 27 , 290 }, { 28 , 285 }, { 31 , 280 }, { 33 , 275 }, { 35 , 270 }, { 38 , 265 }, { 41 , 260 }, { 44 , 255 }, { 48 , 250 }, { 52 , 245 }, { 56 , 240 }, { 61 , 235 }, { 66 , 230 }, { 71 , 225 }, { 78 , 220 }, { 84 , 215 }, { 92 , 210 }, { 100 , 205 }, { 109 , 200 }, { 120 , 195 }, { 131 , 190 }, { 143 , 185 }, { 156 , 180 }, { 171 , 175 }, { 187 , 170 }, { 205 , 165 }, { 224 , 160 }, { 245 , 155 }, { 268 , 150 }, { 293 , 145 }, { 320 , 140 }, { 348 , 135 }, { 379 , 130 }, { 411 , 125 }, { 445 , 120 }, { 480 , 115 }, { 516 , 110 }, { 553 , 105 }, { 591 , 100 }, { 628 , 95 }, { 665 , 90 }, { 702 , 85 }, { 737 , 80 }, { 770 , 75 }, { 801 , 70 }, { 830 , 65 }, { 857 , 60 }, { 881 , 55 }, { 903 , 50 }, { 922 , 45 }, { 939 , 40 }, { 954 , 35 }, { 966 , 30 }, { 977 , 25 }, { 985 , 20 }, { 993 , 15 }, { 999 , 10 }, { 1004 , 5 }, { 1008 , 0 } //safety }; #endif #if (THERMISTORHEATER == 2) || (THERMISTORBED == 2) //200k bed thermistor verified by arcol #define NUMTEMPS_2 64 const short temptable_2[NUMTEMPS_2][2] = { { 16, 315}, { 17, 310}, { 18, 305}, { 19, 300}, { 20, 295}, { 21, 290}, { 22, 285}, { 23, 280}, { 24, 275}, { 25, 270}, { 29, 265}, { 30, 260}, { 35, 255}, { 40, 250}, { 45, 245}, { 50, 240}, { 55, 235}, { 60, 230}, { 65, 225}, { 70, 220}, { 90, 215}, { 95, 210}, { 103, 205}, { 105, 200}, { 115, 195}, { 130, 190}, { 150, 185}, { 167, 180}, { 190, 175}, { 200, 170}, { 230, 165}, { 250, 160}, { 270, 155}, { 300, 150}, { 330, 145}, { 360, 140}, { 380, 135}, { 408, 130}, { 450, 125}, { 500, 120}, { 530, 115}, { 550, 110}, { 570, 105}, { 595, 100}, { 615, 95}, { 640, 90}, { 665, 85}, { 700, 80}, { 740, 75}, { 780, 70}, { 810, 65}, { 840, 60}, { 880, 55}, { 920, 50}, { 960, 45}, { 980, 40}, { 990, 35}, {1000, 30}, {1005, 25}, {1006, 20}, {1009, 15}, {1010, 10}, {1020, 5}, {1023, 0} //safety }; #endif #if (THERMISTORHEATER == 3) || (THERMISTORBED == 3) //mendel-parts #define NUMTEMPS_3 28 const short temptable_3[NUMTEMPS_3][2] = { {1,864}, {21,300}, {25,290}, {29,280}, {33,270}, {39,260}, {46,250}, {54,240}, {64,230}, {75,220}, {90,210}, {107,200}, {128,190}, {154,180}, {184,170}, {221,160}, {265,150}, {316,140}, {375,130}, {441,120}, {513,110}, {588,100}, {734,80}, {856,60}, {938,40}, {986,20}, {1008,0}, {1018,-20} }; #endif #if (THERMISTORHEATER == 4) || (THERMISTORBED == 4) //10k thermistor #define NUMTEMPS_4 20 const short temptable_4[NUMTEMPS_4][2] = { {1, 430}, {54, 137}, {107, 107}, {160, 91}, {213, 80}, {266, 71}, {319, 64}, {372, 57}, {425, 51}, {478, 46}, {531, 41}, {584, 35}, {637, 30}, {690, 25}, {743, 20}, {796, 14}, {849, 7}, {902, 0}, {955, -11}, {1008, -35} }; #endif #if (THERMISTORHEATER == 5) || (THERMISTORBED == 5) //100k ParCan thermistor (104GT-2) #define NUMTEMPS_5 61 const short temptable_5[NUMTEMPS_5][2] = { {1, 713}, {18, 316}, {35, 266}, {52, 239}, {69, 221}, {86, 208}, {103, 197}, {120, 188}, {137, 181}, {154, 174}, {171, 169}, {188, 163}, {205, 159}, {222, 154}, {239, 150}, {256, 147}, {273, 143}, {290, 140}, {307, 136}, {324, 133}, {341, 130}, {358, 128}, {375, 125}, {392, 122}, {409, 120}, {426, 117}, {443, 115}, {460, 112}, {477, 110}, {494, 108}, {511, 106}, {528, 103}, {545, 101}, {562, 99}, {579, 97}, {596, 95}, {613, 92}, {630, 90}, {647, 88}, {664, 86}, {681, 84}, {698, 81}, {715, 79}, {732, 77}, {749, 75}, {766, 72}, {783, 70}, {800, 67}, {817, 64}, {834, 61}, {851, 58}, {868, 55}, {885, 52}, {902, 48}, {919, 44}, {936, 40}, {953, 34}, {970, 28}, {987, 20}, {1004, 8}, {1021, 0} }; #endif #if (THERMISTORHEATER == 6) || (THERMISTORBED == 6) // 100k Epcos thermistor #define NUMTEMPS_6 36 const short temptable_6[NUMTEMPS_6][2] = { {28, 250}, {31, 245}, {35, 240}, {39, 235}, {42, 230}, {44, 225}, {49, 220}, {53, 215}, {62, 210}, {71, 205}, //fitted graphically {78, 200}, //fitted graphically {94, 190}, {102, 185}, {116, 170}, {143, 160}, {183, 150}, {223, 140}, {270, 130}, {318, 120}, {383, 110}, {413, 105}, {439, 100}, {484, 95}, {513, 90}, {607, 80}, {664, 70}, {781, 60}, {810, 55}, {849, 50}, {914, 45}, {914, 40}, {935, 35}, {954, 30}, {970, 25}, {978, 22}, {1008, 3} }; #endif #if (THERMISTORHEATER == 7) || (THERMISTORBED == 7) // 100k Honeywell 135-104LAG-J01 #define NUMTEMPS_7 55 const short temptable_7[NUMTEMPS_7][2] = { {46, 270}, {50, 265}, {54, 260}, {58, 255}, {62, 250}, {67, 245}, {72, 240}, {79, 235}, {85, 230}, {91, 225}, {99, 220}, {107, 215}, {116, 210}, {126, 205}, {136, 200}, {149, 195}, {160, 190}, {175, 185}, {191, 180}, {209, 175}, {224, 170}, {246, 165}, {267, 160}, {293, 155}, {316, 150}, {340, 145}, {364, 140}, {396, 135}, {425, 130}, {460, 125}, {489, 120}, {526, 115}, {558, 110}, {591, 105}, {628, 100}, {660, 95}, {696, 90}, {733, 85}, {761, 80}, {794, 75}, {819, 70}, {847, 65}, {870, 60}, {892, 55}, {911, 50}, {929, 45}, {944, 40}, {959, 35}, {971, 30}, {981, 25}, {989, 20}, {994, 15}, {1001, 10}, {1005, 5}, {1021, 0} //safety }; #endif #if THERMISTORHEATER == 1 #define NUMTEMPS NUMTEMPS_1 #define temptable temptable_1 #elif THERMISTORHEATER == 2 #define NUMTEMPS NUMTEMPS_2 #define temptable temptable_2 #elif THERMISTORHEATER == 3 #define NUMTEMPS NUMTEMPS_3 #define temptable temptable_3 #elif THERMISTORHEATER == 4 #define NUMTEMPS NUMTEMPS_4 #define temptable temptable_4 #elif THERMISTORHEATER == 5 #define NUMTEMPS NUMTEMPS_5 #define temptable temptable_5 #elif THERMISTORHEATER == 6 #define NUMTEMPS NUMTEMPS_6 #define temptable temptable_6 #elif THERMISTORHEATER == 7 #define NUMTEMPS NUMTEMPS_7 #define temptable temptable_7 #elif defined HEATER_USES_THERMISTOR #error No heater thermistor table specified #endif #if THERMISTORBED == 1 #define BNUMTEMPS NUMTEMPS_1 #define bedtemptable temptable_1 #elif THERMISTORBED == 2 #define BNUMTEMPS NUMTEMPS_2 #define bedtemptable temptable_2 #elif THERMISTORBED == 3 #define BNUMTEMPS NUMTEMPS_3 #define bedtemptable temptable_3 #elif THERMISTORBED == 4 #define BNUMTEMPS NUMTEMPS_4 #define bedtemptable temptable_4 #elif THERMISTORBED == 5 #define BNUMTEMPS NUMTEMPS_5 #define bedtemptable temptable_5 #elif THERMISTORBED == 6 #define BNUMTEMPS NUMTEMPS_6 #define bedtemptable temptable_6 #elif THERMISTORBED == 7 #define BNUMTEMPS NUMTEMPS_7 #define bedtemptable temptable_7 #elif defined BED_USES_THERMISTOR #error No bed thermistor table specified #endif #endif //THERMISTORTABLES_H_