├── Sprinter
├── arc_func.h
├── store_eeprom.h
├── SdFatUtil.h
├── heater.h
├── Sprinter.h
├── createTemperatureLookup.py
├── arc_func.cpp
├── SdInfo.h
├── store_eeprom.cpp
├── Makefile
├── SdFatmainpage.h
├── thermistortables.h
├── Sd2Card.h
├── SdVolume.cpp
├── speed_lookuptable.h
├── Sd2PinMap.h
├── FatStructs.h
├── Configuration.h
├── Sd2Card.cpp
└── SdFat.h
└── README
/Sprinter/arc_func.h:
--------------------------------------------------------------------------------
1 | /*
2 | arc_func.h - high level interface for issuing motion commands
3 | Part of Grbl
4 |
5 | Copyright (c) 2009-2011 Simen Svale Skogsrud
6 | Copyright (c) 2011 Sungeun K. Jeon
7 |
8 | Grbl is free software: you can redistribute it and/or modify
9 | it under the terms of the GNU General Public License as published by
10 | the Free Software Foundation, either version 3 of the License, or
11 | (at your option) any later version.
12 |
13 | Grbl is distributed in the hope that it will be useful,
14 | but WITHOUT ANY WARRANTY; without even the implied warranty of
15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16 | GNU General Public License for more details.
17 |
18 | You should have received a copy of the GNU General Public License
19 | along with Grbl. If not, see .
20 | */
21 |
22 | #ifndef arc_func_h
23 | #define arc_func_h
24 |
25 | // Execute an arc in offset mode format. position == current xyz, target == target xyz,
26 | // offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
27 | // the direction of helical travel, radius == circle radius, isclockwise boolean. Used
28 | // for vector transformation direction.
29 | void mc_arc(float *position, float *target, float *offset, unsigned char axis_0, unsigned char axis_1,
30 | unsigned char axis_linear, float feed_rate, float radius, unsigned char isclockwise);
31 |
32 | #endif
33 |
--------------------------------------------------------------------------------
/Sprinter/store_eeprom.h:
--------------------------------------------------------------------------------
1 | /*
2 | EEPROM routines to save Sprinter Settings
3 |
4 | This program is free software: you can redistribute it and/or modify
5 | it under the terms of the GNU General Public License as published by
6 | the Free Software Foundation, either version 3 of the License, or
7 | (at your option) any later version.
8 |
9 | This program is distributed in the hope that it will be useful,
10 | but WITHOUT ANY WARRANTY; without even the implied warranty of
11 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 | GNU General Public License for more details.
13 |
14 | You should have received a copy of the GNU General Public License
15 | along with this program. If not, see .
16 | */
17 |
18 |
19 | #ifndef __EEPROMH
20 | #define __EEPROMH
21 |
22 | #define EEPROM_OFFSET 100
23 |
24 |
25 | // IMPORTANT: Whenever there are changes made to the variables stored in EEPROM
26 | // in the functions below, also increment the version number. This makes sure that
27 | // the default values are used whenever there is a change to the data, to prevent
28 | // wrong data being written to the variables.
29 | // ALSO: always make sure the variables in the Store and retrieve sections are in the same order.
30 | #define EEPROM_VERSION "S03"
31 |
32 |
33 | extern float axis_steps_per_unit[4];
34 | extern float max_feedrate[4];
35 | extern long max_acceleration_units_per_sq_second[4];
36 | extern float move_acceleration;
37 | extern float retract_acceleration;
38 | extern float mintravelfeedrate;
39 | extern float minimumfeedrate;
40 | extern float max_xy_jerk;
41 | extern float max_z_jerk;
42 | extern float max_e_jerk;
43 | extern unsigned long min_seg_time;
44 |
45 | #define axis_steps_per_unit_address (EEPROM_OFFSET + 4*sizeof(char))
46 | #define max_feedrate_address (axis_steps_per_unit_address + 4*sizeof(float))
47 | #define max_acceleration_units_per_sq_second_address (max_feedrate_address + 4*sizeof(float))
48 | #define move_acceleration_address (max_acceleration_units_per_sq_second_address + 4*sizeof(long))
49 | #define retract_acceleration_address (move_acceleration_address + sizeof(float))
50 | #define mintravelfeedrate_address (retract_acceleration_address + sizeof(float))
51 | #define minimumfeedrate_address (mintravelfeedrate_address + sizeof(float))
52 | #define max_xy_jerk_address (minimumfeedrate_address + sizeof(float))
53 | #define max_z_jerk_address (max_xy_jerk_address + sizeof(float))
54 | #define max_e_jerk_address (max_z_jerk_address + sizeof(float))
55 | #define min_seg_time_address (max_e_jerk_address + sizeof(float))
56 | #define Kp_address (min_seg_time_address + sizeof(unsigned long))
57 | #define Ki_address (Kp_address + sizeof(unsigned int))
58 | #define Kd_address (Ki_address + sizeof(unsigned int))
59 |
60 | extern void EEPROM_RetrieveSettings(bool def, bool printout );
61 | extern void EEPROM_printSettings();
62 | extern void EEPROM_StoreSettings();
63 |
64 |
65 | #endif
66 |
--------------------------------------------------------------------------------
/Sprinter/SdFatUtil.h:
--------------------------------------------------------------------------------
1 | /* Arduino SdFat Library
2 | * Copyright (C) 2008 by William Greiman
3 | *
4 | * This file is part of the Arduino SdFat Library
5 | *
6 | * This Library is free software: you can redistribute it and/or modify
7 | * it under the terms of the GNU General Public License as published by
8 | * the Free Software Foundation, either version 3 of the License, or
9 | * (at your option) any later version.
10 | *
11 | * This Library is distributed in the hope that it will be useful,
12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | * GNU General Public License for more details.
15 |
16 | * You should have received a copy of the GNU General Public License
17 | * along with the Arduino SdFat Library. If not, see
18 | * .
19 | */
20 | #ifndef SdFatUtil_h
21 | #define SdFatUtil_h
22 | /**
23 | * \file
24 | * Useful utility functions.
25 | */
26 | #if defined(ARDUINO) && ARDUINO >= 100
27 | #include
28 | #else
29 | #include
30 | #endif
31 | #include
32 | /** Store and print a string in flash memory.*/
33 | #define PgmPrint(x) SerialPrint_P(PSTR(x))
34 | /** Store and print a string in flash memory followed by a CR/LF.*/
35 | #define PgmPrintln(x) SerialPrintln_P(PSTR(x))
36 | /** Defined so doxygen works for function definitions. */
37 | #define NOINLINE __attribute__((noinline))
38 | //------------------------------------------------------------------------------
39 | /** Return the number of bytes currently free in RAM. */
40 | static int FreeRam(void) {
41 | extern int __bss_end;
42 | extern int* __brkval;
43 | int free_memory;
44 | if (reinterpret_cast(__brkval) == 0) {
45 | // if no heap use from end of bss section
46 | free_memory = reinterpret_cast(&free_memory)
47 | - reinterpret_cast(&__bss_end);
48 | } else {
49 | // use from top of stack to heap
50 | free_memory = reinterpret_cast(&free_memory)
51 | - reinterpret_cast(__brkval);
52 | }
53 | return free_memory;
54 | }
55 | //------------------------------------------------------------------------------
56 | /**
57 | * %Print a string in flash memory to the serial port.
58 | *
59 | * \param[in] str Pointer to string stored in flash memory.
60 | */
61 | static NOINLINE void SerialPrint_P(PGM_P str) {
62 | for (uint8_t c; (c = pgm_read_byte(str)); str++) Serial.print(char(c));
63 | }
64 | //------------------------------------------------------------------------------
65 | /**
66 | * %Print a string in flash memory followed by a CR/LF.
67 | *
68 | * \param[in] str Pointer to string stored in flash memory.
69 | */
70 | static NOINLINE void SerialPrintln_P(PGM_P str) {
71 | SerialPrint_P(str);
72 | Serial.println();
73 | }
74 | #endif // #define SdFatUtil_h
75 |
--------------------------------------------------------------------------------
/Sprinter/heater.h:
--------------------------------------------------------------------------------
1 | /*
2 | Reprap heater funtions based on Sprinter
3 |
4 | This program is free software: you can redistribute it and/or modify
5 | it under the terms of the GNU General Public License as published by
6 | the Free Software Foundation, either version 3 of the License, or
7 | (at your option) any later version.
8 |
9 | This program is distributed in the hope that it will be useful,
10 | but WITHOUT ANY WARRANTY; without even the implied warranty of
11 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 | GNU General Public License for more details.
13 |
14 | You should have received a copy of the GNU General Public License
15 | along with this program. If not, see . */
16 |
17 | /*
18 | This softwarepart for Heatercontrol is based on Sprinter
19 | big thanks to kliment (https://github.com/kliment/Sprinter)
20 |
21 | */
22 |
23 |
24 | #include "Configuration.h"
25 | #include "thermistortables.h"
26 |
27 | #if defined HEATER_USES_THERMISTOR
28 | #define temp2analogh( c ) temp2analog_thermistor(c,temptable,NUMTEMPS)
29 | #define analog2temp( c ) analog2temp_thermistor(c,temptable,NUMTEMPS)
30 | #elif defined HEATER_USES_AD595
31 | #define temp2analogh( c ) temp2analog_ad595(c)
32 | #define analog2temp( c ) analog2temp_ad595(c)
33 | #elif defined HEATER_USES_MAX6675
34 | #define temp2analogh( c ) temp2analog_max6675(c)
35 | #define analog2temp( c ) analog2temp_max6675(c)
36 | #endif
37 |
38 | #if defined BED_USES_THERMISTOR
39 | #define temp2analogBed( c ) temp2analog_thermistor((c),bedtemptable,BNUMTEMPS)
40 | #define analog2tempBed( c ) analog2temp_thermistor((c),bedtemptable,BNUMTEMPS)
41 | #elif defined BED_USES_AD595
42 | #define temp2analogBed( c ) temp2analog_ad595(c)
43 | #define analog2tempBed( c ) analog2temp_ad595(c)
44 | #elif defined BED_USES_MAX6675
45 | #define temp2analogBed( c ) temp2analog_max6675(c)
46 | #define analog2tempBed( c ) analog2temp_max6675(c)
47 | #endif
48 |
49 | #if defined (HEATER_USES_THERMISTOR) || defined (BED_USES_THERMISTOR)
50 | int temp2analog_thermistor(int celsius, const short table[][2], int numtemps);
51 | int analog2temp_thermistor(int raw,const short table[][2], int numtemps);
52 | #endif
53 |
54 | #if defined (HEATER_USES_AD595) || defined (BED_USES_AD595)
55 | int temp2analog_ad595(int celsius);
56 | int analog2temp_ad595(int raw);
57 | #endif
58 |
59 | #if defined (HEATER_USES_MAX6675) || defined (BED_USES_MAX6675)
60 | int temp2analog_max6675(int celsius);
61 | int analog2temp_max6675(int raw);
62 | #endif
63 |
64 |
65 | extern int target_raw;
66 | extern int target_temp;
67 | extern int current_raw;
68 | extern int current_raw_maxval;
69 | extern int current_raw_minval;
70 | extern int tt_maxval;
71 | extern int tt_minval;
72 | extern int target_bed_raw;
73 | extern int current_bed_raw;
74 | extern unsigned long previous_millis_heater, previous_millis_bed_heater;
75 | extern unsigned char manage_monitor;
76 |
77 | #ifdef PIDTEMP
78 | extern volatile unsigned char g_heater_pwm_val;
79 |
80 | extern unsigned char PWM_off_time;
81 | extern unsigned char PWM_out_on;
82 |
83 | extern int temp_iState;
84 | extern int temp_dState;
85 | extern int prev_temp;
86 | extern int pTerm;
87 | extern int iTerm;
88 | extern int dTerm;
89 | extern int error;
90 | extern int heater_duty;
91 |
92 | extern unsigned int PID_Kp, PID_Ki, PID_Kd;
93 | #endif
94 |
95 | #if defined(FAN_SOFT_PWM) && (FAN_PIN > -1)
96 | extern volatile unsigned char g_fan_pwm_val;
97 | #endif
98 |
99 | #ifdef AUTOTEMP
100 | extern float autotemp_max;
101 | extern float autotemp_min;
102 | extern float autotemp_factor;
103 | extern int autotemp_setpoint;
104 | extern bool autotemp_enabled;
105 | #endif
106 |
107 |
108 | #ifdef SMOOTHING
109 | extern uint32_t nma;
110 | #endif
111 |
112 | #ifdef WATCHPERIOD
113 | extern int watch_raw;
114 | extern unsigned long watchmillis;
115 | #endif
116 |
117 |
118 |
119 |
120 | #if defined(PID_SOFT_PWM) || (defined(FAN_SOFT_PWM) && (FAN_PIN > -1))
121 | void init_Timer2_softpwm(void);
122 | #endif
123 |
124 | #ifdef PID_AUTOTUNE
125 | void PID_autotune(int PIDAT_test_temp);
126 | #endif
127 |
128 | #ifdef PIDTEMP
129 | void updatePID();
130 | #endif
131 |
132 | void manage_heater();
133 |
--------------------------------------------------------------------------------
/Sprinter/Sprinter.h:
--------------------------------------------------------------------------------
1 | // Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
2 | // Licence: GPL
3 |
4 | //Check Version of Arduino and then include the right libraries
5 | #if defined(ARDUINO) && ARDUINO >= 100
6 | #include "Arduino.h"
7 | #else
8 | #include
9 | #endif
10 |
11 | #include "fastio.h"
12 |
13 | extern "C" void __cxa_pure_virtual();
14 |
15 | #define FORCE_INLINE __attribute__((always_inline)) inline
16 |
17 | #if X_ENABLE_PIN > -1
18 | #define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
19 | #define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
20 | #else
21 | #define enable_x() ;
22 | #define disable_x() ;
23 | #endif
24 | #if Y_ENABLE_PIN > -1
25 | #define enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
26 | #define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON)
27 | #else
28 | #define enable_y() ;
29 | #define disable_y() ;
30 | #endif
31 | #if Z_ENABLE_PIN > -1
32 | #define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
33 | #define disable_z() WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON)
34 | #else
35 | #define enable_z() ;
36 | #define disable_z() ;
37 | #endif
38 | #if E_ENABLE_PIN > -1
39 | #define enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
40 | #define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
41 | #else
42 | #define enable_e() ;
43 | #define disable_e() ;
44 | #endif
45 |
46 | #define X_AXIS 0
47 | #define Y_AXIS 1
48 | #define Z_AXIS 2
49 | #define E_AXIS 3
50 |
51 |
52 | // This struct is used when buffering the setup for each linear movement "nominal" values are as specified in
53 | // the source g-code and may never actually be reached if acceleration management is active.
54 | typedef struct {
55 | // Fields used by the bresenham algorithm for tracing the line
56 | long steps_x, steps_y, steps_z, steps_e; // Step count along each axis
57 |
58 | unsigned long step_event_count; // The number of step events required to complete this block
59 | long accelerate_until; // The index of the step event on which to stop acceleration
60 | long decelerate_after; // The index of the step event on which to start decelerating
61 | long acceleration_rate; // The acceleration rate used for acceleration calculation
62 | unsigned char direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
63 |
64 | #ifdef ADVANCE
65 | long advance_rate;
66 | volatile long initial_advance;
67 | volatile long final_advance;
68 | float advance;
69 | #endif
70 |
71 | // Fields used by the motion planner to manage acceleration
72 | // float speed_x, speed_y, speed_z, speed_e; // Nominal mm/minute for each axis
73 | float nominal_speed; // The nominal speed for this block in mm/min
74 | float entry_speed; // Entry speed at previous-current junction in mm/min
75 | float max_entry_speed; // Maximum allowable junction entry speed in mm/min
76 | float millimeters; // The total travel of this block in mm
77 | float acceleration; // acceleration mm/sec^2
78 | unsigned char recalculate_flag; // Planner flag to recalculate trapezoids on entry junction
79 | unsigned char nominal_length_flag; // Planner flag for nominal speed always reached
80 |
81 |
82 | // Settings for the trapezoid generator
83 | long nominal_rate; // The nominal step rate for this block in step_events/sec
84 | long initial_rate; // The jerk-adjusted step rate at start of block
85 | long final_rate; // The minimal rate at exit
86 | long acceleration_st; // acceleration steps/sec^2
87 | volatile char busy;
88 | } block_t;
89 |
90 |
91 | void FlushSerialRequestResend();
92 | void ClearToSend();
93 |
94 | void analogWrite_check(uint8_t check_pin, int val);
95 | void showString (PGM_P s);
96 |
97 | void manage_inactivity(byte debug);
98 |
99 | void get_command();
100 | void get_coordinates();
101 | void prepare_move();
102 | void prepare_arc_move(char isclockwise);
103 | FORCE_INLINE void process_commands();
104 | #ifdef USE_ARC_FUNCTION
105 | FORCE_INLINE void get_arc_coordinates();
106 | #endif
107 |
108 | void kill(byte debug);
109 |
110 | void check_axes_activity();
111 | void plan_init();
112 | void st_init();
113 | void tp_init();
114 | void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
115 | void plan_set_position(float x, float y, float z, float e);
116 | void st_wake_up();
117 | void st_synchronize();
118 | void st_set_position(const long &x, const long &y, const long &z, const long &e);
119 |
120 | void check_buffer_while_arc();
121 |
122 | #ifdef SDSUPPORT
123 | void print_disk_info(void);
124 | #endif //SDSUPPORT
125 |
126 | #if (MINIMUM_FAN_START_SPEED > 0)
127 | void manage_fan_start_speed(void);
128 | #endif
129 |
130 | #ifdef DEBUG
131 | void log_message(char* message);
132 | void log_bool(char* message, bool value);
133 | void log_int(char* message, int value);
134 | void log_long(char* message, long value);
135 | void log_float(char* message, float value);
136 | void log_uint(char* message, unsigned int value);
137 | void log_ulong(char* message, unsigned long value);
138 | #endif
139 |
--------------------------------------------------------------------------------
/Sprinter/createTemperatureLookup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/python
2 | #
3 | # Creates a C code lookup table for doing ADC to temperature conversion
4 | # on a microcontroller
5 | # based on: http://hydraraptor.blogspot.com/2007/10/measuring-temperature-easy-way.html
6 | """Thermistor Value Lookup Table Generator
7 |
8 | Generates lookup to temperature values for use in a microcontroller in C format based on:
9 | http://hydraraptor.blogspot.com/2007/10/measuring-temperature-easy-way.html
10 |
11 | The main use is for Arduino programs that read data from the circuit board described here:
12 | http://make.rrrf.org/ts-1.0
13 |
14 | Usage: python createTemperatureLookup.py [options]
15 |
16 | Options:
17 | -h, --help show this help
18 | --r0=... thermistor rating where # is the ohm rating of the thermistor at t0 (eg: 10K = 10000)
19 | --t0=... thermistor temp rating where # is the temperature in Celsuis to get r0 (from your datasheet)
20 | --beta=... thermistor beta rating. see http://reprap.org/bin/view/Main/MeasuringThermistorBeta
21 | --r1=... R1 rating where # is the ohm rating of R1 (eg: 10K = 10000)
22 | --r2=... R2 rating where # is the ohm rating of R2 (eg: 10K = 10000)
23 | --num-temps=... the number of temperature points to calculate (default: 20)
24 | --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
25 | """
26 |
27 | from math import *
28 | import sys
29 | import getopt
30 |
31 | class Thermistor:
32 | "Class to do the thermistor maths"
33 | def __init__(self, r0, t0, beta, r1, r2):
34 | self.r0 = r0 # stated resistance, e.g. 10K
35 | self.t0 = t0 + 273.15 # temperature at stated resistance, e.g. 25C
36 | self.beta = beta # stated beta, e.g. 3500
37 | self.vadc = 5.0 # ADC reference
38 | self.vcc = 5.0 # supply voltage to potential divider
39 | self.k = r0 * exp(-beta / self.t0) # constant part of calculation
40 |
41 | if r1 > 0:
42 | self.vs = r1 * self.vcc / (r1 + r2) # effective bias voltage
43 | self.rs = r1 * r2 / (r1 + r2) # effective bias impedance
44 | else:
45 | self.vs = self.vcc # effective bias voltage
46 | self.rs = r2 # effective bias impedance
47 |
48 | def temp(self,adc):
49 | "Convert ADC reading into a temperature in Celcius"
50 | v = adc * self.vadc / 1024 # convert the 10 bit ADC value to a voltage
51 | r = self.rs * v / (self.vs - v) # resistance of thermistor
52 | return (self.beta / log(r / self.k)) - 273.15 # temperature
53 |
54 | def setting(self, t):
55 | "Convert a temperature into a ADC value"
56 | r = self.r0 * exp(self.beta * (1 / (t + 273.15) - 1 / self.t0)) # resistance of the thermistor
57 | v = self.vs * r / (self.rs + r) # the voltage at the potential divider
58 | return round(v / self.vadc * 1024) # the ADC reading
59 |
60 | def main(argv):
61 |
62 | r0 = 10000;
63 | t0 = 25;
64 | beta = 3947;
65 | r1 = 680;
66 | r2 = 1600;
67 | num_temps = int(20);
68 |
69 | try:
70 | opts, args = getopt.getopt(argv, "h", ["help", "r0=", "t0=", "beta=", "r1=", "r2="])
71 | except getopt.GetoptError:
72 | usage()
73 | sys.exit(2)
74 |
75 | for opt, arg in opts:
76 | if opt in ("-h", "--help"):
77 | usage()
78 | sys.exit()
79 | elif opt == "--r0":
80 | r0 = int(arg)
81 | elif opt == "--t0":
82 | t0 = int(arg)
83 | elif opt == "--beta":
84 | beta = int(arg)
85 | elif opt == "--r1":
86 | r1 = int(arg)
87 | elif opt == "--r2":
88 | r2 = int(arg)
89 |
90 | if r1:
91 | max_adc = int(1023 * r1 / (r1 + r2));
92 | else:
93 | max_adc = 1023
94 | increment = int(max_adc/(num_temps-1));
95 |
96 | t = Thermistor(r0, t0, beta, r1, r2)
97 |
98 | adcs = range(1, max_adc, increment);
99 | # adcs = [1, 20, 25, 30, 35, 40, 45, 50, 60, 70, 80, 90, 100, 110, 130, 150, 190, 220, 250, 300]
100 | first = 1
101 |
102 | print "// Thermistor lookup table for RepRap Temperature Sensor Boards (http://make.rrrf.org/ts)"
103 | print "// Made with createTemperatureLookup.py (http://svn.reprap.org/trunk/reprap/firmware/Arduino/utilities/createTemperatureLookup.py)"
104 | print "// ./createTemperatureLookup.py --r0=%s --t0=%s --r1=%s --r2=%s --beta=%s --max-adc=%s" % (r0, t0, r1, r2, beta, max_adc)
105 | print "// r0: %s" % (r0)
106 | print "// t0: %s" % (t0)
107 | print "// r1: %s" % (r1)
108 | print "// r2: %s" % (r2)
109 | print "// beta: %s" % (beta)
110 | print "// max adc: %s" % (max_adc)
111 | print "#define NUMTEMPS %s" % (len(adcs))
112 | print "short temptable[NUMTEMPS][2] = {"
113 |
114 | counter = 0
115 | for adc in adcs:
116 | counter = counter +1
117 | if counter == len(adcs):
118 | print " {%s, %s}" % (adc, int(t.temp(adc)))
119 | else:
120 | print " {%s, %s}," % (adc, int(t.temp(adc)))
121 | print "};"
122 |
123 | def usage():
124 | print __doc__
125 |
126 | if __name__ == "__main__":
127 | main(sys.argv[1:])
128 |
--------------------------------------------------------------------------------
/README:
--------------------------------------------------------------------------------
1 | The leading developers of Sprinter are currently Kliment, caru and midopple, though many others contribute with their patches.
2 |
3 | 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.
4 |
5 | This work is licensed under the GNU GPL v3 or (at the user's discretion) any later version.
6 |
7 | It is based on Tonokips's firmware, which was licensed under GPL v2 or later.
8 |
9 | WARNING: This version (April 19th, 2011) fixes a bug that caused speeds to be lower than what
10 | set in GCODE. So before attempting any print, you will have to check all
11 | your axis max speed, including the extruder retract speed. Not following
12 | this guidelines can seriously damage your printer.
13 |
14 | 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:
15 | #include "ThermistorTable.h"
16 |
17 | 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:
18 | #define BNUMTEMPS NUMPTEMPS
19 | #define bedtemptable temptable
20 | Then add a line pointing to your second thermistor table, for example:
21 | #include "BedThermistorTable.h"
22 | 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.
23 |
24 | There are examples of all these configurations in the configuration.h file. Please look at them before you change anything.
25 |
26 |
27 | Complete beginners guide
28 | =======================
29 |
30 | From a fresh Ubuntu install how to update the firmware of your Prusa Mendel ?
31 | (the specifics are for the Prusa Mendel built at the Bath RepRap masterclass.
32 | This version uses the http://reprap.org/wiki/Sanguinololu.
33 | Some details may not fit your hardware, be sure to check what you are doing)
34 |
35 | 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
36 |
37 | Software installation
38 | ----------------------
39 |
40 | 1. Install the required packages (gcc-avr, avr-libc, etc.)
41 | sudo apt-get install arduino-core
42 |
43 | 2. Get the arduino software version 0023, uncompress it in a directory.
44 | Arduino software v1 has not been tested much, but is known to work with some boards.
45 | http://www.arduino.cc/en/Main/Software
46 |
47 | 3. Get the sanguino software, version 0023
48 | http://sanguino.cc/softwareforlinux
49 |
50 | follow the sanguino's readme so that your arduino hardware folder looks like
51 | arduino-0023/hardware/arduino
52 | arduino-0023/hardware/sanguino
53 | arduino-0023/hardware/tools
54 |
55 | 4. Clone the Sprinter git repository.
56 | git clone https://github.com/kliment/Sprinter.git
57 | Optionally, switch to the desired branch
58 | git branch -a
59 | git checkout THE_BRANCH_YOU_WANT
60 |
61 | Firmware compilation and upload
62 | -------------------------------
63 |
64 | 5. Edit INSTALL_DIR inside Sprinter/Makefile (do not mind the default reference to arduino 0022)
65 |
66 | 6. Run make. If everything goes well Sprinter/applet/Sprinter.cpp should have been created.
67 | You can safely ignore the error message mentioning arduino-0023/hardware/arduino/cores/arduino/WString.o
68 |
69 | 7. Connect your Sanguinololu to your computer
70 | http://reprap.org/wiki/Sanguinololu
71 |
72 | 8. Launch arduino-0023/arduino, open Sprinter/Sprinter.pde
73 |
74 | 9. Go to Tools -> Serial Port, and select the relevant option
75 |
76 | 10. Go to Tools -> Board, select Sanguino
77 |
78 | 11. Go to the Configuration.h file and edit the following lines:
79 | #define MOTHERBOARD 62
80 | 62 indicates Sanguino 1.2 or superior
81 |
82 | float axis_steps_per_unit[]
83 |
84 | set values that match your hardware. For the special cast gears of the Bath Masterclass Prusa Mendel, these values are
85 | float axis_steps_per_unit[] = {91.42857, 91.42857, 3200/1.25,700};
86 |
87 | also for the mentioned hardware setup
88 | const bool ENDSTOPS_INVERTING = false; //set to true to invert the logic of the endstops
89 | // false because the switch SIG signal is linked to the ground
90 | // "no touch == closed circuit == SIG connects to GND"
91 | // see http://reprap.org/wiki/Sanguinololu#Endstops
92 |
93 | 12. Click on the "play" button to compile. If everything goes well you should see a "Binary sketch size: " message.
94 |
95 | 13. Click on "the arrow going to the right" button to upload (you had done steps 7,8,9 before, right ?).
96 | If everything goes well you should see the message "Done uploading".
97 |
98 | if GEN7 with 20 Mhz is in use set the Fuses for Bootloader to
99 | lfuse= 0xF7 hfuse = 0xD4 efuse = FD
100 | Brownout must be 2,7 V
101 |
102 | Congratulations, you have just upgraded the firmware of your RepRap !
103 |
104 | You can use pronterface.py to do some manual verifications by moving the printer's tip along
105 | the axes and verifying that the physical displacements match the ones indicated on the interface.
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
--------------------------------------------------------------------------------
/Sprinter/arc_func.cpp:
--------------------------------------------------------------------------------
1 | /*
2 | arc_func.c - high level interface for issuing motion commands
3 | Part of Grbl
4 |
5 | Copyright (c) 2009-2011 Simen Svale Skogsrud
6 | Copyright (c) 2011 Sungeun K. Jeon
7 |
8 | Grbl is free software: you can redistribute it and/or modify
9 | it under the terms of the GNU General Public License as published by
10 | the Free Software Foundation, either version 3 of the License, or
11 | (at your option) any later version.
12 |
13 | Grbl is distributed in the hope that it will be useful,
14 | but WITHOUT ANY WARRANTY; without even the implied warranty of
15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16 | GNU General Public License for more details.
17 |
18 | You should have received a copy of the GNU General Public License
19 | along with Grbl. If not, see .
20 | */
21 |
22 | #include
23 | #include
24 |
25 | #include "Configuration.h"
26 | #include "Sprinter.h"
27 |
28 | #ifdef USE_ARC_FUNCTION
29 | // The arc is approximated by generating a huge number of tiny, linear segments. The length of each
30 | // segment is configured in settings.mm_per_arc_segment.
31 | void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8_t axis_1,
32 | uint8_t axis_linear, float feed_rate, float radius, uint8_t isclockwise)
33 | {
34 | // int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled();
35 | // plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc
36 | float center_axis0 = position[axis_0] + offset[axis_0];
37 | float center_axis1 = position[axis_1] + offset[axis_1];
38 | float linear_travel = target[axis_linear] - position[axis_linear];
39 | float extruder_travel = target[E_AXIS] - position[E_AXIS];
40 | float r_axis0 = -offset[axis_0]; // Radius vector from center to current location
41 | float r_axis1 = -offset[axis_1];
42 | float rt_axis0 = target[axis_0] - center_axis0;
43 | float rt_axis1 = target[axis_1] - center_axis1;
44 |
45 | // CCW angle between position and target from circle center. Only one atan2() trig computation required.
46 | float angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1);
47 | if (angular_travel < 0) { angular_travel += 2*M_PI; }
48 | if (isclockwise) { angular_travel -= 2*M_PI; }
49 |
50 | float millimeters_of_travel = hypot(angular_travel*radius, fabs(linear_travel));
51 | if (millimeters_of_travel < 0.001) { return; }
52 | uint16_t segments = floor(millimeters_of_travel/MM_PER_ARC_SEGMENT);
53 | if(segments == 0) segments = 1;
54 |
55 | /*
56 | // Multiply inverse feed_rate to compensate for the fact that this movement is approximated
57 | // by a number of discrete segments. The inverse feed_rate should be correct for the sum of
58 | // all segments.
59 | if (invert_feed_rate) { feed_rate *= segments; }
60 | */
61 | float theta_per_segment = angular_travel/segments;
62 | float linear_per_segment = linear_travel/segments;
63 | float extruder_per_segment = extruder_travel/segments;
64 |
65 | /* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
66 | and phi is the angle of rotation. Based on the solution approach by Jens Geisler.
67 | r_T = [cos(phi) -sin(phi);
68 | sin(phi) cos(phi] * r ;
69 |
70 | For arc generation, the center of the circle is the axis of rotation and the radius vector is
71 | defined from the circle center to the initial position. Each line segment is formed by successive
72 | vector rotations. This requires only two cos() and sin() computations to form the rotation
73 | matrix for the duration of the entire arc. Error may accumulate from numerical round-off, since
74 | all double numbers are single precision on the Arduino. (True double precision will not have
75 | round off issues for CNC applications.) Single precision error can accumulate to be greater than
76 | tool precision in some cases. Therefore, arc path correction is implemented.
77 |
78 | Small angle approximation may be used to reduce computation overhead further. This approximation
79 | holds for everything, but very small circles and large mm_per_arc_segment values. In other words,
80 | theta_per_segment would need to be greater than 0.1 rad and N_ARC_CORRECTION would need to be large
81 | to cause an appreciable drift error. N_ARC_CORRECTION~=25 is more than small enough to correct for
82 | numerical drift error. N_ARC_CORRECTION may be on the order a hundred(s) before error becomes an
83 | issue for CNC machines with the single precision Arduino calculations.
84 |
85 | This approximation also allows mc_arc to immediately insert a line segment into the planner
86 | without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied
87 | a correction, the planner should have caught up to the lag caused by the initial mc_arc overhead.
88 | This is important when there are successive arc motions.
89 | */
90 | // Vector rotation matrix values
91 | float cos_T = 1-0.5*theta_per_segment*theta_per_segment; // Small angle approximation
92 | float sin_T = theta_per_segment;
93 |
94 | float arc_target[4];
95 | float sin_Ti;
96 | float cos_Ti;
97 | float r_axisi;
98 | uint16_t i;
99 | int8_t count = 0;
100 |
101 | // Initialize the linear axis
102 | arc_target[axis_linear] = position[axis_linear];
103 |
104 | // Initialize the extruder axis
105 | arc_target[E_AXIS] = position[E_AXIS];
106 |
107 | for (i = 1; i.
19 | */
20 | #ifndef SdInfo_h
21 | #define SdInfo_h
22 | #include
23 | // Based on the document:
24 | //
25 | // SD Specifications
26 | // Part 1
27 | // Physical Layer
28 | // Simplified Specification
29 | // Version 2.00
30 | // September 25, 2006
31 | //
32 | // www.sdcard.org/developers/tech/sdcard/pls/Simplified_Physical_Layer_Spec.pdf
33 | //------------------------------------------------------------------------------
34 | // SD card commands
35 | /** GO_IDLE_STATE - init card in spi mode if CS low */
36 | uint8_t const CMD0 = 0X00;
37 | /** SEND_IF_COND - verify SD Memory Card interface operating condition.*/
38 | uint8_t const CMD8 = 0X08;
39 | /** SEND_CSD - read the Card Specific Data (CSD register) */
40 | uint8_t const CMD9 = 0X09;
41 | /** SEND_CID - read the card identification information (CID register) */
42 | uint8_t const CMD10 = 0X0A;
43 | /** SEND_STATUS - read the card status register */
44 | uint8_t const CMD13 = 0X0D;
45 | /** READ_BLOCK - read a single data block from the card */
46 | uint8_t const CMD17 = 0X11;
47 | /** WRITE_BLOCK - write a single data block to the card */
48 | uint8_t const CMD24 = 0X18;
49 | /** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */
50 | uint8_t const CMD25 = 0X19;
51 | /** ERASE_WR_BLK_START - sets the address of the first block to be erased */
52 | uint8_t const CMD32 = 0X20;
53 | /** ERASE_WR_BLK_END - sets the address of the last block of the continuous
54 | range to be erased*/
55 | uint8_t const CMD33 = 0X21;
56 | /** ERASE - erase all previously selected blocks */
57 | uint8_t const CMD38 = 0X26;
58 | /** APP_CMD - escape for application specific command */
59 | uint8_t const CMD55 = 0X37;
60 | /** READ_OCR - read the OCR register of a card */
61 | uint8_t const CMD58 = 0X3A;
62 | /** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be
63 | pre-erased before writing */
64 | uint8_t const ACMD23 = 0X17;
65 | /** SD_SEND_OP_COMD - Sends host capacity support information and
66 | activates the card's initialization process */
67 | uint8_t const ACMD41 = 0X29;
68 | //------------------------------------------------------------------------------
69 | /** status for card in the ready state */
70 | uint8_t const R1_READY_STATE = 0X00;
71 | /** status for card in the idle state */
72 | uint8_t const R1_IDLE_STATE = 0X01;
73 | /** status bit for illegal command */
74 | uint8_t const R1_ILLEGAL_COMMAND = 0X04;
75 | /** start data token for read or write single block*/
76 | uint8_t const DATA_START_BLOCK = 0XFE;
77 | /** stop token for write multiple blocks*/
78 | uint8_t const STOP_TRAN_TOKEN = 0XFD;
79 | /** start data token for write multiple blocks*/
80 | uint8_t const WRITE_MULTIPLE_TOKEN = 0XFC;
81 | /** mask for data response tokens after a write block operation */
82 | uint8_t const DATA_RES_MASK = 0X1F;
83 | /** write data accepted token */
84 | uint8_t const DATA_RES_ACCEPTED = 0X05;
85 | //------------------------------------------------------------------------------
86 | typedef struct CID {
87 | // byte 0
88 | uint8_t mid; // Manufacturer ID
89 | // byte 1-2
90 | char oid[2]; // OEM/Application ID
91 | // byte 3-7
92 | char pnm[5]; // Product name
93 | // byte 8
94 | unsigned prv_m : 4; // Product revision n.m
95 | unsigned prv_n : 4;
96 | // byte 9-12
97 | uint32_t psn; // Product serial number
98 | // byte 13
99 | unsigned mdt_year_high : 4; // Manufacturing date
100 | unsigned reserved : 4;
101 | // byte 14
102 | unsigned mdt_month : 4;
103 | unsigned mdt_year_low :4;
104 | // byte 15
105 | unsigned always1 : 1;
106 | unsigned crc : 7;
107 | }cid_t;
108 | //------------------------------------------------------------------------------
109 | // CSD for version 1.00 cards
110 | typedef struct CSDV1 {
111 | // byte 0
112 | unsigned reserved1 : 6;
113 | unsigned csd_ver : 2;
114 | // byte 1
115 | uint8_t taac;
116 | // byte 2
117 | uint8_t nsac;
118 | // byte 3
119 | uint8_t tran_speed;
120 | // byte 4
121 | uint8_t ccc_high;
122 | // byte 5
123 | unsigned read_bl_len : 4;
124 | unsigned ccc_low : 4;
125 | // byte 6
126 | unsigned c_size_high : 2;
127 | unsigned reserved2 : 2;
128 | unsigned dsr_imp : 1;
129 | unsigned read_blk_misalign :1;
130 | unsigned write_blk_misalign : 1;
131 | unsigned read_bl_partial : 1;
132 | // byte 7
133 | uint8_t c_size_mid;
134 | // byte 8
135 | unsigned vdd_r_curr_max : 3;
136 | unsigned vdd_r_curr_min : 3;
137 | unsigned c_size_low :2;
138 | // byte 9
139 | unsigned c_size_mult_high : 2;
140 | unsigned vdd_w_cur_max : 3;
141 | unsigned vdd_w_curr_min : 3;
142 | // byte 10
143 | unsigned sector_size_high : 6;
144 | unsigned erase_blk_en : 1;
145 | unsigned c_size_mult_low : 1;
146 | // byte 11
147 | unsigned wp_grp_size : 7;
148 | unsigned sector_size_low : 1;
149 | // byte 12
150 | unsigned write_bl_len_high : 2;
151 | unsigned r2w_factor : 3;
152 | unsigned reserved3 : 2;
153 | unsigned wp_grp_enable : 1;
154 | // byte 13
155 | unsigned reserved4 : 5;
156 | unsigned write_partial : 1;
157 | unsigned write_bl_len_low : 2;
158 | // byte 14
159 | unsigned reserved5: 2;
160 | unsigned file_format : 2;
161 | unsigned tmp_write_protect : 1;
162 | unsigned perm_write_protect : 1;
163 | unsigned copy : 1;
164 | unsigned file_format_grp : 1;
165 | // byte 15
166 | unsigned always1 : 1;
167 | unsigned crc : 7;
168 | }csd1_t;
169 | //------------------------------------------------------------------------------
170 | // CSD for version 2.00 cards
171 | typedef struct CSDV2 {
172 | // byte 0
173 | unsigned reserved1 : 6;
174 | unsigned csd_ver : 2;
175 | // byte 1
176 | uint8_t taac;
177 | // byte 2
178 | uint8_t nsac;
179 | // byte 3
180 | uint8_t tran_speed;
181 | // byte 4
182 | uint8_t ccc_high;
183 | // byte 5
184 | unsigned read_bl_len : 4;
185 | unsigned ccc_low : 4;
186 | // byte 6
187 | unsigned reserved2 : 4;
188 | unsigned dsr_imp : 1;
189 | unsigned read_blk_misalign :1;
190 | unsigned write_blk_misalign : 1;
191 | unsigned read_bl_partial : 1;
192 | // byte 7
193 | unsigned reserved3 : 2;
194 | unsigned c_size_high : 6;
195 | // byte 8
196 | uint8_t c_size_mid;
197 | // byte 9
198 | uint8_t c_size_low;
199 | // byte 10
200 | unsigned sector_size_high : 6;
201 | unsigned erase_blk_en : 1;
202 | unsigned reserved4 : 1;
203 | // byte 11
204 | unsigned wp_grp_size : 7;
205 | unsigned sector_size_low : 1;
206 | // byte 12
207 | unsigned write_bl_len_high : 2;
208 | unsigned r2w_factor : 3;
209 | unsigned reserved5 : 2;
210 | unsigned wp_grp_enable : 1;
211 | // byte 13
212 | unsigned reserved6 : 5;
213 | unsigned write_partial : 1;
214 | unsigned write_bl_len_low : 2;
215 | // byte 14
216 | unsigned reserved7: 2;
217 | unsigned file_format : 2;
218 | unsigned tmp_write_protect : 1;
219 | unsigned perm_write_protect : 1;
220 | unsigned copy : 1;
221 | unsigned file_format_grp : 1;
222 | // byte 15
223 | unsigned always1 : 1;
224 | unsigned crc : 7;
225 | }csd2_t;
226 | //------------------------------------------------------------------------------
227 | // union of old and new style CSD register
228 | union csd_t {
229 | csd1_t v1;
230 | csd2_t v2;
231 | };
232 | #endif // SdInfo_h
233 |
--------------------------------------------------------------------------------
/Sprinter/store_eeprom.cpp:
--------------------------------------------------------------------------------
1 | /*
2 | EEPROM routines to save Sprinter Settings
3 |
4 | This program is free software: you can redistribute it and/or modify
5 | it under the terms of the GNU General Public License as published by
6 | the Free Software Foundation, either version 3 of the License, or
7 | (at your option) any later version.
8 |
9 | This program is distributed in the hope that it will be useful,
10 | but WITHOUT ANY WARRANTY; without even the implied warranty of
11 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 | GNU General Public License for more details.
13 |
14 | You should have received a copy of the GNU General Public License
15 | along with this program. If not, see .
16 | */
17 |
18 | #include
19 | #include
20 | #include
21 |
22 | #include "Sprinter.h"
23 | #include "store_eeprom.h"
24 | #include "Configuration.h"
25 |
26 | #ifdef PIDTEMP
27 | extern unsigned int PID_Kp, PID_Ki, PID_Kd;
28 | #endif
29 |
30 |
31 | #ifdef USE_EEPROM_SETTINGS
32 |
33 | //======================================================================================
34 | //========================= Read / Write EEPROM =======================================
35 | template int EEPROM_write_setting(int address, const T& value)
36 | {
37 | const byte* p = (const byte*)(const void*)&value;
38 | int i;
39 | for (i = 0; i < (int)sizeof(value); i++)
40 | eeprom_write_byte((unsigned char *)address++, *p++);
41 | return i;
42 | }
43 |
44 | template int EEPROM_read_setting(int address, T& value)
45 | {
46 | byte* p = (byte*)(void*)&value;
47 | int i;
48 | for (i = 0; i < (int)sizeof(value); i++)
49 | *p++ = eeprom_read_byte((unsigned char *)address++);
50 | return i;
51 | }
52 | //======================================================================================
53 |
54 |
55 | void EEPROM_StoreSettings()
56 | {
57 | char ver[4]= "000";
58 | EEPROM_write_setting(EEPROM_OFFSET, ver); // invalidate data first
59 | EEPROM_write_setting(axis_steps_per_unit_address, axis_steps_per_unit);
60 | EEPROM_write_setting(max_feedrate_address, max_feedrate);
61 | EEPROM_write_setting(max_acceleration_units_per_sq_second_address, max_acceleration_units_per_sq_second);
62 | EEPROM_write_setting(move_acceleration_address, move_acceleration);
63 | EEPROM_write_setting(retract_acceleration_address, retract_acceleration);
64 | EEPROM_write_setting(minimumfeedrate_address, minimumfeedrate);
65 | EEPROM_write_setting(mintravelfeedrate_address, mintravelfeedrate);
66 | EEPROM_write_setting(min_seg_time_address, min_seg_time); //Min Segment Time, not used yet
67 | EEPROM_write_setting(max_xy_jerk_address, max_xy_jerk);
68 | EEPROM_write_setting(max_z_jerk_address, max_z_jerk);
69 | EEPROM_write_setting(max_e_jerk_address, max_e_jerk);
70 |
71 | //PID Settings
72 | #ifdef PIDTEMP
73 | EEPROM_write_setting(Kp_address, PID_Kp); //Kp
74 | EEPROM_write_setting(Ki_address, PID_Ki); //Ki
75 | EEPROM_write_setting(Kd_address, PID_Kd); //Kd
76 | #else
77 | EEPROM_write_setting(Kp_address, 2048); //Kp
78 | EEPROM_write_setting(Ki_address, 32); //Ki
79 | EEPROM_write_setting(Kd_address, 2048); //Kd
80 | #endif
81 |
82 |
83 | char ver2[4]=EEPROM_VERSION;
84 | EEPROM_write_setting(EEPROM_OFFSET, ver2); // validate data
85 | showString(PSTR("Settings Stored\r\n"));
86 |
87 | }
88 |
89 |
90 | void EEPROM_printSettings()
91 | {
92 | #ifdef PRINT_EEPROM_SETTING
93 | showString(PSTR("Steps per unit:\r\n"));
94 | showString(PSTR(" M92 X"));
95 | Serial.print(axis_steps_per_unit[0]);
96 | showString(PSTR(" Y"));
97 | Serial.print(axis_steps_per_unit[1]);
98 | showString(PSTR(" Z"));
99 | Serial.print(axis_steps_per_unit[2]);
100 | showString(PSTR(" E"));
101 | Serial.println(axis_steps_per_unit[3]);
102 |
103 | showString(PSTR("Maximum feedrates (mm/s):\r\n"));
104 | showString(PSTR(" M202 X"));
105 | Serial.print(max_feedrate[0]);
106 | showString(PSTR(" Y"));
107 | Serial.print(max_feedrate[1]);
108 | showString(PSTR(" Z"));
109 | Serial.print(max_feedrate[2]);
110 | showString(PSTR(" E"));
111 | Serial.println(max_feedrate[3]);
112 |
113 | showString(PSTR("Maximum Acceleration (mm/s2):\r\n"));
114 | showString(PSTR(" M201 X"));
115 | Serial.print(max_acceleration_units_per_sq_second[0] );
116 | showString(PSTR(" Y"));
117 | Serial.print(max_acceleration_units_per_sq_second[1] );
118 | showString(PSTR(" Z"));
119 | Serial.print(max_acceleration_units_per_sq_second[2] );
120 | showString(PSTR(" E"));
121 | Serial.println(max_acceleration_units_per_sq_second[3]);
122 |
123 | showString(PSTR("Acceleration: S=acceleration, T=retract acceleration\r\n"));
124 | showString(PSTR(" M204 S"));
125 | Serial.print(move_acceleration );
126 | showString(PSTR(" T"));
127 | Serial.println(retract_acceleration);
128 |
129 | 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"));
130 |
131 | showString(PSTR(" M205 S"));
132 | Serial.print(minimumfeedrate );
133 | showString(PSTR(" T" ));
134 | Serial.print(mintravelfeedrate );
135 | // showString(PSTR(" B"));
136 | // Serial.print(min_seg_time );
137 | showString(PSTR(" X"));
138 | Serial.print(max_xy_jerk );
139 | showString(PSTR(" Z"));
140 | Serial.print(max_z_jerk);
141 | showString(PSTR(" E"));
142 | Serial.println(max_e_jerk);
143 |
144 |
145 | #ifdef PIDTEMP
146 |
147 | showString(PSTR("PID settings:\r\n"));
148 | showString(PSTR(" M301 P"));
149 | Serial.print(PID_Kp);
150 | showString(PSTR(" I"));
151 | Serial.print(PID_Ki);
152 | showString(PSTR(" D"));
153 | Serial.println(PID_Kd);
154 |
155 | #endif
156 | #endif
157 |
158 | }
159 |
160 |
161 | void EEPROM_RetrieveSettings(bool def, bool printout)
162 | { // if def=true, the default values will be used
163 |
164 | int i=EEPROM_OFFSET;
165 | char stored_ver[4];
166 | char ver[4]=EEPROM_VERSION;
167 |
168 | EEPROM_read_setting(EEPROM_OFFSET,stored_ver); //read stored version
169 | if ((!def)&&(strncmp(ver,stored_ver,3)==0))
170 | { // version number match
171 | EEPROM_read_setting(axis_steps_per_unit_address, axis_steps_per_unit);
172 | EEPROM_read_setting(max_feedrate_address, max_feedrate);
173 | EEPROM_read_setting(max_acceleration_units_per_sq_second_address, max_acceleration_units_per_sq_second);
174 | EEPROM_read_setting(move_acceleration_address, move_acceleration);
175 | EEPROM_read_setting(retract_acceleration_address, retract_acceleration);
176 | EEPROM_read_setting(minimumfeedrate_address, minimumfeedrate);
177 | EEPROM_read_setting(mintravelfeedrate_address, mintravelfeedrate);
178 | EEPROM_read_setting(min_seg_time_address, min_seg_time); //min Segmenttime --> not used yet
179 | EEPROM_read_setting(max_xy_jerk_address, max_xy_jerk);
180 | EEPROM_read_setting(max_z_jerk_address, max_z_jerk);
181 | EEPROM_read_setting(max_e_jerk_address, max_e_jerk);
182 |
183 | #ifdef PIDTEMP
184 | EEPROM_read_setting(Kp_address, PID_Kp);
185 | EEPROM_read_setting(Ki_address, PID_Ki);
186 | EEPROM_read_setting(Kd_address, PID_Kd);
187 | #endif
188 |
189 | showString(PSTR("Stored settings retreived\r\n"));
190 | }
191 | else
192 | {
193 |
194 | float tmp1[]=_AXIS_STEP_PER_UNIT;
195 | float tmp2[]=_MAX_FEEDRATE;
196 | long tmp3[]=_MAX_ACCELERATION_UNITS_PER_SQ_SECOND;
197 | for (short i=0;i<4;i++)
198 | {
199 | axis_steps_per_unit[i]=tmp1[i];
200 | max_feedrate[i]=tmp2[i];
201 | max_acceleration_units_per_sq_second[i]=tmp3[i];
202 | }
203 | move_acceleration=_ACCELERATION;
204 | retract_acceleration=_RETRACT_ACCELERATION;
205 | minimumfeedrate=DEFAULT_MINIMUMFEEDRATE;
206 | mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
207 | max_xy_jerk=_MAX_XY_JERK;
208 | max_z_jerk=_MAX_Z_JERK;
209 | max_e_jerk=_MAX_E_JERK;
210 | min_seg_time=_MIN_SEG_TIME;
211 |
212 | #ifdef PIDTEMP
213 | PID_Kp = PID_PGAIN;
214 | PID_Ki = PID_IGAIN;
215 | PID_Kd = PID_DGAIN;
216 | #endif
217 |
218 | showString(PSTR("Using Default settings\r\n"));
219 | }
220 |
221 | if(printout)
222 | {
223 | EEPROM_printSettings();
224 | }
225 | }
226 |
227 | #endif
228 |
--------------------------------------------------------------------------------
/Sprinter/Makefile:
--------------------------------------------------------------------------------
1 | # Sprinter Arduino Project Makefile
2 | #
3 | # Makefile Based on:
4 | # Arduino 0011 Makefile
5 | # Arduino adaptation by mellis, eighthave, oli.keller
6 | #
7 | # This has been tested with Arduino 0022.
8 | #
9 | # This makefile allows you to build sketches from the command line
10 | # without the Arduino environment (or Java).
11 | #
12 | # Detailed instructions for using the makefile:
13 | #
14 | # 1. Modify the line containg "INSTALL_DIR" to point to the directory that
15 | # contains the Arduino installation (for example, under Mac OS X, this
16 | # might be /Applications/arduino-0012).
17 | #
18 | # 2. Modify the line containing "PORT" to refer to the filename
19 | # representing the USB or serial connection to your Arduino board
20 | # (e.g. PORT = /dev/tty.USB0). If the exact name of this file
21 | # changes, you can use * as a wildcard (e.g. PORT = /dev/tty.usb*).
22 | #
23 | # 3. Set the line containing "MCU" to match your board's processor.
24 | # Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth
25 | # or Diecimila have the atmega168. If you're using a LilyPad Arduino,
26 | # change F_CPU to 8000000.
27 | #
28 | # 4. Type "make" and press enter to compile/verify your program.
29 | #
30 | # 5. Type "make upload", reset your Arduino board, and press enter to
31 | # upload your program to the Arduino board.
32 | #
33 | # $Id$
34 |
35 | TARGET = $(notdir $(CURDIR))
36 | INSTALL_DIR = ../../arduino22/arduino-0022/
37 | UPLOAD_RATE = 38400
38 | AVRDUDE_PROGRAMMER = stk500v1
39 | PORT = /dev/ttyUSB0
40 | MCU = atmega2560
41 | #For "old" Arduino Mega
42 | #MCU = atmega1280
43 | #For Sanguinololu
44 | #MCU = atmega644p
45 | F_CPU = 16000000
46 |
47 |
48 | ############################################################################
49 | # Below here nothing should be changed...
50 |
51 | ARDUINO = $(INSTALL_DIR)/hardware/arduino/cores/arduino
52 | AVR_TOOLS_PATH = /usr/bin
53 | SRC = $(ARDUINO)/pins_arduino.c $(ARDUINO)/wiring.c \
54 | $(ARDUINO)/wiring_analog.c $(ARDUINO)/wiring_digital.c \
55 | $(ARDUINO)/wiring_pulse.c \
56 | $(ARDUINO)/wiring_shift.c $(ARDUINO)/WInterrupts.c
57 | CXXSRC = $(ARDUINO)/HardwareSerial.cpp $(ARDUINO)/WMath.cpp $(ARDUINO)/WString.cpp\
58 | $(ARDUINO)/Print.cpp ./SdFile.cpp ./SdVolume.cpp ./Sd2Card.cpp ./heater.cpp ./arc_func.cpp ./store_eeprom.cpp
59 | FORMAT = ihex
60 |
61 |
62 | # Name of this Makefile (used for "make depend").
63 | MAKEFILE = Makefile
64 |
65 | # Debugging format.
66 | # Native formats for AVR-GCC's -g are stabs [default], or dwarf-2.
67 | # AVR (extended) COFF requires stabs, plus an avr-objcopy run.
68 | DEBUG = stabs
69 |
70 | OPT = s
71 |
72 | # Place -D or -U options here
73 | CDEFS = -DF_CPU=$(F_CPU)
74 | CXXDEFS = -DF_CPU=$(F_CPU)
75 |
76 | # Place -I options here
77 | CINCS = -I$(ARDUINO)
78 | CXXINCS = -I$(ARDUINO)
79 |
80 | # Compiler flag to set the C Standard level.
81 | # c89 - "ANSI" C
82 | # gnu89 - c89 plus GCC extensions
83 | # c99 - ISO C99 standard (not yet fully implemented)
84 | # gnu99 - c99 plus GCC extensions
85 | #CSTANDARD = -std=gnu99
86 | CDEBUG = -g$(DEBUG)
87 | CWARN = -Wall -Wstrict-prototypes
88 | CTUNING = -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -w -ffunction-sections -fdata-sections -DARDUINO=22
89 | #CEXTRA = -Wa,-adhlns=$(<:.c=.lst)
90 |
91 | CFLAGS = $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CEXTRA) $(CTUNING)
92 | CXXFLAGS = $(CDEFS) $(CINCS) -O$(OPT) -Wall $(CEXTRA) $(CTUNING)
93 | #ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs
94 | LDFLAGS = -lm
95 |
96 |
97 | # Programming support using avrdude. Settings and variables.
98 | AVRDUDE_PORT = $(PORT)
99 | AVRDUDE_WRITE_FLASH = -U flash:w:applet/$(TARGET).hex:i
100 | AVRDUDE_FLAGS = -D -C $(INSTALL_DIR)/hardware/tools/avrdude.conf \
101 | -p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) \
102 | -b $(UPLOAD_RATE)
103 |
104 | # Program settings
105 | CC = $(AVR_TOOLS_PATH)/avr-gcc
106 | CXX = $(AVR_TOOLS_PATH)/avr-g++
107 | OBJCOPY = $(AVR_TOOLS_PATH)/avr-objcopy
108 | OBJDUMP = $(AVR_TOOLS_PATH)/avr-objdump
109 | AR = $(AVR_TOOLS_PATH)/avr-ar
110 | SIZE = $(AVR_TOOLS_PATH)/avr-size
111 | NM = $(AVR_TOOLS_PATH)/avr-nm
112 | AVRDUDE = $(INSTALL_DIR)/hardware/tools/avrdude
113 | REMOVE = rm -f
114 | MV = mv -f
115 |
116 | # Define all object files.
117 | OBJ = $(SRC:.c=.o) $(CXXSRC:.cpp=.o) $(ASRC:.S=.o)
118 |
119 | # Define all listing files.
120 | LST = $(ASRC:.S=.lst) $(CXXSRC:.cpp=.lst) $(SRC:.c=.lst)
121 |
122 | # Combine all necessary flags and optional flags.
123 | # Add target processor to flags.
124 | ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS)
125 | ALL_CXXFLAGS = -mmcu=$(MCU) -I. $(CXXFLAGS)
126 | ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
127 |
128 |
129 | # Default target.
130 | all: build sizeafter
131 |
132 | build: elf hex
133 |
134 | applet/$(TARGET).cpp: $(TARGET).pde
135 | # Here is the "preprocessing".
136 | # It creates a .cpp file based with the same name as the .pde file.
137 | # On top of the new .cpp file comes the WProgram.h header.
138 | # At the end there is a generic main() function attached.
139 | # Then the .cpp file will be compiled. Errors during compile will
140 | # refer to this new, automatically generated, file.
141 | # Not the original .pde file you actually edit...
142 | test -d applet || mkdir applet
143 | echo '#include "WProgram.h"' > applet/$(TARGET).cpp
144 | cat $(TARGET).pde >> applet/$(TARGET).cpp
145 | cat $(ARDUINO)/main.cpp >> applet/$(TARGET).cpp
146 |
147 | elf: applet/$(TARGET).elf
148 | hex: applet/$(TARGET).hex
149 | eep: applet/$(TARGET).eep
150 | lss: applet/$(TARGET).lss
151 | sym: applet/$(TARGET).sym
152 |
153 | # Program the device.
154 | upload: applet/$(TARGET).hex
155 | $(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH)
156 |
157 |
158 | # Display size of file.
159 | HEXSIZE = $(SIZE) --target=$(FORMAT) applet/$(TARGET).hex
160 | ELFSIZE = $(SIZE) applet/$(TARGET).elf
161 | sizebefore:
162 | @if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(HEXSIZE); echo; fi
163 |
164 | sizeafter:
165 | @if [ -f applet/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(HEXSIZE); echo; fi
166 |
167 |
168 | # Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
169 | COFFCONVERT=$(OBJCOPY) --debugging \
170 | --change-section-address .data-0x800000 \
171 | --change-section-address .bss-0x800000 \
172 | --change-section-address .noinit-0x800000 \
173 | --change-section-address .eeprom-0x810000
174 |
175 |
176 | coff: applet/$(TARGET).elf
177 | $(COFFCONVERT) -O coff-avr applet/$(TARGET).elf $(TARGET).cof
178 |
179 |
180 | extcoff: $(TARGET).elf
181 | $(COFFCONVERT) -O coff-ext-avr applet/$(TARGET).elf $(TARGET).cof
182 |
183 |
184 | .SUFFIXES: .elf .hex .eep .lss .sym
185 |
186 | .elf.hex:
187 | $(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
188 |
189 | .elf.eep:
190 | -$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
191 | --change-section-lma .eeprom=0 -O $(FORMAT) $< $@
192 |
193 | # Create extended listing file from ELF output file.
194 | .elf.lss:
195 | $(OBJDUMP) -h -S $< > $@
196 |
197 | # Create a symbol table from ELF output file.
198 | .elf.sym:
199 | $(NM) -n $< > $@
200 |
201 | # Link: create ELF output file from library.
202 | applet/$(TARGET).elf: applet/$(TARGET).cpp applet/core.a
203 | $(CC) $(ALL_CFLAGS) -Wl,--gc-sections -o $@ applet/$(TARGET).cpp -L. applet/core.a $(LDFLAGS)
204 |
205 | applet/core.a: $(OBJ)
206 | @for i in $(OBJ); do echo $(AR) rcs applet/core.a $$i; $(AR) rcs applet/core.a $$i; done
207 |
208 |
209 |
210 | # Compile: create object files from C++ source files.
211 | .cpp.o:
212 | $(CXX) -c $(ALL_CXXFLAGS) $< -o $@
213 |
214 | # Compile: create object files from C source files.
215 | .c.o:
216 | $(CC) -c $(ALL_CFLAGS) $< -o $@
217 |
218 |
219 | # Compile: create assembler files from C source files.
220 | .c.s:
221 | $(CC) -S $(ALL_CFLAGS) $< -o $@
222 |
223 |
224 | # Assemble: create object files from assembler source files.
225 | .S.o:
226 | $(CC) -c $(ALL_ASFLAGS) $< -o $@
227 |
228 |
229 |
230 | # Target: clean project.
231 | clean:
232 | $(REMOVE) applet/$(TARGET).hex applet/$(TARGET).eep applet/$(TARGET).cof applet/$(TARGET).elf \
233 | applet/$(TARGET).map applet/$(TARGET).sym applet/$(TARGET).lss applet/core.a \
234 | $(OBJ) $(LST) $(SRC:.c=.s) $(SRC:.c=.d) $(CXXSRC:.cpp=.s) $(CXXSRC:.cpp=.d)
235 |
236 | depend:
237 | if grep '^# DO NOT DELETE' $(MAKEFILE) >/dev/null; \
238 | then \
239 | sed -e '/^# DO NOT DELETE/,$$d' $(MAKEFILE) > \
240 | $(MAKEFILE).$$$$ && \
241 | $(MV) $(MAKEFILE).$$$$ $(MAKEFILE); \
242 | fi
243 | echo '# DO NOT DELETE THIS LINE -- make depend depends on it.' \
244 | >> $(MAKEFILE); \
245 | $(CC) -M -mmcu=$(MCU) $(CDEFS) $(CINCS) $(SRC) $(ASRC) >> $(MAKEFILE)
246 |
247 | .PHONY: all build elf hex eep lss sym program coff extcoff clean depend sizebefore sizeafter
248 |
--------------------------------------------------------------------------------
/Sprinter/SdFatmainpage.h:
--------------------------------------------------------------------------------
1 | /* Arduino SdFat Library
2 | * Copyright (C) 2009 by William Greiman
3 | *
4 | * This file is part of the Arduino SdFat Library
5 | *
6 | * This Library is free software: you can redistribute it and/or modify
7 | * it under the terms of the GNU General Public License as published by
8 | * the Free Software Foundation, either version 3 of the License, or
9 | * (at your option) any later version.
10 | *
11 | * This Library is distributed in the hope that it will be useful,
12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | * GNU General Public License for more details.
15 | *
16 | * You should have received a copy of the GNU General Public License
17 | * along with the Arduino SdFat Library. If not, see
18 | * .
19 | */
20 |
21 | /**
22 | \mainpage Arduino SdFat Library
23 | Copyright © 2009 by William Greiman
24 |
25 |
26 | \section Intro Introduction
27 | The Arduino SdFat Library is a minimal implementation of FAT16 and FAT32
28 | file systems on SD flash memory cards. Standard SD and high capacity
29 | SDHC cards are supported.
30 |
31 | The SdFat only supports short 8.3 names.
32 |
33 | The main classes in SdFat are Sd2Card, SdVolume, and SdFile.
34 |
35 | The Sd2Card class supports access to standard SD cards and SDHC cards. Most
36 | applications will only need to call the Sd2Card::init() member function.
37 |
38 | The SdVolume class supports FAT16 and FAT32 partitions. Most applications
39 | will only need to call the SdVolume::init() member function.
40 |
41 | The SdFile class provides file access functions such as open(), read(),
42 | remove(), write(), close() and sync(). This class supports access to the root
43 | directory and subdirectories.
44 |
45 | A number of example are provided in the SdFat/examples folder. These were
46 | developed to test SdFat and illustrate its use.
47 |
48 | SdFat was developed for high speed data recording. SdFat was used to implement
49 | an audio record/play class, WaveRP, for the Adafruit Wave Shield. This
50 | application uses special Sd2Card calls to write to contiguous files in raw mode.
51 | These functions reduce write latency so that audio can be recorded with the
52 | small amount of RAM in the Arduino.
53 |
54 | \section SDcard SD\SDHC Cards
55 |
56 | Arduinos access SD cards using the cards SPI protocol. PCs, Macs, and
57 | most consumer devices use the 4-bit parallel SD protocol. A card that
58 | functions well on A PC or Mac may not work well on the Arduino.
59 |
60 | Most cards have good SPI read performance but cards vary widely in SPI
61 | write performance. Write performance is limited by how efficiently the
62 | card manages internal erase/remapping operations. The Arduino cannot
63 | optimize writes to reduce erase operations because of its limit RAM.
64 |
65 | SanDisk cards generally have good write performance. They seem to have
66 | more internal RAM buffering than other cards and therefore can limit
67 | the number of flash erase operations that the Arduino forces due to its
68 | limited RAM.
69 |
70 | \section Hardware Hardware Configuration
71 |
72 | SdFat was developed using an
73 | Adafruit Industries
74 | Wave Shield.
75 |
76 | The hardware interface to the SD card should not use a resistor based level
77 | shifter. SdFat sets the SPI bus frequency to 8 MHz which results in signal
78 | rise times that are too slow for the edge detectors in many newer SD card
79 | controllers when resistor voltage dividers are used.
80 |
81 | The 5 to 3.3 V level shifter for 5 V Arduinos should be IC based like the
82 | 74HC4050N based circuit shown in the file SdLevel.png. The Adafruit Wave Shield
83 | uses a 74AHC125N. Gravitech sells SD and MicroSD Card Adapters based on the
84 | 74LCX245.
85 |
86 | If you are using a resistor based level shifter and are having problems try
87 | setting the SPI bus frequency to 4 MHz. This can be done by using
88 | card.init(SPI_HALF_SPEED) to initialize the SD card.
89 |
90 | \section comment Bugs and Comments
91 |
92 | If you wish to report bugs or have comments, send email to fat16lib@sbcglobal.net.
93 |
94 | \section SdFatClass SdFat Usage
95 |
96 | SdFat uses a slightly restricted form of short names.
97 | Only printable ASCII characters are supported. No characters with code point
98 | values greater than 127 are allowed. Space is not allowed even though space
99 | was allowed in the API of early versions of DOS.
100 |
101 | Short names are limited to 8 characters followed by an optional period (.)
102 | and extension of up to 3 characters. The characters may be any combination
103 | of letters and digits. The following special characters are also allowed:
104 |
105 | $ % ' - _ @ ~ ` ! ( ) { } ^ # &
106 |
107 | Short names are always converted to upper case and their original case
108 | value is lost.
109 |
110 | \note
111 | The Arduino Print class uses character
112 | at a time writes so it was necessary to use a \link SdFile::sync() sync() \endlink
113 | function to control when data is written to the SD card.
114 |
115 | \par
116 | An application which writes to a file using \link Print::print() print()\endlink,
117 | \link Print::println() println() \endlink
118 | or \link SdFile::write write() \endlink must call \link SdFile::sync() sync() \endlink
119 | at the appropriate time to force data and directory information to be written
120 | to the SD Card. Data and directory information are also written to the SD card
121 | when \link SdFile::close() close() \endlink is called.
122 |
123 | \par
124 | Applications must use care calling \link SdFile::sync() sync() \endlink
125 | since 2048 bytes of I/O is required to update file and
126 | directory information. This includes writing the current data block, reading
127 | the block that contains the directory entry for update, writing the directory
128 | block back and reading back the current data block.
129 |
130 | It is possible to open a file with two or more instances of SdFile. A file may
131 | be corrupted if data is written to the file by more than one instance of SdFile.
132 |
133 | \section HowTo How to format SD Cards as FAT Volumes
134 |
135 | You should use a freshly formatted SD card for best performance. FAT
136 | file systems become slower if many files have been created and deleted.
137 | This is because the directory entry for a deleted file is marked as deleted,
138 | but is not deleted. When a new file is created, these entries must be scanned
139 | before creating the file, a flaw in the FAT design. Also files can become
140 | fragmented which causes reads and writes to be slower.
141 |
142 | Microsoft operating systems support removable media formatted with a
143 | Master Boot Record, MBR, or formatted as a super floppy with a FAT Boot Sector
144 | in block zero.
145 |
146 | Microsoft operating systems expect MBR formatted removable media
147 | to have only one partition. The first partition should be used.
148 |
149 | Microsoft operating systems do not support partitioning SD flash cards.
150 | If you erase an SD card with a program like KillDisk, Most versions of
151 | Windows will format the card as a super floppy.
152 |
153 | The best way to restore an SD card's format is to use SDFormatter
154 | which can be downloaded from:
155 |
156 | http://www.sdcard.org/consumers/formatter/
157 |
158 | SDFormatter aligns flash erase boundaries with file
159 | system structures which reduces write latency and file system overhead.
160 |
161 | SDFormatter does not have an option for FAT type so it may format
162 | small cards as FAT12.
163 |
164 | After the MBR is restored by SDFormatter you may need to reformat small
165 | cards that have been formatted FAT12 to force the volume type to be FAT16.
166 |
167 | If you reformat the SD card with an OS utility, choose a cluster size that
168 | will result in:
169 |
170 | 4084 < CountOfClusters && CountOfClusters < 65525
171 |
172 | The volume will then be FAT16.
173 |
174 | If you are formatting an SD card on OS X or Linux, be sure to use the first
175 | partition. Format this partition with a cluster count in above range.
176 |
177 | \section References References
178 |
179 | Adafruit Industries:
180 |
181 | http://www.adafruit.com/
182 |
183 | http://www.ladyada.net/make/waveshield/
184 |
185 | The Arduino site:
186 |
187 | http://www.arduino.cc/
188 |
189 | For more information about FAT file systems see:
190 |
191 | http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
192 |
193 | For information about using SD cards as SPI devices see:
194 |
195 | http://www.sdcard.org/developers/tech/sdcard/pls/Simplified_Physical_Layer_Spec.pdf
196 |
197 | The ATmega328 datasheet:
198 |
199 | http://www.atmel.com/dyn/resources/prod_documents/doc8161.pdf
200 |
201 |
202 | */
203 |
--------------------------------------------------------------------------------
/Sprinter/thermistortables.h:
--------------------------------------------------------------------------------
1 | #ifndef THERMISTORTABLES_H_
2 | #define THERMISTORTABLES_H_
3 |
4 | #if (THERMISTORHEATER == 1) || (THERMISTORBED == 1) //100k bed thermistor
5 |
6 |
7 | #define NUMTEMPS_1 61
8 | const short temptable_1[NUMTEMPS_1][2] = {
9 | { 23 , 300 },
10 | { 25 , 295 },
11 | { 27 , 290 },
12 | { 28 , 285 },
13 | { 31 , 280 },
14 | { 33 , 275 },
15 | { 35 , 270 },
16 | { 38 , 265 },
17 | { 41 , 260 },
18 | { 44 , 255 },
19 | { 48 , 250 },
20 | { 52 , 245 },
21 | { 56 , 240 },
22 | { 61 , 235 },
23 | { 66 , 230 },
24 | { 71 , 225 },
25 | { 78 , 220 },
26 | { 84 , 215 },
27 | { 92 , 210 },
28 | { 100 , 205 },
29 | { 109 , 200 },
30 | { 120 , 195 },
31 | { 131 , 190 },
32 | { 143 , 185 },
33 | { 156 , 180 },
34 | { 171 , 175 },
35 | { 187 , 170 },
36 | { 205 , 165 },
37 | { 224 , 160 },
38 | { 245 , 155 },
39 | { 268 , 150 },
40 | { 293 , 145 },
41 | { 320 , 140 },
42 | { 348 , 135 },
43 | { 379 , 130 },
44 | { 411 , 125 },
45 | { 445 , 120 },
46 | { 480 , 115 },
47 | { 516 , 110 },
48 | { 553 , 105 },
49 | { 591 , 100 },
50 | { 628 , 95 },
51 | { 665 , 90 },
52 | { 702 , 85 },
53 | { 737 , 80 },
54 | { 770 , 75 },
55 | { 801 , 70 },
56 | { 830 , 65 },
57 | { 857 , 60 },
58 | { 881 , 55 },
59 | { 903 , 50 },
60 | { 922 , 45 },
61 | { 939 , 40 },
62 | { 954 , 35 },
63 | { 966 , 30 },
64 | { 977 , 25 },
65 | { 985 , 20 },
66 | { 993 , 15 },
67 | { 999 , 10 },
68 | { 1004 , 5 },
69 | { 1008 , 0 } //safety
70 | };
71 | #endif
72 | #if (THERMISTORHEATER == 2) || (THERMISTORBED == 2) //200k bed thermistor verified by arcol
73 | #define NUMTEMPS_2 64
74 | const short temptable_2[NUMTEMPS_2][2] = {
75 | { 16, 315},
76 | { 17, 310},
77 | { 18, 305},
78 | { 19, 300},
79 | { 20, 295},
80 | { 21, 290},
81 | { 22, 285},
82 | { 23, 280},
83 | { 24, 275},
84 | { 25, 270},
85 | { 29, 265},
86 | { 30, 260},
87 | { 35, 255},
88 | { 40, 250},
89 | { 45, 245},
90 | { 50, 240},
91 | { 55, 235},
92 | { 60, 230},
93 | { 65, 225},
94 | { 70, 220},
95 | { 90, 215},
96 | { 95, 210},
97 | { 103, 205},
98 | { 105, 200},
99 | { 115, 195},
100 | { 130, 190},
101 | { 150, 185},
102 | { 167, 180},
103 | { 190, 175},
104 | { 200, 170},
105 | { 230, 165},
106 | { 250, 160},
107 | { 270, 155},
108 | { 300, 150},
109 | { 330, 145},
110 | { 360, 140},
111 | { 380, 135},
112 | { 408, 130},
113 | { 450, 125},
114 | { 500, 120},
115 | { 530, 115},
116 | { 550, 110},
117 | { 570, 105},
118 | { 595, 100},
119 | { 615, 95},
120 | { 640, 90},
121 | { 665, 85},
122 | { 700, 80},
123 | { 740, 75},
124 | { 780, 70},
125 | { 810, 65},
126 | { 840, 60},
127 | { 880, 55},
128 | { 920, 50},
129 | { 960, 45},
130 | { 980, 40},
131 | { 990, 35},
132 | {1000, 30},
133 | {1005, 25},
134 | {1006, 20},
135 | {1009, 15},
136 | {1010, 10},
137 | {1020, 5},
138 | {1023, 0} //safety
139 | };
140 |
141 | #endif
142 | #if (THERMISTORHEATER == 3) || (THERMISTORBED == 3) //mendel-parts
143 | #define NUMTEMPS_3 28
144 | const short temptable_3[NUMTEMPS_3][2] = {
145 | {1,864},
146 | {21,300},
147 | {25,290},
148 | {29,280},
149 | {33,270},
150 | {39,260},
151 | {46,250},
152 | {54,240},
153 | {64,230},
154 | {75,220},
155 | {90,210},
156 | {107,200},
157 | {128,190},
158 | {154,180},
159 | {184,170},
160 | {221,160},
161 | {265,150},
162 | {316,140},
163 | {375,130},
164 | {441,120},
165 | {513,110},
166 | {588,100},
167 | {734,80},
168 | {856,60},
169 | {938,40},
170 | {986,20},
171 | {1008,0},
172 | {1018,-20}
173 | };
174 |
175 | #endif
176 | #if (THERMISTORHEATER == 4) || (THERMISTORBED == 4) //10k thermistor
177 |
178 | #define NUMTEMPS_4 20
179 | const short temptable_4[NUMTEMPS_4][2] = {
180 | {1, 430},
181 | {54, 137},
182 | {107, 107},
183 | {160, 91},
184 | {213, 80},
185 | {266, 71},
186 | {319, 64},
187 | {372, 57},
188 | {425, 51},
189 | {478, 46},
190 | {531, 41},
191 | {584, 35},
192 | {637, 30},
193 | {690, 25},
194 | {743, 20},
195 | {796, 14},
196 | {849, 7},
197 | {902, 0},
198 | {955, -11},
199 | {1008, -35}
200 | };
201 | #endif
202 |
203 | #if (THERMISTORHEATER == 5) || (THERMISTORBED == 5) //100k ParCan thermistor (104GT-2)
204 |
205 | #define NUMTEMPS_5 61
206 | const short temptable_5[NUMTEMPS_5][2] = {
207 | {1, 713},
208 | {18, 316},
209 | {35, 266},
210 | {52, 239},
211 | {69, 221},
212 | {86, 208},
213 | {103, 197},
214 | {120, 188},
215 | {137, 181},
216 | {154, 174},
217 | {171, 169},
218 | {188, 163},
219 | {205, 159},
220 | {222, 154},
221 | {239, 150},
222 | {256, 147},
223 | {273, 143},
224 | {290, 140},
225 | {307, 136},
226 | {324, 133},
227 | {341, 130},
228 | {358, 128},
229 | {375, 125},
230 | {392, 122},
231 | {409, 120},
232 | {426, 117},
233 | {443, 115},
234 | {460, 112},
235 | {477, 110},
236 | {494, 108},
237 | {511, 106},
238 | {528, 103},
239 | {545, 101},
240 | {562, 99},
241 | {579, 97},
242 | {596, 95},
243 | {613, 92},
244 | {630, 90},
245 | {647, 88},
246 | {664, 86},
247 | {681, 84},
248 | {698, 81},
249 | {715, 79},
250 | {732, 77},
251 | {749, 75},
252 | {766, 72},
253 | {783, 70},
254 | {800, 67},
255 | {817, 64},
256 | {834, 61},
257 | {851, 58},
258 | {868, 55},
259 | {885, 52},
260 | {902, 48},
261 | {919, 44},
262 | {936, 40},
263 | {953, 34},
264 | {970, 28},
265 | {987, 20},
266 | {1004, 8},
267 | {1021, 0}
268 | };
269 | #endif
270 |
271 | #if (THERMISTORHEATER == 6) || (THERMISTORBED == 6) // 100k Epcos thermistor
272 | #define NUMTEMPS_6 36
273 | const short temptable_6[NUMTEMPS_6][2] = {
274 | {28, 250},
275 | {31, 245},
276 | {35, 240},
277 | {39, 235},
278 | {42, 230},
279 | {44, 225},
280 | {49, 220},
281 | {53, 215},
282 | {62, 210},
283 | {71, 205}, //fitted graphically
284 | {78, 200}, //fitted graphically
285 | {94, 190},
286 | {102, 185},
287 | {116, 170},
288 | {143, 160},
289 | {183, 150},
290 | {223, 140},
291 | {270, 130},
292 | {318, 120},
293 | {383, 110},
294 | {413, 105},
295 | {439, 100},
296 | {484, 95},
297 | {513, 90},
298 | {607, 80},
299 | {664, 70},
300 | {781, 60},
301 | {810, 55},
302 | {849, 50},
303 | {914, 45},
304 | {914, 40},
305 | {935, 35},
306 | {954, 30},
307 | {970, 25},
308 | {978, 22},
309 | {1008, 3}
310 | };
311 | #endif
312 |
313 | #if (THERMISTORHEATER == 7) || (THERMISTORBED == 7) // 100k Honeywell 135-104LAG-J01
314 | #define NUMTEMPS_7 55
315 | const short temptable_7[NUMTEMPS_7][2] = {
316 | {46, 270},
317 | {50, 265},
318 | {54, 260},
319 | {58, 255},
320 | {62, 250},
321 | {67, 245},
322 | {72, 240},
323 | {79, 235},
324 | {85, 230},
325 | {91, 225},
326 | {99, 220},
327 | {107, 215},
328 | {116, 210},
329 | {126, 205},
330 | {136, 200},
331 | {149, 195},
332 | {160, 190},
333 | {175, 185},
334 | {191, 180},
335 | {209, 175},
336 | {224, 170},
337 | {246, 165},
338 | {267, 160},
339 | {293, 155},
340 | {316, 150},
341 | {340, 145},
342 | {364, 140},
343 | {396, 135},
344 | {425, 130},
345 | {460, 125},
346 | {489, 120},
347 | {526, 115},
348 | {558, 110},
349 | {591, 105},
350 | {628, 100},
351 | {660, 95},
352 | {696, 90},
353 | {733, 85},
354 | {761, 80},
355 | {794, 75},
356 | {819, 70},
357 | {847, 65},
358 | {870, 60},
359 | {892, 55},
360 | {911, 50},
361 | {929, 45},
362 | {944, 40},
363 | {959, 35},
364 | {971, 30},
365 | {981, 25},
366 | {989, 20},
367 | {994, 15},
368 | {1001, 10},
369 | {1005, 5},
370 | {1021, 0} //safety
371 |
372 | };
373 | #endif
374 |
375 |
376 |
377 | #if THERMISTORHEATER == 1
378 | #define NUMTEMPS NUMTEMPS_1
379 | #define temptable temptable_1
380 | #elif THERMISTORHEATER == 2
381 | #define NUMTEMPS NUMTEMPS_2
382 | #define temptable temptable_2
383 | #elif THERMISTORHEATER == 3
384 | #define NUMTEMPS NUMTEMPS_3
385 | #define temptable temptable_3
386 | #elif THERMISTORHEATER == 4
387 | #define NUMTEMPS NUMTEMPS_4
388 | #define temptable temptable_4
389 | #elif THERMISTORHEATER == 5
390 | #define NUMTEMPS NUMTEMPS_5
391 | #define temptable temptable_5
392 | #elif THERMISTORHEATER == 6
393 | #define NUMTEMPS NUMTEMPS_6
394 | #define temptable temptable_6
395 | #elif THERMISTORHEATER == 7
396 | #define NUMTEMPS NUMTEMPS_7
397 | #define temptable temptable_7
398 | #elif defined HEATER_USES_THERMISTOR
399 | #error No heater thermistor table specified
400 | #endif
401 | #if THERMISTORBED == 1
402 | #define BNUMTEMPS NUMTEMPS_1
403 | #define bedtemptable temptable_1
404 | #elif THERMISTORBED == 2
405 | #define BNUMTEMPS NUMTEMPS_2
406 | #define bedtemptable temptable_2
407 | #elif THERMISTORBED == 3
408 | #define BNUMTEMPS NUMTEMPS_3
409 | #define bedtemptable temptable_3
410 | #elif THERMISTORBED == 4
411 | #define BNUMTEMPS NUMTEMPS_4
412 | #define bedtemptable temptable_4
413 | #elif THERMISTORBED == 5
414 | #define BNUMTEMPS NUMTEMPS_5
415 | #define bedtemptable temptable_5
416 | #elif THERMISTORBED == 6
417 | #define BNUMTEMPS NUMTEMPS_6
418 | #define bedtemptable temptable_6
419 | #elif THERMISTORBED == 7
420 | #define BNUMTEMPS NUMTEMPS_7
421 | #define bedtemptable temptable_7
422 | #elif defined BED_USES_THERMISTOR
423 | #error No bed thermistor table specified
424 | #endif
425 |
426 | #endif //THERMISTORTABLES_H_
427 |
--------------------------------------------------------------------------------
/Sprinter/Sd2Card.h:
--------------------------------------------------------------------------------
1 | /* Arduino Sd2Card Library
2 | * Copyright (C) 2009 by William Greiman
3 | *
4 | * This file is part of the Arduino Sd2Card Library
5 | *
6 | * This Library is free software: you can redistribute it and/or modify
7 | * it under the terms of the GNU General Public License as published by
8 | * the Free Software Foundation, either version 3 of the License, or
9 | * (at your option) any later version.
10 | *
11 | * This Library is distributed in the hope that it will be useful,
12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | * GNU General Public License for more details.
15 | *
16 | * You should have received a copy of the GNU General Public License
17 | * along with the Arduino Sd2Card Library. If not, see
18 | * .
19 | */
20 | #ifndef Sd2Card_h
21 | #define Sd2Card_h
22 | /**
23 | * \file
24 | * Sd2Card class
25 | */
26 | #include "Sd2PinMap.h"
27 | #include "SdInfo.h"
28 | /** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */
29 | uint8_t const SPI_FULL_SPEED = 0;
30 | /** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */
31 | uint8_t const SPI_HALF_SPEED = 1;
32 | /** Set SCK rate to F_CPU/8. Sd2Card::setSckRate(). */
33 | uint8_t const SPI_QUARTER_SPEED = 2;
34 | /**
35 | * Define MEGA_SOFT_SPI non-zero to use software SPI on Mega Arduinos.
36 | * Pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
37 | *
38 | * MEGA_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used
39 | * on Mega Arduinos. Software SPI works well with GPS Shield V1.1
40 | * but many SD cards will fail with GPS Shield V1.0.
41 | */
42 | #define MEGA_SOFT_SPI 0
43 | //------------------------------------------------------------------------------
44 | #if MEGA_SOFT_SPI && (defined(__AVR_ATmega1280__)||defined(__AVR_ATmega2560__))
45 | #define SOFTWARE_SPI
46 | #endif // MEGA_SOFT_SPI
47 | //------------------------------------------------------------------------------
48 | // SPI pin definitions
49 | //
50 | #ifndef SOFTWARE_SPI
51 | // hardware pin defs
52 | /**
53 | * SD Chip Select pin
54 | *
55 | * Warning if this pin is redefined the hardware SS will pin will be enabled
56 | * as an output by init(). An avr processor will not function as an SPI
57 | * master unless SS is set to output mode.
58 | */
59 | /** The default chip select pin for the SD card is SS. */
60 | uint8_t const SD_CHIP_SELECT_PIN = SS_PIN;
61 | // The following three pins must not be redefined for hardware SPI.
62 | /** SPI Master Out Slave In pin */
63 | uint8_t const SPI_MOSI_PIN = MOSI_PIN;
64 | /** SPI Master In Slave Out pin */
65 | uint8_t const SPI_MISO_PIN = MISO_PIN;
66 | /** SPI Clock pin */
67 | uint8_t const SPI_SCK_PIN = SCK_PIN;
68 | /** optimize loops for hardware SPI */
69 | #define OPTIMIZE_HARDWARE_SPI
70 |
71 | #else // SOFTWARE_SPI
72 | // define software SPI pins so Mega can use unmodified GPS Shield
73 | /** SPI chip select pin */
74 | uint8_t const SD_CHIP_SELECT_PIN = 10;
75 | /** SPI Master Out Slave In pin */
76 | uint8_t const SPI_MOSI_PIN = 11;
77 | /** SPI Master In Slave Out pin */
78 | uint8_t const SPI_MISO_PIN = 12;
79 | /** SPI Clock pin */
80 | uint8_t const SPI_SCK_PIN = 13;
81 | #endif // SOFTWARE_SPI
82 | //------------------------------------------------------------------------------
83 | /** Protect block zero from write if nonzero */
84 | #define SD_PROTECT_BLOCK_ZERO 1
85 | /** init timeout ms */
86 | uint16_t const SD_INIT_TIMEOUT = 2000;
87 | /** erase timeout ms */
88 | uint16_t const SD_ERASE_TIMEOUT = 10000;
89 | /** read timeout ms */
90 | uint16_t const SD_READ_TIMEOUT = 300;
91 | /** write time out ms */
92 | uint16_t const SD_WRITE_TIMEOUT = 600;
93 | //------------------------------------------------------------------------------
94 | // SD card errors
95 | /** timeout error for command CMD0 */
96 | uint8_t const SD_CARD_ERROR_CMD0 = 0X1;
97 | /** CMD8 was not accepted - not a valid SD card*/
98 | uint8_t const SD_CARD_ERROR_CMD8 = 0X2;
99 | /** card returned an error response for CMD17 (read block) */
100 | uint8_t const SD_CARD_ERROR_CMD17 = 0X3;
101 | /** card returned an error response for CMD24 (write block) */
102 | uint8_t const SD_CARD_ERROR_CMD24 = 0X4;
103 | /** WRITE_MULTIPLE_BLOCKS command failed */
104 | uint8_t const SD_CARD_ERROR_CMD25 = 0X05;
105 | /** card returned an error response for CMD58 (read OCR) */
106 | uint8_t const SD_CARD_ERROR_CMD58 = 0X06;
107 | /** SET_WR_BLK_ERASE_COUNT failed */
108 | uint8_t const SD_CARD_ERROR_ACMD23 = 0X07;
109 | /** card's ACMD41 initialization process timeout */
110 | uint8_t const SD_CARD_ERROR_ACMD41 = 0X08;
111 | /** card returned a bad CSR version field */
112 | uint8_t const SD_CARD_ERROR_BAD_CSD = 0X09;
113 | /** erase block group command failed */
114 | uint8_t const SD_CARD_ERROR_ERASE = 0X0A;
115 | /** card not capable of single block erase */
116 | uint8_t const SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0X0B;
117 | /** Erase sequence timed out */
118 | uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0X0C;
119 | /** card returned an error token instead of read data */
120 | uint8_t const SD_CARD_ERROR_READ = 0X0D;
121 | /** read CID or CSD failed */
122 | uint8_t const SD_CARD_ERROR_READ_REG = 0X0E;
123 | /** timeout while waiting for start of read data */
124 | uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0X0F;
125 | /** card did not accept STOP_TRAN_TOKEN */
126 | uint8_t const SD_CARD_ERROR_STOP_TRAN = 0X10;
127 | /** card returned an error token as a response to a write operation */
128 | uint8_t const SD_CARD_ERROR_WRITE = 0X11;
129 | /** attempt to write protected block zero */
130 | uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0X12;
131 | /** card did not go ready for a multiple block write */
132 | uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0X13;
133 | /** card returned an error to a CMD13 status check after a write */
134 | uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0X14;
135 | /** timeout occurred during write programming */
136 | uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0X15;
137 | /** incorrect rate selected */
138 | uint8_t const SD_CARD_ERROR_SCK_RATE = 0X16;
139 | //------------------------------------------------------------------------------
140 | // card types
141 | /** Standard capacity V1 SD card */
142 | uint8_t const SD_CARD_TYPE_SD1 = 1;
143 | /** Standard capacity V2 SD card */
144 | uint8_t const SD_CARD_TYPE_SD2 = 2;
145 | /** High Capacity SD card */
146 | uint8_t const SD_CARD_TYPE_SDHC = 3;
147 | //------------------------------------------------------------------------------
148 | /**
149 | * \class Sd2Card
150 | * \brief Raw access to SD and SDHC flash memory cards.
151 | */
152 | class Sd2Card {
153 | public:
154 | /** Construct an instance of Sd2Card. */
155 | Sd2Card(void) : errorCode_(0), inBlock_(0), partialBlockRead_(0), type_(0) {}
156 | uint32_t cardSize(void);
157 | uint8_t erase(uint32_t firstBlock, uint32_t lastBlock);
158 | uint8_t eraseSingleBlockEnable(void);
159 | /**
160 | * \return error code for last error. See Sd2Card.h for a list of error codes.
161 | */
162 | uint8_t errorCode(void) const {return errorCode_;}
163 | /** \return error data for last error. */
164 | uint8_t errorData(void) const {return status_;}
165 | /**
166 | * Initialize an SD flash memory card with default clock rate and chip
167 | * select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
168 | */
169 | uint8_t init(void) {
170 | return init(SPI_FULL_SPEED, SD_CHIP_SELECT_PIN);
171 | }
172 | /**
173 | * Initialize an SD flash memory card with the selected SPI clock rate
174 | * and the default SD chip select pin.
175 | * See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
176 | */
177 | uint8_t init(uint8_t sckRateID) {
178 | return init(sckRateID, SD_CHIP_SELECT_PIN);
179 | }
180 | uint8_t init(uint8_t sckRateID, uint8_t chipSelectPin);
181 | void partialBlockRead(uint8_t value);
182 | /** Returns the current value, true or false, for partial block read. */
183 | uint8_t partialBlockRead(void) const {return partialBlockRead_;}
184 | uint8_t readBlock(uint32_t block, uint8_t* dst);
185 | uint8_t readData(uint32_t block,
186 | uint16_t offset, uint16_t count, uint8_t* dst);
187 | /**
188 | * Read a cards CID register. The CID contains card identification
189 | * information such as Manufacturer ID, Product name, Product serial
190 | * number and Manufacturing date. */
191 | uint8_t readCID(cid_t* cid) {
192 | return readRegister(CMD10, cid);
193 | }
194 | /**
195 | * Read a cards CSD register. The CSD contains Card-Specific Data that
196 | * provides information regarding access to the card's contents. */
197 | uint8_t readCSD(csd_t* csd) {
198 | return readRegister(CMD9, csd);
199 | }
200 | void readEnd(void);
201 | uint8_t setSckRate(uint8_t sckRateID);
202 | /** Return the card type: SD V1, SD V2 or SDHC */
203 | uint8_t type(void) const {return type_;}
204 | uint8_t writeBlock(uint32_t blockNumber, const uint8_t* src);
205 | uint8_t writeData(const uint8_t* src);
206 | uint8_t writeStart(uint32_t blockNumber, uint32_t eraseCount);
207 | uint8_t writeStop(void);
208 | private:
209 | uint32_t block_;
210 | uint8_t chipSelectPin_;
211 | uint8_t errorCode_;
212 | uint8_t inBlock_;
213 | uint16_t offset_;
214 | uint8_t partialBlockRead_;
215 | uint8_t status_;
216 | uint8_t type_;
217 | // private functions
218 | uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
219 | cardCommand(CMD55, 0);
220 | return cardCommand(cmd, arg);
221 | }
222 | uint8_t cardCommand(uint8_t cmd, uint32_t arg);
223 | void error(uint8_t code) {errorCode_ = code;}
224 | uint8_t readRegister(uint8_t cmd, void* buf);
225 | uint8_t sendWriteCommand(uint32_t blockNumber, uint32_t eraseCount);
226 | void chipSelectHigh(void);
227 | void chipSelectLow(void);
228 | void type(uint8_t value) {type_ = value;}
229 | uint8_t waitNotBusy(uint16_t timeoutMillis);
230 | uint8_t writeData(uint8_t token, const uint8_t* src);
231 | uint8_t waitStartBlock(void);
232 | };
233 | #endif // Sd2Card_h
234 |
--------------------------------------------------------------------------------
/Sprinter/SdVolume.cpp:
--------------------------------------------------------------------------------
1 | /* Arduino SdFat Library
2 | * Copyright (C) 2009 by William Greiman
3 | *
4 | * This file is part of the Arduino SdFat Library
5 | *
6 | * This Library is free software: you can redistribute it and/or modify
7 | * it under the terms of the GNU General Public License as published by
8 | * the Free Software Foundation, either version 3 of the License, or
9 | * (at your option) any later version.
10 | *
11 | * This Library is distributed in the hope that it will be useful,
12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | * GNU General Public License for more details.
15 | *
16 | * You should have received a copy of the GNU General Public License
17 | * along with the Arduino SdFat Library. If not, see
18 | * .
19 | */
20 | #include "SdFat.h"
21 | //------------------------------------------------------------------------------
22 | // raw block cache
23 | // init cacheBlockNumber_to invalid SD block number
24 | uint32_t SdVolume::cacheBlockNumber_ = 0XFFFFFFFF;
25 | cache_t SdVolume::cacheBuffer_; // 512 byte cache for Sd2Card
26 | Sd2Card* SdVolume::sdCard_; // pointer to SD card object
27 | uint8_t SdVolume::cacheDirty_ = 0; // cacheFlush() will write block if true
28 | uint32_t SdVolume::cacheMirrorBlock_ = 0; // mirror block for second FAT
29 | //------------------------------------------------------------------------------
30 | // find a contiguous group of clusters
31 | uint8_t SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
32 | // start of group
33 | uint32_t bgnCluster;
34 |
35 | // flag to save place to start next search
36 | uint8_t setStart;
37 |
38 | // set search start cluster
39 | if (*curCluster) {
40 | // try to make file contiguous
41 | bgnCluster = *curCluster + 1;
42 |
43 | // don't save new start location
44 | setStart = false;
45 | } else {
46 | // start at likely place for free cluster
47 | bgnCluster = allocSearchStart_;
48 |
49 | // save next search start if one cluster
50 | setStart = 1 == count;
51 | }
52 | // end of group
53 | uint32_t endCluster = bgnCluster;
54 |
55 | // last cluster of FAT
56 | uint32_t fatEnd = clusterCount_ + 1;
57 |
58 | // search the FAT for free clusters
59 | for (uint32_t n = 0;; n++, endCluster++) {
60 | // can't find space checked all clusters
61 | if (n >= clusterCount_) return false;
62 |
63 | // past end - start from beginning of FAT
64 | if (endCluster > fatEnd) {
65 | bgnCluster = endCluster = 2;
66 | }
67 | uint32_t f;
68 | if (!fatGet(endCluster, &f)) return false;
69 |
70 | if (f != 0) {
71 | // cluster in use try next cluster as bgnCluster
72 | bgnCluster = endCluster + 1;
73 | } else if ((endCluster - bgnCluster + 1) == count) {
74 | // done - found space
75 | break;
76 | }
77 | }
78 | // mark end of chain
79 | if (!fatPutEOC(endCluster)) return false;
80 |
81 | // link clusters
82 | while (endCluster > bgnCluster) {
83 | if (!fatPut(endCluster - 1, endCluster)) return false;
84 | endCluster--;
85 | }
86 | if (*curCluster != 0) {
87 | // connect chains
88 | if (!fatPut(*curCluster, bgnCluster)) return false;
89 | }
90 | // return first cluster number to caller
91 | *curCluster = bgnCluster;
92 |
93 | // remember possible next free cluster
94 | if (setStart) allocSearchStart_ = bgnCluster + 1;
95 |
96 | return true;
97 | }
98 | //------------------------------------------------------------------------------
99 | uint8_t SdVolume::cacheFlush(void) {
100 | if (cacheDirty_) {
101 | if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) {
102 | return false;
103 | }
104 | // mirror FAT tables
105 | if (cacheMirrorBlock_) {
106 | if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data)) {
107 | return false;
108 | }
109 | cacheMirrorBlock_ = 0;
110 | }
111 | cacheDirty_ = 0;
112 | }
113 | return true;
114 | }
115 | //------------------------------------------------------------------------------
116 | uint8_t SdVolume::cacheRawBlock(uint32_t blockNumber, uint8_t action) {
117 | if (cacheBlockNumber_ != blockNumber) {
118 | if (!cacheFlush()) return false;
119 | if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) return false;
120 | cacheBlockNumber_ = blockNumber;
121 | }
122 | cacheDirty_ |= action;
123 | return true;
124 | }
125 | //------------------------------------------------------------------------------
126 | // cache a zero block for blockNumber
127 | uint8_t SdVolume::cacheZeroBlock(uint32_t blockNumber) {
128 | if (!cacheFlush()) return false;
129 |
130 | // loop take less flash than memset(cacheBuffer_.data, 0, 512);
131 | for (uint16_t i = 0; i < 512; i++) {
132 | cacheBuffer_.data[i] = 0;
133 | }
134 | cacheBlockNumber_ = blockNumber;
135 | cacheSetDirty();
136 | return true;
137 | }
138 | //------------------------------------------------------------------------------
139 | // return the size in bytes of a cluster chain
140 | uint8_t SdVolume::chainSize(uint32_t cluster, uint32_t* size) const {
141 | uint32_t s = 0;
142 | do {
143 | if (!fatGet(cluster, &cluster)) return false;
144 | s += 512UL << clusterSizeShift_;
145 | } while (!isEOC(cluster));
146 | *size = s;
147 | return true;
148 | }
149 | //------------------------------------------------------------------------------
150 | // Fetch a FAT entry
151 | uint8_t SdVolume::fatGet(uint32_t cluster, uint32_t* value) const {
152 | if (cluster > (clusterCount_ + 1)) return false;
153 | uint32_t lba = fatStartBlock_;
154 | lba += fatType_ == 16 ? cluster >> 8 : cluster >> 7;
155 | if (lba != cacheBlockNumber_) {
156 | if (!cacheRawBlock(lba, CACHE_FOR_READ)) return false;
157 | }
158 | if (fatType_ == 16) {
159 | *value = cacheBuffer_.fat16[cluster & 0XFF];
160 | } else {
161 | *value = cacheBuffer_.fat32[cluster & 0X7F] & FAT32MASK;
162 | }
163 | return true;
164 | }
165 | //------------------------------------------------------------------------------
166 | // Store a FAT entry
167 | uint8_t SdVolume::fatPut(uint32_t cluster, uint32_t value) {
168 | // error if reserved cluster
169 | if (cluster < 2) return false;
170 |
171 | // error if not in FAT
172 | if (cluster > (clusterCount_ + 1)) return false;
173 |
174 | // calculate block address for entry
175 | uint32_t lba = fatStartBlock_;
176 | lba += fatType_ == 16 ? cluster >> 8 : cluster >> 7;
177 |
178 | if (lba != cacheBlockNumber_) {
179 | if (!cacheRawBlock(lba, CACHE_FOR_READ)) return false;
180 | }
181 | // store entry
182 | if (fatType_ == 16) {
183 | cacheBuffer_.fat16[cluster & 0XFF] = value;
184 | } else {
185 | cacheBuffer_.fat32[cluster & 0X7F] = value;
186 | }
187 | cacheSetDirty();
188 |
189 | // mirror second FAT
190 | if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
191 | return true;
192 | }
193 | //------------------------------------------------------------------------------
194 | // free a cluster chain
195 | uint8_t SdVolume::freeChain(uint32_t cluster) {
196 | // clear free cluster location
197 | allocSearchStart_ = 2;
198 |
199 | do {
200 | uint32_t next;
201 | if (!fatGet(cluster, &next)) return false;
202 |
203 | // free cluster
204 | if (!fatPut(cluster, 0)) return false;
205 |
206 | cluster = next;
207 | } while (!isEOC(cluster));
208 |
209 | return true;
210 | }
211 | //------------------------------------------------------------------------------
212 | /**
213 | * Initialize a FAT volume.
214 | *
215 | * \param[in] dev The SD card where the volume is located.
216 | *
217 | * \param[in] part The partition to be used. Legal values for \a part are
218 | * 1-4 to use the corresponding partition on a device formatted with
219 | * a MBR, Master Boot Record, or zero if the device is formatted as
220 | * a super floppy with the FAT boot sector in block zero.
221 | *
222 | * \return The value one, true, is returned for success and
223 | * the value zero, false, is returned for failure. Reasons for
224 | * failure include not finding a valid partition, not finding a valid
225 | * FAT file system in the specified partition or an I/O error.
226 | */
227 | uint8_t SdVolume::init(Sd2Card* dev, uint8_t part) {
228 | uint32_t volumeStartBlock = 0;
229 | sdCard_ = dev;
230 | // if part == 0 assume super floppy with FAT boot sector in block zero
231 | // if part > 0 assume mbr volume with partition table
232 | if (part) {
233 | if (part > 4)return false;
234 | if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) return false;
235 | part_t* p = &cacheBuffer_.mbr.part[part-1];
236 | if ((p->boot & 0X7F) !=0 ||
237 | p->totalSectors < 100 ||
238 | p->firstSector == 0) {
239 | // not a valid partition
240 | return false;
241 | }
242 | volumeStartBlock = p->firstSector;
243 | }
244 | if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) return false;
245 | bpb_t* bpb = &cacheBuffer_.fbs.bpb;
246 | if (bpb->bytesPerSector != 512 ||
247 | bpb->fatCount == 0 ||
248 | bpb->reservedSectorCount == 0 ||
249 | bpb->sectorsPerCluster == 0) {
250 | // not valid FAT volume
251 | return false;
252 | }
253 | fatCount_ = bpb->fatCount;
254 | blocksPerCluster_ = bpb->sectorsPerCluster;
255 |
256 | // determine shift that is same as multiply by blocksPerCluster_
257 | clusterSizeShift_ = 0;
258 | while (blocksPerCluster_ != (1 << clusterSizeShift_)) {
259 | // error if not power of 2
260 | if (clusterSizeShift_++ > 7) return false;
261 | }
262 | blocksPerFat_ = bpb->sectorsPerFat16 ?
263 | bpb->sectorsPerFat16 : bpb->sectorsPerFat32;
264 |
265 | fatStartBlock_ = volumeStartBlock + bpb->reservedSectorCount;
266 |
267 | // count for FAT16 zero for FAT32
268 | rootDirEntryCount_ = bpb->rootDirEntryCount;
269 |
270 | // directory start for FAT16 dataStart for FAT32
271 | rootDirStart_ = fatStartBlock_ + bpb->fatCount * blocksPerFat_;
272 |
273 | // data start for FAT16 and FAT32
274 | dataStartBlock_ = rootDirStart_ + ((32 * bpb->rootDirEntryCount + 511)/512);
275 |
276 | // total blocks for FAT16 or FAT32
277 | uint32_t totalBlocks = bpb->totalSectors16 ?
278 | bpb->totalSectors16 : bpb->totalSectors32;
279 | // total data blocks
280 | clusterCount_ = totalBlocks - (dataStartBlock_ - volumeStartBlock);
281 |
282 | // divide by cluster size to get cluster count
283 | clusterCount_ >>= clusterSizeShift_;
284 |
285 | // FAT type is determined by cluster count
286 | if (clusterCount_ < 4085) {
287 | fatType_ = 12;
288 | } else if (clusterCount_ < 65525) {
289 | fatType_ = 16;
290 | } else {
291 | rootDirStart_ = bpb->fat32RootCluster;
292 | fatType_ = 32;
293 | }
294 | return true;
295 | }
296 |
--------------------------------------------------------------------------------
/Sprinter/speed_lookuptable.h:
--------------------------------------------------------------------------------
1 | #ifndef SPEED_LOOKUPTABLE_H
2 | #define SPEED_LOOKUPTABLE_H
3 |
4 | #include
5 |
6 |
7 | #if F_CPU == 16000000
8 | const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {\
9 | { 62500, 55556}, { 6944, 3268}, { 3676, 1176}, { 2500, 607}, { 1893, 369}, { 1524, 249}, { 1275, 179}, { 1096, 135},
10 | { 961, 105}, { 856, 85}, { 771, 69}, { 702, 58}, { 644, 49}, { 595, 42}, { 553, 37}, { 516, 32},
11 | { 484, 28}, { 456, 25}, { 431, 23}, { 408, 20}, { 388, 19}, { 369, 16}, { 353, 16}, { 337, 14},
12 | { 323, 13}, { 310, 11}, { 299, 11}, { 288, 11}, { 277, 9}, { 268, 9}, { 259, 8}, { 251, 8},
13 | { 243, 8}, { 235, 7}, { 228, 6}, { 222, 6}, { 216, 6}, { 210, 6}, { 204, 5}, { 199, 5},
14 | { 194, 5}, { 189, 4}, { 185, 4}, { 181, 4}, { 177, 4}, { 173, 4}, { 169, 4}, { 165, 3},
15 | { 162, 3}, { 159, 4}, { 155, 3}, { 152, 3}, { 149, 2}, { 147, 3}, { 144, 3}, { 141, 2},
16 | { 139, 3}, { 136, 2}, { 134, 2}, { 132, 3}, { 129, 2}, { 127, 2}, { 125, 2}, { 123, 2},
17 | { 121, 2}, { 119, 1}, { 118, 2}, { 116, 2}, { 114, 1}, { 113, 2}, { 111, 2}, { 109, 1},
18 | { 108, 2}, { 106, 1}, { 105, 2}, { 103, 1}, { 102, 1}, { 101, 1}, { 100, 2}, { 98, 1},
19 | { 97, 1}, { 96, 1}, { 95, 2}, { 93, 1}, { 92, 1}, { 91, 1}, { 90, 1}, { 89, 1},
20 | { 88, 1}, { 87, 1}, { 86, 1}, { 85, 1}, { 84, 1}, { 83, 0}, { 83, 1}, { 82, 1},
21 | { 81, 1}, { 80, 1}, { 79, 1}, { 78, 0}, { 78, 1}, { 77, 1}, { 76, 1}, { 75, 0},
22 | { 75, 1}, { 74, 1}, { 73, 1}, { 72, 0}, { 72, 1}, { 71, 1}, { 70, 0}, { 70, 1},
23 | { 69, 0}, { 69, 1}, { 68, 1}, { 67, 0}, { 67, 1}, { 66, 0}, { 66, 1}, { 65, 0},
24 | { 65, 1}, { 64, 1}, { 63, 0}, { 63, 1}, { 62, 0}, { 62, 1}, { 61, 0}, { 61, 1},
25 | { 60, 0}, { 60, 0}, { 60, 1}, { 59, 0}, { 59, 1}, { 58, 0}, { 58, 1}, { 57, 0},
26 | { 57, 1}, { 56, 0}, { 56, 0}, { 56, 1}, { 55, 0}, { 55, 1}, { 54, 0}, { 54, 0},
27 | { 54, 1}, { 53, 0}, { 53, 0}, { 53, 1}, { 52, 0}, { 52, 0}, { 52, 1}, { 51, 0},
28 | { 51, 0}, { 51, 1}, { 50, 0}, { 50, 0}, { 50, 1}, { 49, 0}, { 49, 0}, { 49, 1},
29 | { 48, 0}, { 48, 0}, { 48, 1}, { 47, 0}, { 47, 0}, { 47, 0}, { 47, 1}, { 46, 0},
30 | { 46, 0}, { 46, 1}, { 45, 0}, { 45, 0}, { 45, 0}, { 45, 1}, { 44, 0}, { 44, 0},
31 | { 44, 0}, { 44, 1}, { 43, 0}, { 43, 0}, { 43, 0}, { 43, 1}, { 42, 0}, { 42, 0},
32 | { 42, 0}, { 42, 1}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 0}, { 41, 1}, { 40, 0},
33 | { 40, 0}, { 40, 0}, { 40, 0}, { 40, 1}, { 39, 0}, { 39, 0}, { 39, 0}, { 39, 0},
34 | { 39, 1}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 0}, { 38, 1}, { 37, 0}, { 37, 0},
35 | { 37, 0}, { 37, 0}, { 37, 0}, { 37, 1}, { 36, 0}, { 36, 0}, { 36, 0}, { 36, 0},
36 | { 36, 1}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 0}, { 35, 1},
37 | { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 0}, { 34, 1}, { 33, 0}, { 33, 0},
38 | { 33, 0}, { 33, 0}, { 33, 0}, { 33, 0}, { 33, 1}, { 32, 0}, { 32, 0}, { 32, 0},
39 | { 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0},
40 | { 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
41 | };
42 |
43 | const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {\
44 | { 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894},
45 | { 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657},
46 | { 12500, 596}, { 11904, 541}, { 11363, 494}, { 10869, 453}, { 10416, 416}, { 10000, 385}, { 9615, 356}, { 9259, 331},
47 | { 8928, 308}, { 8620, 287}, { 8333, 269}, { 8064, 252}, { 7812, 237}, { 7575, 223}, { 7352, 210}, { 7142, 198},
48 | { 6944, 188}, { 6756, 178}, { 6578, 168}, { 6410, 160}, { 6250, 153}, { 6097, 145}, { 5952, 139}, { 5813, 132},
49 | { 5681, 126}, { 5555, 121}, { 5434, 115}, { 5319, 111}, { 5208, 106}, { 5102, 102}, { 5000, 99}, { 4901, 94},
50 | { 4807, 91}, { 4716, 87}, { 4629, 84}, { 4545, 81}, { 4464, 79}, { 4385, 75}, { 4310, 73}, { 4237, 71},
51 | { 4166, 68}, { 4098, 66}, { 4032, 64}, { 3968, 62}, { 3906, 60}, { 3846, 59}, { 3787, 56}, { 3731, 55},
52 | { 3676, 53}, { 3623, 52}, { 3571, 50}, { 3521, 49}, { 3472, 48}, { 3424, 46}, { 3378, 45}, { 3333, 44},
53 | { 3289, 43}, { 3246, 41}, { 3205, 41}, { 3164, 39}, { 3125, 39}, { 3086, 38}, { 3048, 36}, { 3012, 36},
54 | { 2976, 35}, { 2941, 35}, { 2906, 33}, { 2873, 33}, { 2840, 32}, { 2808, 31}, { 2777, 30}, { 2747, 30},
55 | { 2717, 29}, { 2688, 29}, { 2659, 28}, { 2631, 27}, { 2604, 27}, { 2577, 26}, { 2551, 26}, { 2525, 25},
56 | { 2500, 25}, { 2475, 25}, { 2450, 23}, { 2427, 24}, { 2403, 23}, { 2380, 22}, { 2358, 22}, { 2336, 22},
57 | { 2314, 21}, { 2293, 21}, { 2272, 20}, { 2252, 20}, { 2232, 20}, { 2212, 20}, { 2192, 19}, { 2173, 18},
58 | { 2155, 19}, { 2136, 18}, { 2118, 18}, { 2100, 17}, { 2083, 17}, { 2066, 17}, { 2049, 17}, { 2032, 16},
59 | { 2016, 16}, { 2000, 16}, { 1984, 16}, { 1968, 15}, { 1953, 16}, { 1937, 14}, { 1923, 15}, { 1908, 15},
60 | { 1893, 14}, { 1879, 14}, { 1865, 14}, { 1851, 13}, { 1838, 14}, { 1824, 13}, { 1811, 13}, { 1798, 13},
61 | { 1785, 12}, { 1773, 13}, { 1760, 12}, { 1748, 12}, { 1736, 12}, { 1724, 12}, { 1712, 12}, { 1700, 11},
62 | { 1689, 12}, { 1677, 11}, { 1666, 11}, { 1655, 11}, { 1644, 11}, { 1633, 10}, { 1623, 11}, { 1612, 10},
63 | { 1602, 10}, { 1592, 10}, { 1582, 10}, { 1572, 10}, { 1562, 10}, { 1552, 9}, { 1543, 10}, { 1533, 9},
64 | { 1524, 9}, { 1515, 9}, { 1506, 9}, { 1497, 9}, { 1488, 9}, { 1479, 9}, { 1470, 9}, { 1461, 8},
65 | { 1453, 8}, { 1445, 9}, { 1436, 8}, { 1428, 8}, { 1420, 8}, { 1412, 8}, { 1404, 8}, { 1396, 8},
66 | { 1388, 7}, { 1381, 8}, { 1373, 7}, { 1366, 8}, { 1358, 7}, { 1351, 7}, { 1344, 8}, { 1336, 7},
67 | { 1329, 7}, { 1322, 7}, { 1315, 7}, { 1308, 6}, { 1302, 7}, { 1295, 7}, { 1288, 6}, { 1282, 7},
68 | { 1275, 6}, { 1269, 7}, { 1262, 6}, { 1256, 6}, { 1250, 7}, { 1243, 6}, { 1237, 6}, { 1231, 6},
69 | { 1225, 6}, { 1219, 6}, { 1213, 6}, { 1207, 6}, { 1201, 5}, { 1196, 6}, { 1190, 6}, { 1184, 5},
70 | { 1179, 6}, { 1173, 5}, { 1168, 6}, { 1162, 5}, { 1157, 5}, { 1152, 6}, { 1146, 5}, { 1141, 5},
71 | { 1136, 5}, { 1131, 5}, { 1126, 5}, { 1121, 5}, { 1116, 5}, { 1111, 5}, { 1106, 5}, { 1101, 5},
72 | { 1096, 5}, { 1091, 5}, { 1086, 4}, { 1082, 5}, { 1077, 5}, { 1072, 4}, { 1068, 5}, { 1063, 4},
73 | { 1059, 5}, { 1054, 4}, { 1050, 4}, { 1046, 5}, { 1041, 4}, { 1037, 4}, { 1033, 5}, { 1028, 4},
74 | { 1024, 4}, { 1020, 4}, { 1016, 4}, { 1012, 4}, { 1008, 4}, { 1004, 4}, { 1000, 4}, { 996, 4},
75 | { 992, 4}, { 988, 4}, { 984, 4}, { 980, 4}, { 976, 4}, { 972, 4}, { 968, 3}, { 965, 3}
76 | };
77 |
78 | #else
79 |
80 | const uint16_t speed_lookuptable_fast[256][2] PROGMEM = {
81 | {62500, 54055}, {8445, 3917}, {4528, 1434}, {3094, 745}, {2349, 456}, {1893, 307}, {1586, 222}, {1364, 167},
82 | {1197, 131}, {1066, 105}, {961, 86}, {875, 72}, {803, 61}, {742, 53}, {689, 45}, {644, 40},
83 | {604, 35}, {569, 32}, {537, 28}, {509, 25}, {484, 23}, {461, 21}, {440, 19}, {421, 17},
84 | {404, 16}, {388, 15}, {373, 14}, {359, 13}, {346, 12}, {334, 11}, {323, 10}, {313, 10},
85 | {303, 9}, {294, 9}, {285, 8}, {277, 7}, {270, 8}, {262, 7}, {255, 6}, {249, 6},
86 | {243, 6}, {237, 6}, {231, 5}, {226, 5}, {221, 5}, {216, 5}, {211, 4}, {207, 5},
87 | {202, 4}, {198, 4}, {194, 4}, {190, 3}, {187, 4}, {183, 3}, {180, 3}, {177, 4},
88 | {173, 3}, {170, 3}, {167, 2}, {165, 3}, {162, 3}, {159, 2}, {157, 3}, {154, 2},
89 | {152, 3}, {149, 2}, {147, 2}, {145, 2}, {143, 2}, {141, 2}, {139, 2}, {137, 2},
90 | {135, 2}, {133, 2}, {131, 2}, {129, 1}, {128, 2}, {126, 2}, {124, 1}, {123, 2},
91 | {121, 1}, {120, 2}, {118, 1}, {117, 1}, {116, 2}, {114, 1}, {113, 1}, {112, 2},
92 | {110, 1}, {109, 1}, {108, 1}, {107, 2}, {105, 1}, {104, 1}, {103, 1}, {102, 1},
93 | {101, 1}, {100, 1}, {99, 1}, {98, 1}, {97, 1}, {96, 1}, {95, 1}, {94, 1},
94 | {93, 1}, {92, 1}, {91, 0}, {91, 1}, {90, 1}, {89, 1}, {88, 1}, {87, 0},
95 | {87, 1}, {86, 1}, {85, 1}, {84, 0}, {84, 1}, {83, 1}, {82, 1}, {81, 0},
96 | {81, 1}, {80, 1}, {79, 0}, {79, 1}, {78, 0}, {78, 1}, {77, 1}, {76, 0},
97 | {76, 1}, {75, 0}, {75, 1}, {74, 1}, {73, 0}, {73, 1}, {72, 0}, {72, 1},
98 | {71, 0}, {71, 1}, {70, 0}, {70, 1}, {69, 0}, {69, 1}, {68, 0}, {68, 1},
99 | {67, 0}, {67, 1}, {66, 0}, {66, 1}, {65, 0}, {65, 0}, {65, 1}, {64, 0},
100 | {64, 1}, {63, 0}, {63, 1}, {62, 0}, {62, 0}, {62, 1}, {61, 0}, {61, 1},
101 | {60, 0}, {60, 0}, {60, 1}, {59, 0}, {59, 0}, {59, 1}, {58, 0}, {58, 0},
102 | {58, 1}, {57, 0}, {57, 0}, {57, 1}, {56, 0}, {56, 0}, {56, 1}, {55, 0},
103 | {55, 0}, {55, 1}, {54, 0}, {54, 0}, {54, 1}, {53, 0}, {53, 0}, {53, 0},
104 | {53, 1}, {52, 0}, {52, 0}, {52, 1}, {51, 0}, {51, 0}, {51, 0}, {51, 1},
105 | {50, 0}, {50, 0}, {50, 0}, {50, 1}, {49, 0}, {49, 0}, {49, 0}, {49, 1},
106 | {48, 0}, {48, 0}, {48, 0}, {48, 1}, {47, 0}, {47, 0}, {47, 0}, {47, 1},
107 | {46, 0}, {46, 0}, {46, 0}, {46, 0}, {46, 1}, {45, 0}, {45, 0}, {45, 0},
108 | {45, 1}, {44, 0}, {44, 0}, {44, 0}, {44, 0}, {44, 1}, {43, 0}, {43, 0},
109 | {43, 0}, {43, 0}, {43, 1}, {42, 0}, {42, 0}, {42, 0}, {42, 0}, {42, 0},
110 | {42, 1}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 0}, {41, 1}, {40, 0},
111 | {40, 0}, {40, 0}, {40, 0}, {40, 1}, {39, 0}, {39, 0}, {39, 0}, {39, 0},
112 | {39, 0}, {39, 0}, {39, 1}, {38, 0}, {38, 0}, {38, 0}, {38, 0}, {38, 0},
113 | };
114 |
115 | const uint16_t speed_lookuptable_slow[256][2] PROGMEM = {
116 | {62500, 10417}, {52083, 7441}, {44642, 5580}, {39062, 4340}, {34722, 3472}, {31250, 2841}, {28409, 2368}, {26041, 2003},
117 | {24038, 1717}, {22321, 1488}, {20833, 1302}, {19531, 1149}, {18382, 1021}, {17361, 914}, {16447, 822}, {15625, 745},
118 | {14880, 676}, {14204, 618}, {13586, 566}, {13020, 520}, {12500, 481}, {12019, 445}, {11574, 414}, {11160, 385},
119 | {10775, 359}, {10416, 336}, {10080, 315}, {9765, 296}, {9469, 278}, {9191, 263}, {8928, 248}, {8680, 235},
120 | {8445, 222}, {8223, 211}, {8012, 200}, {7812, 191}, {7621, 181}, {7440, 173}, {7267, 165}, {7102, 158},
121 | {6944, 151}, {6793, 145}, {6648, 138}, {6510, 133}, {6377, 127}, {6250, 123}, {6127, 118}, {6009, 113},
122 | {5896, 109}, {5787, 106}, {5681, 101}, {5580, 98}, {5482, 95}, {5387, 91}, {5296, 88}, {5208, 86},
123 | {5122, 82}, {5040, 80}, {4960, 78}, {4882, 75}, {4807, 73}, {4734, 70}, {4664, 69}, {4595, 67},
124 | {4528, 64}, {4464, 63}, {4401, 61}, {4340, 60}, {4280, 58}, {4222, 56}, {4166, 55}, {4111, 53},
125 | {4058, 52}, {4006, 51}, {3955, 49}, {3906, 48}, {3858, 48}, {3810, 45}, {3765, 45}, {3720, 44},
126 | {3676, 43}, {3633, 42}, {3591, 40}, {3551, 40}, {3511, 39}, {3472, 38}, {3434, 38}, {3396, 36},
127 | {3360, 36}, {3324, 35}, {3289, 34}, {3255, 34}, {3221, 33}, {3188, 32}, {3156, 31}, {3125, 31},
128 | {3094, 31}, {3063, 30}, {3033, 29}, {3004, 28}, {2976, 28}, {2948, 28}, {2920, 27}, {2893, 27},
129 | {2866, 26}, {2840, 25}, {2815, 25}, {2790, 25}, {2765, 24}, {2741, 24}, {2717, 24}, {2693, 23},
130 | {2670, 22}, {2648, 22}, {2626, 22}, {2604, 22}, {2582, 21}, {2561, 21}, {2540, 20}, {2520, 20},
131 | {2500, 20}, {2480, 20}, {2460, 19}, {2441, 19}, {2422, 19}, {2403, 18}, {2385, 18}, {2367, 18},
132 | {2349, 17}, {2332, 18}, {2314, 17}, {2297, 16}, {2281, 17}, {2264, 16}, {2248, 16}, {2232, 16},
133 | {2216, 16}, {2200, 15}, {2185, 15}, {2170, 15}, {2155, 15}, {2140, 15}, {2125, 14}, {2111, 14},
134 | {2097, 14}, {2083, 14}, {2069, 14}, {2055, 13}, {2042, 13}, {2029, 13}, {2016, 13}, {2003, 13},
135 | {1990, 13}, {1977, 12}, {1965, 12}, {1953, 13}, {1940, 11}, {1929, 12}, {1917, 12}, {1905, 12},
136 | {1893, 11}, {1882, 11}, {1871, 11}, {1860, 11}, {1849, 11}, {1838, 11}, {1827, 11}, {1816, 10},
137 | {1806, 11}, {1795, 10}, {1785, 10}, {1775, 10}, {1765, 10}, {1755, 10}, {1745, 9}, {1736, 10},
138 | {1726, 9}, {1717, 10}, {1707, 9}, {1698, 9}, {1689, 9}, {1680, 9}, {1671, 9}, {1662, 9},
139 | {1653, 9}, {1644, 8}, {1636, 9}, {1627, 8}, {1619, 9}, {1610, 8}, {1602, 8}, {1594, 8},
140 | {1586, 8}, {1578, 8}, {1570, 8}, {1562, 8}, {1554, 7}, {1547, 8}, {1539, 8}, {1531, 7},
141 | {1524, 8}, {1516, 7}, {1509, 7}, {1502, 7}, {1495, 7}, {1488, 7}, {1481, 7}, {1474, 7},
142 | {1467, 7}, {1460, 7}, {1453, 7}, {1446, 6}, {1440, 7}, {1433, 7}, {1426, 6}, {1420, 6},
143 | {1414, 7}, {1407, 6}, {1401, 6}, {1395, 7}, {1388, 6}, {1382, 6}, {1376, 6}, {1370, 6},
144 | {1364, 6}, {1358, 6}, {1352, 6}, {1346, 5}, {1341, 6}, {1335, 6}, {1329, 5}, {1324, 6},
145 | {1318, 5}, {1313, 6}, {1307, 5}, {1302, 6}, {1296, 5}, {1291, 5}, {1286, 6}, {1280, 5},
146 | {1275, 5}, {1270, 5}, {1265, 5}, {1260, 5}, {1255, 5}, {1250, 5}, {1245, 5}, {1240, 5},
147 | {1235, 5}, {1230, 5}, {1225, 5}, {1220, 5}, {1215, 4}, {1211, 5}, {1206, 5}, {1201, 5},
148 | };
149 | #endif
150 |
151 | #endif
152 |
--------------------------------------------------------------------------------
/Sprinter/Sd2PinMap.h:
--------------------------------------------------------------------------------
1 | /* Arduino SdFat Library
2 | * Copyright (C) 2010 by William Greiman
3 | *
4 | * This file is part of the Arduino SdFat Library
5 | *
6 | * This Library is free software: you can redistribute it and/or modify
7 | * it under the terms of the GNU General Public License as published by
8 | * the Free Software Foundation, either version 3 of the License, or
9 | * (at your option) any later version.
10 | *
11 | * This Library is distributed in the hope that it will be useful,
12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | * GNU General Public License for more details.
15 | *
16 | * You should have received a copy of the GNU General Public License
17 | * along with the Arduino SdFat Library. If not, see
18 | * .
19 | */
20 | // Warning this file was generated by a program.
21 | #ifndef Sd2PinMap_h
22 | #define Sd2PinMap_h
23 | #include
24 |
25 | //------------------------------------------------------------------------------
26 | /** struct for mapping digital pins */
27 | struct pin_map_t {
28 | volatile uint8_t* ddr;
29 | volatile uint8_t* pin;
30 | volatile uint8_t* port;
31 | uint8_t bit;
32 | };
33 | //------------------------------------------------------------------------------
34 | #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
35 | // Mega
36 |
37 | // Two Wire (aka I2C) ports
38 | uint8_t const SDA_PIN = 20;
39 | uint8_t const SCL_PIN = 21;
40 |
41 | // SPI port
42 | uint8_t const SS_PIN = 53;
43 | uint8_t const MOSI_PIN = 51;
44 | uint8_t const MISO_PIN = 50;
45 | uint8_t const SCK_PIN = 52;
46 |
47 | static const pin_map_t digitalPinMap[] = {
48 | {&DDRE, &PINE, &PORTE, 0}, // E0 0
49 | {&DDRE, &PINE, &PORTE, 1}, // E1 1
50 | {&DDRE, &PINE, &PORTE, 4}, // E4 2
51 | {&DDRE, &PINE, &PORTE, 5}, // E5 3
52 | {&DDRG, &PING, &PORTG, 5}, // G5 4
53 | {&DDRE, &PINE, &PORTE, 3}, // E3 5
54 | {&DDRH, &PINH, &PORTH, 3}, // H3 6
55 | {&DDRH, &PINH, &PORTH, 4}, // H4 7
56 | {&DDRH, &PINH, &PORTH, 5}, // H5 8
57 | {&DDRH, &PINH, &PORTH, 6}, // H6 9
58 | {&DDRB, &PINB, &PORTB, 4}, // B4 10
59 | {&DDRB, &PINB, &PORTB, 5}, // B5 11
60 | {&DDRB, &PINB, &PORTB, 6}, // B6 12
61 | {&DDRB, &PINB, &PORTB, 7}, // B7 13
62 | {&DDRJ, &PINJ, &PORTJ, 1}, // J1 14
63 | {&DDRJ, &PINJ, &PORTJ, 0}, // J0 15
64 | {&DDRH, &PINH, &PORTH, 1}, // H1 16
65 | {&DDRH, &PINH, &PORTH, 0}, // H0 17
66 | {&DDRD, &PIND, &PORTD, 3}, // D3 18
67 | {&DDRD, &PIND, &PORTD, 2}, // D2 19
68 | {&DDRD, &PIND, &PORTD, 1}, // D1 20
69 | {&DDRD, &PIND, &PORTD, 0}, // D0 21
70 | {&DDRA, &PINA, &PORTA, 0}, // A0 22
71 | {&DDRA, &PINA, &PORTA, 1}, // A1 23
72 | {&DDRA, &PINA, &PORTA, 2}, // A2 24
73 | {&DDRA, &PINA, &PORTA, 3}, // A3 25
74 | {&DDRA, &PINA, &PORTA, 4}, // A4 26
75 | {&DDRA, &PINA, &PORTA, 5}, // A5 27
76 | {&DDRA, &PINA, &PORTA, 6}, // A6 28
77 | {&DDRA, &PINA, &PORTA, 7}, // A7 29
78 | {&DDRC, &PINC, &PORTC, 7}, // C7 30
79 | {&DDRC, &PINC, &PORTC, 6}, // C6 31
80 | {&DDRC, &PINC, &PORTC, 5}, // C5 32
81 | {&DDRC, &PINC, &PORTC, 4}, // C4 33
82 | {&DDRC, &PINC, &PORTC, 3}, // C3 34
83 | {&DDRC, &PINC, &PORTC, 2}, // C2 35
84 | {&DDRC, &PINC, &PORTC, 1}, // C1 36
85 | {&DDRC, &PINC, &PORTC, 0}, // C0 37
86 | {&DDRD, &PIND, &PORTD, 7}, // D7 38
87 | {&DDRG, &PING, &PORTG, 2}, // G2 39
88 | {&DDRG, &PING, &PORTG, 1}, // G1 40
89 | {&DDRG, &PING, &PORTG, 0}, // G0 41
90 | {&DDRL, &PINL, &PORTL, 7}, // L7 42
91 | {&DDRL, &PINL, &PORTL, 6}, // L6 43
92 | {&DDRL, &PINL, &PORTL, 5}, // L5 44
93 | {&DDRL, &PINL, &PORTL, 4}, // L4 45
94 | {&DDRL, &PINL, &PORTL, 3}, // L3 46
95 | {&DDRL, &PINL, &PORTL, 2}, // L2 47
96 | {&DDRL, &PINL, &PORTL, 1}, // L1 48
97 | {&DDRL, &PINL, &PORTL, 0}, // L0 49
98 | {&DDRB, &PINB, &PORTB, 3}, // B3 50
99 | {&DDRB, &PINB, &PORTB, 2}, // B2 51
100 | {&DDRB, &PINB, &PORTB, 1}, // B1 52
101 | {&DDRB, &PINB, &PORTB, 0}, // B0 53
102 | {&DDRF, &PINF, &PORTF, 0}, // F0 54
103 | {&DDRF, &PINF, &PORTF, 1}, // F1 55
104 | {&DDRF, &PINF, &PORTF, 2}, // F2 56
105 | {&DDRF, &PINF, &PORTF, 3}, // F3 57
106 | {&DDRF, &PINF, &PORTF, 4}, // F4 58
107 | {&DDRF, &PINF, &PORTF, 5}, // F5 59
108 | {&DDRF, &PINF, &PORTF, 6}, // F6 60
109 | {&DDRF, &PINF, &PORTF, 7}, // F7 61
110 | {&DDRK, &PINK, &PORTK, 0}, // K0 62
111 | {&DDRK, &PINK, &PORTK, 1}, // K1 63
112 | {&DDRK, &PINK, &PORTK, 2}, // K2 64
113 | {&DDRK, &PINK, &PORTK, 3}, // K3 65
114 | {&DDRK, &PINK, &PORTK, 4}, // K4 66
115 | {&DDRK, &PINK, &PORTK, 5}, // K5 67
116 | {&DDRK, &PINK, &PORTK, 6}, // K6 68
117 | {&DDRK, &PINK, &PORTK, 7} // K7 69
118 | };
119 | //------------------------------------------------------------------------------
120 | #elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega1284P__)
121 | // Sanguino
122 |
123 | // Two Wire (aka I2C) ports
124 | uint8_t const SDA_PIN = 17;
125 | uint8_t const SCL_PIN = 18;
126 |
127 | // SPI port
128 | uint8_t const SS_PIN = 4;
129 | uint8_t const MOSI_PIN = 5;
130 | uint8_t const MISO_PIN = 6;
131 | uint8_t const SCK_PIN = 7;
132 |
133 | static const pin_map_t digitalPinMap[] = {
134 | {&DDRB, &PINB, &PORTB, 0}, // B0 0
135 | {&DDRB, &PINB, &PORTB, 1}, // B1 1
136 | {&DDRB, &PINB, &PORTB, 2}, // B2 2
137 | {&DDRB, &PINB, &PORTB, 3}, // B3 3
138 | {&DDRB, &PINB, &PORTB, 4}, // B4 4
139 | {&DDRB, &PINB, &PORTB, 5}, // B5 5
140 | {&DDRB, &PINB, &PORTB, 6}, // B6 6
141 | {&DDRB, &PINB, &PORTB, 7}, // B7 7
142 | {&DDRD, &PIND, &PORTD, 0}, // D0 8
143 | {&DDRD, &PIND, &PORTD, 1}, // D1 9
144 | {&DDRD, &PIND, &PORTD, 2}, // D2 10
145 | {&DDRD, &PIND, &PORTD, 3}, // D3 11
146 | {&DDRD, &PIND, &PORTD, 4}, // D4 12
147 | {&DDRD, &PIND, &PORTD, 5}, // D5 13
148 | {&DDRD, &PIND, &PORTD, 6}, // D6 14
149 | {&DDRD, &PIND, &PORTD, 7}, // D7 15
150 | {&DDRC, &PINC, &PORTC, 0}, // C0 16
151 | {&DDRC, &PINC, &PORTC, 1}, // C1 17
152 | {&DDRC, &PINC, &PORTC, 2}, // C2 18
153 | {&DDRC, &PINC, &PORTC, 3}, // C3 19
154 | {&DDRC, &PINC, &PORTC, 4}, // C4 20
155 | {&DDRC, &PINC, &PORTC, 5}, // C5 21
156 | {&DDRC, &PINC, &PORTC, 6}, // C6 22
157 | {&DDRC, &PINC, &PORTC, 7}, // C7 23
158 | {&DDRA, &PINA, &PORTA, 7}, // A7 24
159 | {&DDRA, &PINA, &PORTA, 6}, // A6 25
160 | {&DDRA, &PINA, &PORTA, 5}, // A5 26
161 | {&DDRA, &PINA, &PORTA, 4}, // A4 27
162 | {&DDRA, &PINA, &PORTA, 3}, // A3 28
163 | {&DDRA, &PINA, &PORTA, 2}, // A2 29
164 | {&DDRA, &PINA, &PORTA, 1}, // A1 30
165 | {&DDRA, &PINA, &PORTA, 0} // A0 31
166 | };
167 | //------------------------------------------------------------------------------
168 | #elif defined(__AVR_ATmega32U4__)
169 | // Teensy 2.0
170 |
171 | // Two Wire (aka I2C) ports
172 | uint8_t const SDA_PIN = 6;
173 | uint8_t const SCL_PIN = 5;
174 |
175 | // SPI port
176 | uint8_t const SS_PIN = 0;
177 | uint8_t const MOSI_PIN = 2;
178 | uint8_t const MISO_PIN = 3;
179 | uint8_t const SCK_PIN = 1;
180 |
181 | static const pin_map_t digitalPinMap[] = {
182 | {&DDRB, &PINB, &PORTB, 0}, // B0 0
183 | {&DDRB, &PINB, &PORTB, 1}, // B1 1
184 | {&DDRB, &PINB, &PORTB, 2}, // B2 2
185 | {&DDRB, &PINB, &PORTB, 3}, // B3 3
186 | {&DDRB, &PINB, &PORTB, 7}, // B7 4
187 | {&DDRD, &PIND, &PORTD, 0}, // D0 5
188 | {&DDRD, &PIND, &PORTD, 1}, // D1 6
189 | {&DDRD, &PIND, &PORTD, 2}, // D2 7
190 | {&DDRD, &PIND, &PORTD, 3}, // D3 8
191 | {&DDRC, &PINC, &PORTC, 6}, // C6 9
192 | {&DDRC, &PINC, &PORTC, 7}, // C7 10
193 | {&DDRD, &PIND, &PORTD, 6}, // D6 11
194 | {&DDRD, &PIND, &PORTD, 7}, // D7 12
195 | {&DDRB, &PINB, &PORTB, 4}, // B4 13
196 | {&DDRB, &PINB, &PORTB, 5}, // B5 14
197 | {&DDRB, &PINB, &PORTB, 6}, // B6 15
198 | {&DDRF, &PINF, &PORTF, 7}, // F7 16
199 | {&DDRF, &PINF, &PORTF, 6}, // F6 17
200 | {&DDRF, &PINF, &PORTF, 5}, // F5 18
201 | {&DDRF, &PINF, &PORTF, 4}, // F4 19
202 | {&DDRF, &PINF, &PORTF, 1}, // F1 20
203 | {&DDRF, &PINF, &PORTF, 0}, // F0 21
204 | {&DDRD, &PIND, &PORTD, 4}, // D4 22
205 | {&DDRD, &PIND, &PORTD, 5}, // D5 23
206 | {&DDRE, &PINE, &PORTE, 6} // E6 24
207 | };
208 | //------------------------------------------------------------------------------
209 | #elif defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB1286__)
210 | // Teensy++ 1.0 & 2.0
211 |
212 | // Two Wire (aka I2C) ports
213 | uint8_t const SDA_PIN = 1;
214 | uint8_t const SCL_PIN = 0;
215 |
216 | // SPI port
217 | uint8_t const SS_PIN = 20;
218 | uint8_t const MOSI_PIN = 22;
219 | uint8_t const MISO_PIN = 23;
220 | uint8_t const SCK_PIN = 21;
221 |
222 | static const pin_map_t digitalPinMap[] = {
223 | {&DDRD, &PIND, &PORTD, 0}, // D0 0
224 | {&DDRD, &PIND, &PORTD, 1}, // D1 1
225 | {&DDRD, &PIND, &PORTD, 2}, // D2 2
226 | {&DDRD, &PIND, &PORTD, 3}, // D3 3
227 | {&DDRD, &PIND, &PORTD, 4}, // D4 4
228 | {&DDRD, &PIND, &PORTD, 5}, // D5 5
229 | {&DDRD, &PIND, &PORTD, 6}, // D6 6
230 | {&DDRD, &PIND, &PORTD, 7}, // D7 7
231 | {&DDRE, &PINE, &PORTE, 0}, // E0 8
232 | {&DDRE, &PINE, &PORTE, 1}, // E1 9
233 | {&DDRC, &PINC, &PORTC, 0}, // C0 10
234 | {&DDRC, &PINC, &PORTC, 1}, // C1 11
235 | {&DDRC, &PINC, &PORTC, 2}, // C2 12
236 | {&DDRC, &PINC, &PORTC, 3}, // C3 13
237 | {&DDRC, &PINC, &PORTC, 4}, // C4 14
238 | {&DDRC, &PINC, &PORTC, 5}, // C5 15
239 | {&DDRC, &PINC, &PORTC, 6}, // C6 16
240 | {&DDRC, &PINC, &PORTC, 7}, // C7 17
241 | {&DDRE, &PINE, &PORTE, 6}, // E6 18
242 | {&DDRE, &PINE, &PORTE, 7}, // E7 19
243 | {&DDRB, &PINB, &PORTB, 0}, // B0 20
244 | {&DDRB, &PINB, &PORTB, 1}, // B1 21
245 | {&DDRB, &PINB, &PORTB, 2}, // B2 22
246 | {&DDRB, &PINB, &PORTB, 3}, // B3 23
247 | {&DDRB, &PINB, &PORTB, 4}, // B4 24
248 | {&DDRB, &PINB, &PORTB, 5}, // B5 25
249 | {&DDRB, &PINB, &PORTB, 6}, // B6 26
250 | {&DDRB, &PINB, &PORTB, 7}, // B7 27
251 | {&DDRA, &PINA, &PORTA, 0}, // A0 28
252 | {&DDRA, &PINA, &PORTA, 1}, // A1 29
253 | {&DDRA, &PINA, &PORTA, 2}, // A2 30
254 | {&DDRA, &PINA, &PORTA, 3}, // A3 31
255 | {&DDRA, &PINA, &PORTA, 4}, // A4 32
256 | {&DDRA, &PINA, &PORTA, 5}, // A5 33
257 | {&DDRA, &PINA, &PORTA, 6}, // A6 34
258 | {&DDRA, &PINA, &PORTA, 7}, // A7 35
259 | {&DDRE, &PINE, &PORTE, 4}, // E4 36
260 | {&DDRE, &PINE, &PORTE, 5}, // E5 37
261 | {&DDRF, &PINF, &PORTF, 0}, // F0 38
262 | {&DDRF, &PINF, &PORTF, 1}, // F1 39
263 | {&DDRF, &PINF, &PORTF, 2}, // F2 40
264 | {&DDRF, &PINF, &PORTF, 3}, // F3 41
265 | {&DDRF, &PINF, &PORTF, 4}, // F4 42
266 | {&DDRF, &PINF, &PORTF, 5}, // F5 43
267 | {&DDRF, &PINF, &PORTF, 6}, // F6 44
268 | {&DDRF, &PINF, &PORTF, 7} // F7 45
269 | };
270 | //------------------------------------------------------------------------------
271 | #else // defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
272 | // 168 and 328 Arduinos
273 |
274 | // Two Wire (aka I2C) ports
275 | uint8_t const SDA_PIN = 18;
276 | uint8_t const SCL_PIN = 19;
277 |
278 | // SPI port
279 | uint8_t const SS_PIN = 10;
280 | uint8_t const MOSI_PIN = 11;
281 | uint8_t const MISO_PIN = 12;
282 | uint8_t const SCK_PIN = 13;
283 |
284 | static const pin_map_t digitalPinMap[] = {
285 | {&DDRD, &PIND, &PORTD, 0}, // D0 0
286 | {&DDRD, &PIND, &PORTD, 1}, // D1 1
287 | {&DDRD, &PIND, &PORTD, 2}, // D2 2
288 | {&DDRD, &PIND, &PORTD, 3}, // D3 3
289 | {&DDRD, &PIND, &PORTD, 4}, // D4 4
290 | {&DDRD, &PIND, &PORTD, 5}, // D5 5
291 | {&DDRD, &PIND, &PORTD, 6}, // D6 6
292 | {&DDRD, &PIND, &PORTD, 7}, // D7 7
293 | {&DDRB, &PINB, &PORTB, 0}, // B0 8
294 | {&DDRB, &PINB, &PORTB, 1}, // B1 9
295 | {&DDRB, &PINB, &PORTB, 2}, // B2 10
296 | {&DDRB, &PINB, &PORTB, 3}, // B3 11
297 | {&DDRB, &PINB, &PORTB, 4}, // B4 12
298 | {&DDRB, &PINB, &PORTB, 5}, // B5 13
299 | {&DDRC, &PINC, &PORTC, 0}, // C0 14
300 | {&DDRC, &PINC, &PORTC, 1}, // C1 15
301 | {&DDRC, &PINC, &PORTC, 2}, // C2 16
302 | {&DDRC, &PINC, &PORTC, 3}, // C3 17
303 | {&DDRC, &PINC, &PORTC, 4}, // C4 18
304 | {&DDRC, &PINC, &PORTC, 5} // C5 19
305 | };
306 | #endif // defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
307 | //------------------------------------------------------------------------------
308 | static const uint8_t digitalPinCount = sizeof(digitalPinMap)/sizeof(pin_map_t);
309 |
310 | uint8_t badPinNumber(void)
311 | __attribute__((error("Pin number is too large or not a constant")));
312 |
313 | static inline __attribute__((always_inline))
314 | uint8_t getPinMode(uint8_t pin) {
315 | if (__builtin_constant_p(pin) && pin < digitalPinCount) {
316 | return (*digitalPinMap[pin].ddr >> digitalPinMap[pin].bit) & 1;
317 | } else {
318 | return badPinNumber();
319 | }
320 | }
321 | static inline __attribute__((always_inline))
322 | void setPinMode(uint8_t pin, uint8_t mode) {
323 | if (__builtin_constant_p(pin) && pin < digitalPinCount) {
324 | if (mode) {
325 | *digitalPinMap[pin].ddr |= 1 << digitalPinMap[pin].bit;
326 | } else {
327 | *digitalPinMap[pin].ddr &= ~(1 << digitalPinMap[pin].bit);
328 | }
329 | } else {
330 | badPinNumber();
331 | }
332 | }
333 | static inline __attribute__((always_inline))
334 | uint8_t fastDigitalRead(uint8_t pin) {
335 | if (__builtin_constant_p(pin) && pin < digitalPinCount) {
336 | return (*digitalPinMap[pin].pin >> digitalPinMap[pin].bit) & 1;
337 | } else {
338 | return badPinNumber();
339 | }
340 | }
341 | static inline __attribute__((always_inline))
342 | void fastDigitalWrite(uint8_t pin, uint8_t value) {
343 | if (__builtin_constant_p(pin) && pin < digitalPinCount) {
344 | if (value) {
345 | *digitalPinMap[pin].port |= 1 << digitalPinMap[pin].bit;
346 | } else {
347 | *digitalPinMap[pin].port &= ~(1 << digitalPinMap[pin].bit);
348 | }
349 | } else {
350 | badPinNumber();
351 | }
352 | }
353 | #endif // Sd2PinMap_h
354 |
--------------------------------------------------------------------------------
/Sprinter/FatStructs.h:
--------------------------------------------------------------------------------
1 | /* Arduino SdFat Library
2 | * Copyright (C) 2009 by William Greiman
3 | *
4 | * This file is part of the Arduino SdFat Library
5 | *
6 | * This Library is free software: you can redistribute it and/or modify
7 | * it under the terms of the GNU General Public License as published by
8 | * the Free Software Foundation, either version 3 of the License, or
9 | * (at your option) any later version.
10 | *
11 | * This Library is distributed in the hope that it will be useful,
12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | * GNU General Public License for more details.
15 | *
16 | * You should have received a copy of the GNU General Public License
17 | * along with the Arduino SdFat Library. If not, see
18 | * .
19 | */
20 | #ifndef FatStructs_h
21 | #define FatStructs_h
22 | /**
23 | * \file
24 | * FAT file structures
25 | */
26 | /*
27 | * mostly from Microsoft document fatgen103.doc
28 | * http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
29 | */
30 | //------------------------------------------------------------------------------
31 | /** Value for byte 510 of boot block or MBR */
32 | uint8_t const BOOTSIG0 = 0X55;
33 | /** Value for byte 511 of boot block or MBR */
34 | uint8_t const BOOTSIG1 = 0XAA;
35 | //------------------------------------------------------------------------------
36 | /**
37 | * \struct partitionTable
38 | * \brief MBR partition table entry
39 | *
40 | * A partition table entry for a MBR formatted storage device.
41 | * The MBR partition table has four entries.
42 | */
43 | struct partitionTable {
44 | /**
45 | * Boot Indicator . Indicates whether the volume is the active
46 | * partition. Legal values include: 0X00. Do not use for booting.
47 | * 0X80 Active partition.
48 | */
49 | uint8_t boot;
50 | /**
51 | * Head part of Cylinder-head-sector address of the first block in
52 | * the partition. Legal values are 0-255. Only used in old PC BIOS.
53 | */
54 | uint8_t beginHead;
55 | /**
56 | * Sector part of Cylinder-head-sector address of the first block in
57 | * the partition. Legal values are 1-63. Only used in old PC BIOS.
58 | */
59 | unsigned beginSector : 6;
60 | /** High bits cylinder for first block in partition. */
61 | unsigned beginCylinderHigh : 2;
62 | /**
63 | * Combine beginCylinderLow with beginCylinderHigh. Legal values
64 | * are 0-1023. Only used in old PC BIOS.
65 | */
66 | uint8_t beginCylinderLow;
67 | /**
68 | * Partition type. See defines that begin with PART_TYPE_ for
69 | * some Microsoft partition types.
70 | */
71 | uint8_t type;
72 | /**
73 | * head part of cylinder-head-sector address of the last sector in the
74 | * partition. Legal values are 0-255. Only used in old PC BIOS.
75 | */
76 | uint8_t endHead;
77 | /**
78 | * Sector part of cylinder-head-sector address of the last sector in
79 | * the partition. Legal values are 1-63. Only used in old PC BIOS.
80 | */
81 | unsigned endSector : 6;
82 | /** High bits of end cylinder */
83 | unsigned endCylinderHigh : 2;
84 | /**
85 | * Combine endCylinderLow with endCylinderHigh. Legal values
86 | * are 0-1023. Only used in old PC BIOS.
87 | */
88 | uint8_t endCylinderLow;
89 | /** Logical block address of the first block in the partition. */
90 | uint32_t firstSector;
91 | /** Length of the partition, in blocks. */
92 | uint32_t totalSectors;
93 | };
94 | /** Type name for partitionTable */
95 | typedef struct partitionTable part_t;
96 | //------------------------------------------------------------------------------
97 | /**
98 | * \struct masterBootRecord
99 | *
100 | * \brief Master Boot Record
101 | *
102 | * The first block of a storage device that is formatted with a MBR.
103 | */
104 | struct masterBootRecord {
105 | /** Code Area for master boot program. */
106 | uint8_t codeArea[440];
107 | /** Optional WindowsNT disk signature. May contain more boot code. */
108 | uint32_t diskSignature;
109 | /** Usually zero but may be more boot code. */
110 | uint16_t usuallyZero;
111 | /** Partition tables. */
112 | part_t part[4];
113 | /** First MBR signature byte. Must be 0X55 */
114 | uint8_t mbrSig0;
115 | /** Second MBR signature byte. Must be 0XAA */
116 | uint8_t mbrSig1;
117 | };
118 | /** Type name for masterBootRecord */
119 | typedef struct masterBootRecord mbr_t;
120 | //------------------------------------------------------------------------------
121 | /**
122 | * \struct biosParmBlock
123 | *
124 | * \brief BIOS parameter block
125 | *
126 | * The BIOS parameter block describes the physical layout of a FAT volume.
127 | */
128 | struct biosParmBlock {
129 | /**
130 | * Count of bytes per sector. This value may take on only the
131 | * following values: 512, 1024, 2048 or 4096
132 | */
133 | uint16_t bytesPerSector;
134 | /**
135 | * Number of sectors per allocation unit. This value must be a
136 | * power of 2 that is greater than 0. The legal values are
137 | * 1, 2, 4, 8, 16, 32, 64, and 128.
138 | */
139 | uint8_t sectorsPerCluster;
140 | /**
141 | * Number of sectors before the first FAT.
142 | * This value must not be zero.
143 | */
144 | uint16_t reservedSectorCount;
145 | /** The count of FAT data structures on the volume. This field should
146 | * always contain the value 2 for any FAT volume of any type.
147 | */
148 | uint8_t fatCount;
149 | /**
150 | * For FAT12 and FAT16 volumes, this field contains the count of
151 | * 32-byte directory entries in the root directory. For FAT32 volumes,
152 | * this field must be set to 0. For FAT12 and FAT16 volumes, this
153 | * value should always specify a count that when multiplied by 32
154 | * results in a multiple of bytesPerSector. FAT16 volumes should
155 | * use the value 512.
156 | */
157 | uint16_t rootDirEntryCount;
158 | /**
159 | * This field is the old 16-bit total count of sectors on the volume.
160 | * This count includes the count of all sectors in all four regions
161 | * of the volume. This field can be 0; if it is 0, then totalSectors32
162 | * must be non-zero. For FAT32 volumes, this field must be 0. For
163 | * FAT12 and FAT16 volumes, this field contains the sector count, and
164 | * totalSectors32 is 0 if the total sector count fits
165 | * (is less than 0x10000).
166 | */
167 | uint16_t totalSectors16;
168 | /**
169 | * This dates back to the old MS-DOS 1.x media determination and is
170 | * no longer usually used for anything. 0xF8 is the standard value
171 | * for fixed (non-removable) media. For removable media, 0xF0 is
172 | * frequently used. Legal values are 0xF0 or 0xF8-0xFF.
173 | */
174 | uint8_t mediaType;
175 | /**
176 | * Count of sectors occupied by one FAT on FAT12/FAT16 volumes.
177 | * On FAT32 volumes this field must be 0, and sectorsPerFat32
178 | * contains the FAT size count.
179 | */
180 | uint16_t sectorsPerFat16;
181 | /** Sectors per track for interrupt 0x13. Not used otherwise. */
182 | uint16_t sectorsPerTrtack;
183 | /** Number of heads for interrupt 0x13. Not used otherwise. */
184 | uint16_t headCount;
185 | /**
186 | * Count of hidden sectors preceding the partition that contains this
187 | * FAT volume. This field is generally only relevant for media
188 | * visible on interrupt 0x13.
189 | */
190 | uint32_t hidddenSectors;
191 | /**
192 | * This field is the new 32-bit total count of sectors on the volume.
193 | * This count includes the count of all sectors in all four regions
194 | * of the volume. This field can be 0; if it is 0, then
195 | * totalSectors16 must be non-zero.
196 | */
197 | uint32_t totalSectors32;
198 | /**
199 | * Count of sectors occupied by one FAT on FAT32 volumes.
200 | */
201 | uint32_t sectorsPerFat32;
202 | /**
203 | * This field is only defined for FAT32 media and does not exist on
204 | * FAT12 and FAT16 media.
205 | * Bits 0-3 -- Zero-based number of active FAT.
206 | * Only valid if mirroring is disabled.
207 | * Bits 4-6 -- Reserved.
208 | * Bit 7 -- 0 means the FAT is mirrored at runtime into all FATs.
209 | * -- 1 means only one FAT is active; it is the one referenced in bits 0-3.
210 | * Bits 8-15 -- Reserved.
211 | */
212 | uint16_t fat32Flags;
213 | /**
214 | * FAT32 version. High byte is major revision number.
215 | * Low byte is minor revision number. Only 0.0 define.
216 | */
217 | uint16_t fat32Version;
218 | /**
219 | * Cluster number of the first cluster of the root directory for FAT32.
220 | * This usually 2 but not required to be 2.
221 | */
222 | uint32_t fat32RootCluster;
223 | /**
224 | * Sector number of FSINFO structure in the reserved area of the
225 | * FAT32 volume. Usually 1.
226 | */
227 | uint16_t fat32FSInfo;
228 | /**
229 | * If non-zero, indicates the sector number in the reserved area
230 | * of the volume of a copy of the boot record. Usually 6.
231 | * No value other than 6 is recommended.
232 | */
233 | uint16_t fat32BackBootBlock;
234 | /**
235 | * Reserved for future expansion. Code that formats FAT32 volumes
236 | * should always set all of the bytes of this field to 0.
237 | */
238 | uint8_t fat32Reserved[12];
239 | };
240 | /** Type name for biosParmBlock */
241 | typedef struct biosParmBlock bpb_t;
242 | //------------------------------------------------------------------------------
243 | /**
244 | * \struct fat32BootSector
245 | *
246 | * \brief Boot sector for a FAT16 or FAT32 volume.
247 | *
248 | */
249 | struct fat32BootSector {
250 | /** X86 jmp to boot program */
251 | uint8_t jmpToBootCode[3];
252 | /** informational only - don't depend on it */
253 | char oemName[8];
254 | /** BIOS Parameter Block */
255 | bpb_t bpb;
256 | /** for int0x13 use value 0X80 for hard drive */
257 | uint8_t driveNumber;
258 | /** used by Windows NT - should be zero for FAT */
259 | uint8_t reserved1;
260 | /** 0X29 if next three fields are valid */
261 | uint8_t bootSignature;
262 | /** usually generated by combining date and time */
263 | uint32_t volumeSerialNumber;
264 | /** should match volume label in root dir */
265 | char volumeLabel[11];
266 | /** informational only - don't depend on it */
267 | char fileSystemType[8];
268 | /** X86 boot code */
269 | uint8_t bootCode[420];
270 | /** must be 0X55 */
271 | uint8_t bootSectorSig0;
272 | /** must be 0XAA */
273 | uint8_t bootSectorSig1;
274 | };
275 | //------------------------------------------------------------------------------
276 | // End Of Chain values for FAT entries
277 | /** FAT16 end of chain value used by Microsoft. */
278 | uint16_t const FAT16EOC = 0XFFFF;
279 | /** Minimum value for FAT16 EOC. Use to test for EOC. */
280 | uint16_t const FAT16EOC_MIN = 0XFFF8;
281 | /** FAT32 end of chain value used by Microsoft. */
282 | uint32_t const FAT32EOC = 0X0FFFFFFF;
283 | /** Minimum value for FAT32 EOC. Use to test for EOC. */
284 | uint32_t const FAT32EOC_MIN = 0X0FFFFFF8;
285 | /** Mask a for FAT32 entry. Entries are 28 bits. */
286 | uint32_t const FAT32MASK = 0X0FFFFFFF;
287 |
288 | /** Type name for fat32BootSector */
289 | typedef struct fat32BootSector fbs_t;
290 | //------------------------------------------------------------------------------
291 | /**
292 | * \struct directoryEntry
293 | * \brief FAT short directory entry
294 | *
295 | * Short means short 8.3 name, not the entry size.
296 | *
297 | * Date Format. A FAT directory entry date stamp is a 16-bit field that is
298 | * basically a date relative to the MS-DOS epoch of 01/01/1980. Here is the
299 | * format (bit 0 is the LSB of the 16-bit word, bit 15 is the MSB of the
300 | * 16-bit word):
301 | *
302 | * Bits 9-15: Count of years from 1980, valid value range 0-127
303 | * inclusive (1980-2107).
304 | *
305 | * Bits 5-8: Month of year, 1 = January, valid value range 1-12 inclusive.
306 | *
307 | * Bits 0-4: Day of month, valid value range 1-31 inclusive.
308 | *
309 | * Time Format. A FAT directory entry time stamp is a 16-bit field that has
310 | * a granularity of 2 seconds. Here is the format (bit 0 is the LSB of the
311 | * 16-bit word, bit 15 is the MSB of the 16-bit word).
312 | *
313 | * Bits 11-15: Hours, valid value range 0-23 inclusive.
314 | *
315 | * Bits 5-10: Minutes, valid value range 0-59 inclusive.
316 | *
317 | * Bits 0-4: 2-second count, valid value range 0-29 inclusive (0 - 58 seconds).
318 | *
319 | * The valid time range is from Midnight 00:00:00 to 23:59:58.
320 | */
321 | struct directoryEntry {
322 | /**
323 | * Short 8.3 name.
324 | * The first eight bytes contain the file name with blank fill.
325 | * The last three bytes contain the file extension with blank fill.
326 | */
327 | uint8_t name[11];
328 | /** Entry attributes.
329 | *
330 | * The upper two bits of the attribute byte are reserved and should
331 | * always be set to 0 when a file is created and never modified or
332 | * looked at after that. See defines that begin with DIR_ATT_.
333 | */
334 | uint8_t attributes;
335 | /**
336 | * Reserved for use by Windows NT. Set value to 0 when a file is
337 | * created and never modify or look at it after that.
338 | */
339 | uint8_t reservedNT;
340 | /**
341 | * The granularity of the seconds part of creationTime is 2 seconds
342 | * so this field is a count of tenths of a second and its valid
343 | * value range is 0-199 inclusive. (WHG note - seems to be hundredths)
344 | */
345 | uint8_t creationTimeTenths;
346 | /** Time file was created. */
347 | uint16_t creationTime;
348 | /** Date file was created. */
349 | uint16_t creationDate;
350 | /**
351 | * Last access date. Note that there is no last access time, only
352 | * a date. This is the date of last read or write. In the case of
353 | * a write, this should be set to the same date as lastWriteDate.
354 | */
355 | uint16_t lastAccessDate;
356 | /**
357 | * High word of this entry's first cluster number (always 0 for a
358 | * FAT12 or FAT16 volume).
359 | */
360 | uint16_t firstClusterHigh;
361 | /** Time of last write. File creation is considered a write. */
362 | uint16_t lastWriteTime;
363 | /** Date of last write. File creation is considered a write. */
364 | uint16_t lastWriteDate;
365 | /** Low word of this entry's first cluster number. */
366 | uint16_t firstClusterLow;
367 | /** 32-bit unsigned holding this file's size in bytes. */
368 | uint32_t fileSize;
369 | };
370 | //------------------------------------------------------------------------------
371 | // Definitions for directory entries
372 | //
373 | /** Type name for directoryEntry */
374 | typedef struct directoryEntry dir_t;
375 | /** escape for name[0] = 0XE5 */
376 | uint8_t const DIR_NAME_0XE5 = 0X05;
377 | /** name[0] value for entry that is free after being "deleted" */
378 | uint8_t const DIR_NAME_DELETED = 0XE5;
379 | /** name[0] value for entry that is free and no allocated entries follow */
380 | uint8_t const DIR_NAME_FREE = 0X00;
381 | /** file is read-only */
382 | uint8_t const DIR_ATT_READ_ONLY = 0X01;
383 | /** File should hidden in directory listings */
384 | uint8_t const DIR_ATT_HIDDEN = 0X02;
385 | /** Entry is for a system file */
386 | uint8_t const DIR_ATT_SYSTEM = 0X04;
387 | /** Directory entry contains the volume label */
388 | uint8_t const DIR_ATT_VOLUME_ID = 0X08;
389 | /** Entry is for a directory */
390 | uint8_t const DIR_ATT_DIRECTORY = 0X10;
391 | /** Old DOS archive bit for backup support */
392 | uint8_t const DIR_ATT_ARCHIVE = 0X20;
393 | /** Test value for long name entry. Test is
394 | (d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME. */
395 | uint8_t const DIR_ATT_LONG_NAME = 0X0F;
396 | /** Test mask for long name entry */
397 | uint8_t const DIR_ATT_LONG_NAME_MASK = 0X3F;
398 | /** defined attribute bits */
399 | uint8_t const DIR_ATT_DEFINED_BITS = 0X3F;
400 | /** Directory entry is part of a long name */
401 | static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) {
402 | return (dir->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME;
403 | }
404 | /** Mask for file/subdirectory tests */
405 | uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
406 | /** Directory entry is for a file */
407 | static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
408 | return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0;
409 | }
410 | /** Directory entry is for a subdirectory */
411 | static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
412 | return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY;
413 | }
414 | /** Directory entry is for a file or subdirectory */
415 | static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) {
416 | return (dir->attributes & DIR_ATT_VOLUME_ID) == 0;
417 | }
418 | #endif // FatStructs_h
419 |
--------------------------------------------------------------------------------
/Sprinter/Configuration.h:
--------------------------------------------------------------------------------
1 | #ifndef CONFIGURATION_H
2 | #define CONFIGURATION_H
3 |
4 | // BASIC SETTINGS: select your board type, thermistor type, axis scaling, and endstop configuration
5 |
6 | //// The following define selects which electronics board you have. Please choose the one that matches your setup
7 | // MEGA/RAMPS up to 1.2 = 3,
8 | // RAMPS 1.3/1.4 = 33
9 | // Gen6 = 5,
10 | // Gen6 deluxe = 51
11 | // Sanguinololu up to 1.1 = 6
12 | // Sanguinololu 1.2 and above = 62
13 | // Gen 7 @ 16MHZ only= 7
14 | // Gen 7 @ 20MHZ only= 71
15 | // Teensylu (at90usb) = 8
16 | // Printrboard Rev. B (ATMEGA90USB1286) = 9
17 | // Gen 3 Plus = 21
18 | // gen 3 Monolithic Electronics = 22
19 | // Gen3 PLUS for TechZone Gen3 Remix Motherboard = 23
20 | #define MOTHERBOARD 33
21 |
22 | //// Thermistor settings:
23 | // 1 is 100k thermistor
24 | // 2 is 200k thermistor
25 | // 3 is mendel-parts thermistor
26 | // 4 is 10k thermistor
27 | // 5 is ParCan supplied 104GT-2 100K
28 | // 6 is EPCOS 100k
29 | // 7 is 100k Honeywell thermistor 135-104LAG-J01
30 | #define THERMISTORHEATER 1
31 | #define THERMISTORBED 1
32 |
33 | //// Calibration variables
34 | // X, Y, Z, E steps per unit - Metric Prusa Mendel with Wade extruder:
35 | #define _AXIS_STEP_PER_UNIT {80, 80, 3200/1.25,700}
36 | // Metric Prusa Mendel with Makergear geared stepper extruder:
37 | //#define _AXIS_STEP_PER_UNIT {80,80,3200/1.25,1380}
38 | // MakerGear Hybrid Prusa Mendel:
39 | // Z axis value is for .9 stepper(if you have 1.8 steppers for Z, you need to use 2272.7272)
40 | //#define _AXIS_STEP_PER_UNIT {104.987, 104.987, 4545.4544, 1487}
41 |
42 |
43 | //// Endstop Settings
44 | #define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
45 | // The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
46 | //If your axes are only moving in one direction, make sure the endstops are connected properly.
47 | //If your axes move in one direction ONLY when the endstops are triggered, set [XYZ]_ENDSTOP_INVERT to true here:
48 | const bool X_ENDSTOP_INVERT = false;
49 | const bool Y_ENDSTOP_INVERT = false;
50 | const bool Z_ENDSTOP_INVERT = false;
51 |
52 | // This determines the communication speed of the printer
53 | #define BAUDRATE 115200
54 | //#define BAUDRATE 250000
55 |
56 | // Comment out (using // at the start of the line) to disable SD support:
57 | #define SDSUPPORT
58 |
59 | // Uncomment to make run init.g from SD on boot
60 | //#define SDINITFILE
61 |
62 | //Only work with Atmega1284 you need +1 kb ram
63 | //#define SD_FAST_XFER_AKTIV
64 |
65 | //-----------------------------------------------------------------------
66 | //// STORE SETTINGS TO EEPROM
67 | //-----------------------------------------------------------------------
68 | // the microcontroller can store settings in the EEPROM
69 | // M500 - stores paramters in EEPROM
70 | // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
71 | // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
72 | // M503 - Print settings
73 | // define this to enable eeprom support
74 | //#define USE_EEPROM_SETTINGS
75 |
76 | // to disable EEPROM Serial responses and decrease program space by ~1000 byte: comment this out:
77 | // please keep turned on if you can.
78 | //#define PRINT_EEPROM_SETTING
79 |
80 | //-----------------------------------------------------------------------
81 | //// ARC Function (G2/G3 Command)
82 | //-----------------------------------------------------------------------
83 | //Uncomment to aktivate the arc (circle) function (G2/G3 Command)
84 | //Without SD function an ARC function the used Flash is smaller 31 kb
85 | #define USE_ARC_FUNCTION
86 |
87 | //-----------------------------------------------------------------------
88 | //// ADVANCED SETTINGS - to tweak parameters
89 | //-----------------------------------------------------------------------
90 |
91 | #ifdef SDSUPPORT
92 | #ifdef SD_FAST_XFER_AKTIV
93 | //Fast transfer chunk size (> 1024 is unstable, change at your own risk).
94 | #define SD_FAST_XFER_CHUNK_SIZE 1024
95 | #endif
96 | #endif
97 |
98 | //-----------------------------------------------------------------------
99 | // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
100 | //-----------------------------------------------------------------------
101 | #define X_ENABLE_ON 0
102 | #define Y_ENABLE_ON 0
103 | #define Z_ENABLE_ON 0
104 | #define E_ENABLE_ON 0
105 |
106 | //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
107 | //#define DELAY_ENABLE 15
108 |
109 | //-----------------------------------------------------------------------
110 | // Disables axis when it's not being used.
111 | //-----------------------------------------------------------------------
112 | const bool DISABLE_X = false;
113 | const bool DISABLE_Y = false;
114 | const bool DISABLE_Z = true;
115 | const bool DISABLE_E = false;
116 |
117 | //-----------------------------------------------------------------------
118 | // Inverting axis direction
119 | //-----------------------------------------------------------------------
120 | const bool INVERT_X_DIR = false;
121 | const bool INVERT_Y_DIR = false;
122 | const bool INVERT_Z_DIR = true;
123 | const bool INVERT_E_DIR = false;
124 |
125 | //-----------------------------------------------------------------------
126 | //// ENDSTOP SETTINGS:
127 | //-----------------------------------------------------------------------
128 | // Sets direction of endstops when homing; 1=MAX, -1=MIN
129 | #define X_HOME_DIR -1
130 | #define Y_HOME_DIR -1
131 | #define Z_HOME_DIR -1
132 |
133 | //#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
134 |
135 | const bool min_software_endstops = false; //If true, axis won't move to coordinates less than zero.
136 | const bool max_software_endstops = true; //If true, axis won't move to coordinates greater than the defined lengths below.
137 |
138 |
139 | //-----------------------------------------------------------------------
140 | //Max Length for Prusa Mendel, check the ways of your axis and set this Values
141 | //-----------------------------------------------------------------------
142 | const int X_MAX_LENGTH = 200;
143 | const int Y_MAX_LENGTH = 200;
144 | const int Z_MAX_LENGTH = 100;
145 |
146 | //-----------------------------------------------------------------------
147 | //// MOVEMENT SETTINGS
148 | //-----------------------------------------------------------------------
149 | const int NUM_AXIS = 4; // The axis order in all axis related arrays is X, Y, Z, E
150 | #define _MAX_FEEDRATE {400, 400, 2, 45} // (mm/sec)
151 | #define _HOMING_FEEDRATE {1500,1500,120} // (mm/min) !!
152 | #define _AXIS_RELATIVE_MODES {false, false, false, false}
153 |
154 | #define MAX_STEP_FREQUENCY 30000 // Max step frequency
155 |
156 | //For the retract (negative Extruder) move this maxiumum Limit of Feedrate is used
157 | //The next positive Extruder move use also this Limit,
158 | //then for the next (second after retract) move the original Maximum (_MAX_FEEDRATE) Limit is used
159 | #define MAX_RETRACT_FEEDRATE 100 //mm/sec
160 |
161 | //-----------------------------------------------------------------------
162 | //// Not used at the Moment
163 | //-----------------------------------------------------------------------
164 |
165 | // Min step delay in microseconds. If you are experiencing missing steps, try to raise the delay microseconds, but be aware this
166 | // If you enable this, make sure STEP_DELAY_RATIO is disabled.
167 | //#define STEP_DELAY_MICROS 1
168 |
169 | // Step delay over interval ratio. If you are still experiencing missing steps, try to uncomment the following line, but be aware this
170 | // If you enable this, make sure STEP_DELAY_MICROS is disabled. (except for Gen6: both need to be enabled.)
171 | //#define STEP_DELAY_RATIO 0.25
172 |
173 | ///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.
174 | // At this Version with Planner this Function ist not used
175 | //#define RAPID_OSCILLATION_REDUCTION
176 |
177 | #ifdef RAPID_OSCILLATION_REDUCTION
178 | const long min_time_before_dir_change = 30; //milliseconds
179 | #endif
180 |
181 | //-----------------------------------------------------------------------
182 | //// Acceleration settings
183 | //-----------------------------------------------------------------------
184 | // 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.
185 | #define _ACCELERATION 1000 // Axis Normal acceleration mm/s^2
186 | #define _RETRACT_ACCELERATION 2000 // Extruder Normal acceleration mm/s^2
187 | #define _MAX_XY_JERK 20.0
188 | #define _MAX_Z_JERK 0.4
189 | #define _MAX_E_JERK 5.0 // (mm/sec)
190 | //#define _MAX_START_SPEED_UNITS_PER_SECOND {25.0,25.0,0.2,10.0}
191 | #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
192 |
193 |
194 | // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
195 | // of the buffer and all stops. This should not be much greater than zero and should only be changed
196 | // if unwanted behavior is observed on a user's machine when running at very slow speeds.
197 | #define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
198 |
199 | #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
200 | #define DEFAULT_MINTRAVELFEEDRATE 0.0
201 |
202 | #define _MIN_SEG_TIME 20000
203 |
204 | // If defined the movements slow down when the look ahead buffer is only half full
205 | #define SLOWDOWN
206 |
207 |
208 | const int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
209 |
210 | //-----------------------------------------------------------------------
211 | // Machine UUID
212 | //-----------------------------------------------------------------------
213 | // This may be useful if you have multiple machines and wish to identify them by using the M115 command.
214 | // By default we set it to zeros.
215 | #define _DEF_CHAR_UUID "00000000-0000-0000-0000-000000000000"
216 |
217 |
218 |
219 | //-----------------------------------------------------------------------
220 | //// Planner buffer Size
221 | //-----------------------------------------------------------------------
222 |
223 | // The number of linear motions that can be in the plan at any give time
224 | // if the SD Card need to much memory reduce the Values for Plannerpuffer (base of 2)
225 | #ifdef SDSUPPORT
226 | #define BLOCK_BUFFER_SIZE 16
227 | #define BLOCK_BUFFER_MASK 0x0f
228 | #else
229 | #define BLOCK_BUFFER_SIZE 16
230 | #define BLOCK_BUFFER_MASK 0x0f
231 | #endif
232 |
233 | //-----------------------------------------------------------------------
234 | //// SETTINGS FOR ARC FUNCTION (Command G2/G2)
235 | //-----------------------------------------------------------------------
236 |
237 | // Arc interpretation settings:
238 | //Step to split a cirrcle in small Lines
239 | #define MM_PER_ARC_SEGMENT 1
240 | //After this count of steps a new SIN / COS caluclation is startet to correct the circle interpolation
241 | #define N_ARC_CORRECTION 25
242 |
243 | //-----------------------------------------------------------------------
244 | //// FANCONTROL WITH SOFT PWM
245 | //-----------------------------------------------------------------------
246 |
247 | //With this option its possible to drive the fan with SOFT PWM (500hz) and use
248 | //every Digital output for it, main usage for Sanguinololu
249 | #define FAN_SOFT_PWM
250 |
251 | //-----------------------------------------------------------------------
252 | //// MINIMUM START SPEED FOR FAN
253 | //-----------------------------------------------------------------------
254 |
255 | //Minimum start speed for FAN when the last speed was zero
256 | //Set to 0 to deaktivate
257 | //If value is set the fan will drive with this minimum speed for MINIMUM_FAN_START_TIME
258 | #define MINIMUM_FAN_START_SPEED 0
259 |
260 | //This is the time how long the minimum FAN speed is set
261 | #define MINIMUM_FAN_START_TIME 6000 //6sec
262 |
263 | //-----------------------------------------------------------------------
264 | //// HEATERCONTROL AND PID PARAMETERS
265 | //-----------------------------------------------------------------------
266 |
267 | //Testfunction to adjust the Hotend temperatur in case of Printingspeed
268 | //If the Printer print slow the Temp is going to AUTO_TEMP_MIN
269 | //At the moment this Value dont change the targettemp from the Hotend
270 | //The result of this function is only send with the Temperaturerequest to the host
271 | //#define AUTOTEMP
272 | #ifdef AUTOTEMP
273 | #define AUTO_TEMP_MAX 240
274 | #define AUTO_TEMP_MIN 205
275 | #define AUTO_TEMP_FACTOR 0.025
276 | #define AUTOTEMP_OLDWEIGHT 0.98
277 | #endif
278 |
279 | //// AD595 THERMOCOUPLE SUPPORT UNTESTED... USE WITH CAUTION!!!!
280 |
281 | //// PID settings:
282 | // Uncomment the following line to enable PID support. This is untested and could be disastrous. Be careful.
283 | #define PIDTEMP 1
284 | #ifdef PIDTEMP
285 | //Sanguinololu 1.2 and above, the PWM Output Hotend Timer 1 is used for the Hardware PWM
286 | //but in this Software use Timer1 for the Stepperfunction so it is not possible to use the "analogWrite" function.
287 | //This Soft PWM use Timer 2 with 400 Hz to drive the PWM for the hotend
288 | #define PID_SOFT_PWM
289 |
290 | //Measure the MIN/MAX Value of the Hotend Temp and show it with
291 | //Command M601 / Command M602 Reset the MIN/MAX Value
292 | //#define DEBUG_HEATER_TEMP
293 |
294 | // M303 - PID relay autotune S sets the target temperature.
295 | // (default target temperature = 150C)
296 | #define PID_AUTOTUNE
297 |
298 | //PID Controler Settings
299 | #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
300 | #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
301 | #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?)
302 | #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
303 |
304 | // 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
305 | // for my makergear hot-end: linear fit {50,10},{60,20},{80,30},{105,50},{176,100},{128,64},{208,128}
306 | #define HEATER_DUTY_FOR_SETPOINT(setpoint) ((int)((187L*(long)setpoint)>>8)-27)
307 | // magic formula 2, to make led brightness approximately linear
308 | #define LED_PWM_FOR_BRIGHTNESS(brightness) ((64*brightness-1384)/(300-brightness))
309 | #endif
310 |
311 | // Change this value (range 30-255) to limit the current to the nozzle
312 | #define HEATER_CURRENT 255
313 |
314 | // How often should the heater check for new temp readings, in milliseconds
315 | #define HEATER_CHECK_INTERVAL 500
316 | #define BED_CHECK_INTERVAL 5000
317 |
318 | // Comment the following line to enable heat management during acceleration
319 | #define DISABLE_CHECK_DURING_ACC
320 | #ifndef DISABLE_CHECK_DURING_ACC
321 | // Uncomment the following line to disable heat management during moves
322 | //#define DISABLE_CHECK_DURING_MOVE
323 | #endif
324 |
325 | // 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.
326 | // Probably this should remain commented if are using PID.
327 | // It also defines the max milliseconds interval after which a travel move is not considered so for the sake of this feature.
328 | #define DISABLE_CHECK_DURING_TRAVEL 1000
329 |
330 | //// Temperature smoothing - only uncomment this if your temp readings are noisy (Gen6 without EvdZ's 5V hack)
331 | //#define SMOOTHING
332 | //#define SMOOTHFACTOR 16 //best to use a power of two here - determines how many values are averaged together by the smoothing algorithm
333 |
334 |
335 | //// Experimental watchdog and minimal temp
336 | // The watchdog waits for the watchperiod in milliseconds whenever an M104 or M109 increases the target temperature
337 | // 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
338 | //#define WATCHPERIOD 5000 //5 seconds
339 |
340 | // Actual temperature must be close to target for this long before M109 returns success
341 | //#define TEMP_RESIDENCY_TIME 20 // (seconds)
342 | //#define TEMP_HYSTERESIS 5 // (C°) range of +/- temperatures considered "close" to the target one
343 |
344 | //// The minimal temperature defines the temperature below which the heater will not be enabled
345 | #define MINTEMP 5
346 |
347 | //// Experimental max temp
348 | // When temperature exceeds max temp, your heater will be switched off.
349 | // This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
350 | // You should use MINTEMP for thermistor short/failure protection.
351 | #define MAXTEMP 275
352 |
353 | // Select one of these only to define how the nozzle temp is read.
354 | #define HEATER_USES_THERMISTOR
355 | //#define HEATER_USES_AD595
356 | //#define HEATER_USES_MAX6675
357 |
358 | // Select one of these only to define how the bed temp is read.
359 | #define BED_USES_THERMISTOR
360 | //#define BED_USES_AD595
361 |
362 | //This is for controlling a fan to cool down the stepper drivers
363 | //it will turn on when any driver is enabled
364 | //and turn off after the set amount of seconds from last driver being disabled again
365 | //#define CONTROLLERFAN_PIN 23 //Pin used for the fan to cool controller, comment out to disable this function
366 | #define CONTROLLERFAN_SEC 60 //How many seconds, after all motors were disabled, the fan should run
367 |
368 | //This is for controlling a fan that will keep the extruder cool.
369 | //#define EXTRUDERFAN_PIN 66 //Pin used to control the fan, comment out to disable this function
370 | #define EXTRUDERFAN_DEC 50 //Hotend temperature from where the fan will be turned on
371 |
372 | //#define CHAIN_OF_COMMAND 1 //Finish buffered moves before executing M42, fan speed, heater target, and so...
373 |
374 | //-----------------------------------------------------------------------
375 | // DEBUGING
376 | //-----------------------------------------------------------------------
377 |
378 |
379 | //Uncomment this to see on the host if a wrong or unknown Command is recived
380 | //Only for Testing !!!
381 | //#define SEND_WRONG_CMD_INFO
382 |
383 | // Uncomment the following line to enable debugging. You can better control debugging below the following line
384 | //#define DEBUG
385 | #ifdef DEBUG
386 | //#define DEBUG_PREPARE_MOVE //Enable this to debug prepare_move() function
387 | //#define DEBUG_MOVE_TIME //Enable this to time each move and print the result
388 | //#define DEBUG_HEAT_MGMT //Enable this to debug heat management. WARNING, this will cause axes to jitter!
389 | //#define DEBUG_DISABLE_CHECK_DURING_TRAVEL //Debug the namesake feature, see above in this file
390 | #endif
391 |
392 | #endif
393 |
--------------------------------------------------------------------------------
/Sprinter/Sd2Card.cpp:
--------------------------------------------------------------------------------
1 | /* Arduino Sd2Card Library
2 | * Copyright (C) 2009 by William Greiman
3 | *
4 | * This file is part of the Arduino Sd2Card Library
5 | *
6 | * This Library is free software: you can redistribute it and/or modify
7 | * it under the terms of the GNU General Public License as published by
8 | * the Free Software Foundation, either version 3 of the License, or
9 | * (at your option) any later version.
10 | *
11 | * This Library is distributed in the hope that it will be useful,
12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | * GNU General Public License for more details.
15 | *
16 | * You should have received a copy of the GNU General Public License
17 | * along with the Arduino Sd2Card Library. If not, see
18 | * .
19 | */
20 | #if defined(ARDUINO) && ARDUINO >= 100
21 | #include
22 | #else
23 | #include
24 | #endif
25 | #include "Sd2Card.h"
26 | //------------------------------------------------------------------------------
27 | #ifndef SOFTWARE_SPI
28 | // functions for hardware SPI
29 | /** Send a byte to the card */
30 | static void spiSend(uint8_t b) {
31 | SPDR = b;
32 | while (!(SPSR & (1 << SPIF)));
33 | }
34 | /** Receive a byte from the card */
35 | static uint8_t spiRec(void) {
36 | spiSend(0XFF);
37 | return SPDR;
38 | }
39 | #else // SOFTWARE_SPI
40 | //------------------------------------------------------------------------------
41 | /** nop to tune soft SPI timing */
42 | #define nop asm volatile ("nop\n\t")
43 | //------------------------------------------------------------------------------
44 | /** Soft SPI receive */
45 | uint8_t spiRec(void) {
46 | uint8_t data = 0;
47 | // no interrupts during byte receive - about 8 us
48 | cli();
49 | // output pin high - like sending 0XFF
50 | fastDigitalWrite(SPI_MOSI_PIN, HIGH);
51 |
52 | for (uint8_t i = 0; i < 8; i++) {
53 | fastDigitalWrite(SPI_SCK_PIN, HIGH);
54 |
55 | // adjust so SCK is nice
56 | nop;
57 | nop;
58 |
59 | data <<= 1;
60 |
61 | if (fastDigitalRead(SPI_MISO_PIN)) data |= 1;
62 |
63 | fastDigitalWrite(SPI_SCK_PIN, LOW);
64 | }
65 | // enable interrupts
66 | sei();
67 | return data;
68 | }
69 | //------------------------------------------------------------------------------
70 | /** Soft SPI send */
71 | void spiSend(uint8_t data) {
72 | // no interrupts during byte send - about 8 us
73 | cli();
74 | for (uint8_t i = 0; i < 8; i++) {
75 | fastDigitalWrite(SPI_SCK_PIN, LOW);
76 |
77 | fastDigitalWrite(SPI_MOSI_PIN, data & 0X80);
78 |
79 | data <<= 1;
80 |
81 | fastDigitalWrite(SPI_SCK_PIN, HIGH);
82 | }
83 | // hold SCK high for a few ns
84 | nop;
85 | nop;
86 | nop;
87 | nop;
88 |
89 | fastDigitalWrite(SPI_SCK_PIN, LOW);
90 | // enable interrupts
91 | sei();
92 | }
93 | #endif // SOFTWARE_SPI
94 | //------------------------------------------------------------------------------
95 | // send command and return error code. Return zero for OK
96 | uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) {
97 | // end read if in partialBlockRead mode
98 | readEnd();
99 |
100 | // select card
101 | chipSelectLow();
102 |
103 | // wait up to 300 ms if busy
104 | waitNotBusy(300);
105 |
106 | // send command
107 | spiSend(cmd | 0x40);
108 |
109 | // send argument
110 | for (int8_t s = 24; s >= 0; s -= 8) spiSend(arg >> s);
111 |
112 | // send CRC
113 | uint8_t crc = 0XFF;
114 | if (cmd == CMD0) crc = 0X95; // correct crc for CMD0 with arg 0
115 | if (cmd == CMD8) crc = 0X87; // correct crc for CMD8 with arg 0X1AA
116 | spiSend(crc);
117 |
118 | // wait for response
119 | for (uint8_t i = 0; ((status_ = spiRec()) & 0X80) && i != 0XFF; i++);
120 | return status_;
121 | }
122 | //------------------------------------------------------------------------------
123 | /**
124 | * Determine the size of an SD flash memory card.
125 | *
126 | * \return The number of 512 byte data blocks in the card
127 | * or zero if an error occurs.
128 | */
129 | uint32_t Sd2Card::cardSize(void) {
130 | csd_t csd;
131 | if (!readCSD(&csd)) return 0;
132 | if (csd.v1.csd_ver == 0) {
133 | uint8_t read_bl_len = csd.v1.read_bl_len;
134 | uint16_t c_size = (csd.v1.c_size_high << 10)
135 | | (csd.v1.c_size_mid << 2) | csd.v1.c_size_low;
136 | uint8_t c_size_mult = (csd.v1.c_size_mult_high << 1)
137 | | csd.v1.c_size_mult_low;
138 | return (uint32_t)(c_size + 1) << (c_size_mult + read_bl_len - 7);
139 | } else if (csd.v2.csd_ver == 1) {
140 | uint32_t c_size = ((uint32_t)csd.v2.c_size_high << 16)
141 | | (csd.v2.c_size_mid << 8) | csd.v2.c_size_low;
142 | return (c_size + 1) << 10;
143 | } else {
144 | error(SD_CARD_ERROR_BAD_CSD);
145 | return 0;
146 | }
147 | }
148 | //------------------------------------------------------------------------------
149 | void Sd2Card::chipSelectHigh(void) {
150 | digitalWrite(chipSelectPin_, HIGH);
151 | }
152 | //------------------------------------------------------------------------------
153 | void Sd2Card::chipSelectLow(void) {
154 | digitalWrite(chipSelectPin_, LOW);
155 | }
156 | //------------------------------------------------------------------------------
157 | /** Erase a range of blocks.
158 | *
159 | * \param[in] firstBlock The address of the first block in the range.
160 | * \param[in] lastBlock The address of the last block in the range.
161 | *
162 | * \note This function requests the SD card to do a flash erase for a
163 | * range of blocks. The data on the card after an erase operation is
164 | * either 0 or 1, depends on the card vendor. The card must support
165 | * single block erase.
166 | *
167 | * \return The value one, true, is returned for success and
168 | * the value zero, false, is returned for failure.
169 | */
170 | uint8_t Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
171 | if (!eraseSingleBlockEnable()) {
172 | error(SD_CARD_ERROR_ERASE_SINGLE_BLOCK);
173 | goto fail;
174 | }
175 | if (type_ != SD_CARD_TYPE_SDHC) {
176 | firstBlock <<= 9;
177 | lastBlock <<= 9;
178 | }
179 | if (cardCommand(CMD32, firstBlock)
180 | || cardCommand(CMD33, lastBlock)
181 | || cardCommand(CMD38, 0)) {
182 | error(SD_CARD_ERROR_ERASE);
183 | goto fail;
184 | }
185 | if (!waitNotBusy(SD_ERASE_TIMEOUT)) {
186 | error(SD_CARD_ERROR_ERASE_TIMEOUT);
187 | goto fail;
188 | }
189 | chipSelectHigh();
190 | return true;
191 |
192 | fail:
193 | chipSelectHigh();
194 | return false;
195 | }
196 | //------------------------------------------------------------------------------
197 | /** Determine if card supports single block erase.
198 | *
199 | * \return The value one, true, is returned if single block erase is supported.
200 | * The value zero, false, is returned if single block erase is not supported.
201 | */
202 | uint8_t Sd2Card::eraseSingleBlockEnable(void) {
203 | csd_t csd;
204 | return readCSD(&csd) ? csd.v1.erase_blk_en : 0;
205 | }
206 | //------------------------------------------------------------------------------
207 | /**
208 | * Initialize an SD flash memory card.
209 | *
210 | * \param[in] sckRateID SPI clock rate selector. See setSckRate().
211 | * \param[in] chipSelectPin SD chip select pin number.
212 | *
213 | * \return The value one, true, is returned for success and
214 | * the value zero, false, is returned for failure. The reason for failure
215 | * can be determined by calling errorCode() and errorData().
216 | */
217 | uint8_t Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
218 | errorCode_ = inBlock_ = partialBlockRead_ = type_ = 0;
219 | chipSelectPin_ = chipSelectPin;
220 | // 16-bit init start time allows over a minute
221 | uint16_t t0 = (uint16_t)millis();
222 | uint32_t arg;
223 |
224 | // set pin modes
225 | pinMode(chipSelectPin_, OUTPUT);
226 | chipSelectHigh();
227 | pinMode(SPI_MISO_PIN, INPUT);
228 | pinMode(SPI_MOSI_PIN, OUTPUT);
229 | pinMode(SPI_SCK_PIN, OUTPUT);
230 |
231 | #ifndef SOFTWARE_SPI
232 | // SS must be in output mode even it is not chip select
233 | pinMode(SS_PIN, OUTPUT);
234 | // Enable SPI, Master, clock rate f_osc/128
235 | SPCR = (1 << SPE) | (1 << MSTR) | (1 << SPR1) | (1 << SPR0);
236 | // clear double speed
237 | SPSR &= ~(1 << SPI2X);
238 | #endif // SOFTWARE_SPI
239 |
240 | // must supply min of 74 clock cycles with CS high.
241 | for (uint8_t i = 0; i < 10; i++) spiSend(0XFF);
242 |
243 | chipSelectLow();
244 |
245 | // command to go idle in SPI mode
246 | while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) {
247 | if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) {
248 | error(SD_CARD_ERROR_CMD0);
249 | goto fail;
250 | }
251 | }
252 | // check SD version
253 | if ((cardCommand(CMD8, 0x1AA) & R1_ILLEGAL_COMMAND)) {
254 | type(SD_CARD_TYPE_SD1);
255 | } else {
256 | // only need last byte of r7 response
257 | for (uint8_t i = 0; i < 4; i++) status_ = spiRec();
258 | if (status_ != 0XAA) {
259 | error(SD_CARD_ERROR_CMD8);
260 | goto fail;
261 | }
262 | type(SD_CARD_TYPE_SD2);
263 | }
264 | // initialize card and send host supports SDHC if SD2
265 | arg = type() == SD_CARD_TYPE_SD2 ? 0X40000000 : 0;
266 |
267 | while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) {
268 | // check for timeout
269 | if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) {
270 | error(SD_CARD_ERROR_ACMD41);
271 | goto fail;
272 | }
273 | }
274 | // if SD2 read OCR register to check for SDHC card
275 | if (type() == SD_CARD_TYPE_SD2) {
276 | if (cardCommand(CMD58, 0)) {
277 | error(SD_CARD_ERROR_CMD58);
278 | goto fail;
279 | }
280 | if ((spiRec() & 0XC0) == 0XC0) type(SD_CARD_TYPE_SDHC);
281 | // discard rest of ocr - contains allowed voltage range
282 | for (uint8_t i = 0; i < 3; i++) spiRec();
283 | }
284 | chipSelectHigh();
285 |
286 | #ifndef SOFTWARE_SPI
287 | return setSckRate(sckRateID);
288 | #else // SOFTWARE_SPI
289 | return true;
290 | #endif // SOFTWARE_SPI
291 |
292 | fail:
293 | chipSelectHigh();
294 | return false;
295 | }
296 | //------------------------------------------------------------------------------
297 | /**
298 | * Enable or disable partial block reads.
299 | *
300 | * Enabling partial block reads improves performance by allowing a block
301 | * to be read over the SPI bus as several sub-blocks. Errors may occur
302 | * if the time between reads is too long since the SD card may timeout.
303 | * The SPI SS line will be held low until the entire block is read or
304 | * readEnd() is called.
305 | *
306 | * Use this for applications like the Adafruit Wave Shield.
307 | *
308 | * \param[in] value The value TRUE (non-zero) or FALSE (zero).)
309 | */
310 | void Sd2Card::partialBlockRead(uint8_t value) {
311 | readEnd();
312 | partialBlockRead_ = value;
313 | }
314 | //------------------------------------------------------------------------------
315 | /**
316 | * Read a 512 byte block from an SD card device.
317 | *
318 | * \param[in] block Logical block to be read.
319 | * \param[out] dst Pointer to the location that will receive the data.
320 |
321 | * \return The value one, true, is returned for success and
322 | * the value zero, false, is returned for failure.
323 | */
324 | uint8_t Sd2Card::readBlock(uint32_t block, uint8_t* dst) {
325 | return readData(block, 0, 512, dst);
326 | }
327 | //------------------------------------------------------------------------------
328 | /**
329 | * Read part of a 512 byte block from an SD card.
330 | *
331 | * \param[in] block Logical block to be read.
332 | * \param[in] offset Number of bytes to skip at start of block
333 | * \param[out] dst Pointer to the location that will receive the data.
334 | * \param[in] count Number of bytes to read
335 | * \return The value one, true, is returned for success and
336 | * the value zero, false, is returned for failure.
337 | */
338 | uint8_t Sd2Card::readData(uint32_t block,
339 | uint16_t offset, uint16_t count, uint8_t* dst) {
340 | uint16_t n;
341 | if (count == 0) return true;
342 | if ((count + offset) > 512) {
343 | goto fail;
344 | }
345 | if (!inBlock_ || block != block_ || offset < offset_) {
346 | block_ = block;
347 | // use address if not SDHC card
348 | if (type()!= SD_CARD_TYPE_SDHC) block <<= 9;
349 | if (cardCommand(CMD17, block)) {
350 | error(SD_CARD_ERROR_CMD17);
351 | goto fail;
352 | }
353 | if (!waitStartBlock()) {
354 | goto fail;
355 | }
356 | offset_ = 0;
357 | inBlock_ = 1;
358 | }
359 |
360 | #ifdef OPTIMIZE_HARDWARE_SPI
361 | // start first spi transfer
362 | SPDR = 0XFF;
363 |
364 | // skip data before offset
365 | for (;offset_ < offset; offset_++) {
366 | while (!(SPSR & (1 << SPIF)));
367 | SPDR = 0XFF;
368 | }
369 | // transfer data
370 | n = count - 1;
371 | for (uint16_t i = 0; i < n; i++) {
372 | while (!(SPSR & (1 << SPIF)));
373 | dst[i] = SPDR;
374 | SPDR = 0XFF;
375 | }
376 | // wait for last byte
377 | while (!(SPSR & (1 << SPIF)));
378 | dst[n] = SPDR;
379 |
380 | #else // OPTIMIZE_HARDWARE_SPI
381 |
382 | // skip data before offset
383 | for (;offset_ < offset; offset_++) {
384 | spiRec();
385 | }
386 | // transfer data
387 | for (uint16_t i = 0; i < count; i++) {
388 | dst[i] = spiRec();
389 | }
390 | #endif // OPTIMIZE_HARDWARE_SPI
391 |
392 | offset_ += count;
393 | if (!partialBlockRead_ || offset_ >= 512) {
394 | // read rest of data, checksum and set chip select high
395 | readEnd();
396 | }
397 | return true;
398 |
399 | fail:
400 | chipSelectHigh();
401 | return false;
402 | }
403 | //------------------------------------------------------------------------------
404 | /** Skip remaining data in a block when in partial block read mode. */
405 | void Sd2Card::readEnd(void) {
406 | if (inBlock_) {
407 | // skip data and crc
408 | #ifdef OPTIMIZE_HARDWARE_SPI
409 | // optimize skip for hardware
410 | SPDR = 0XFF;
411 | while (offset_++ < 513) {
412 | while (!(SPSR & (1 << SPIF)));
413 | SPDR = 0XFF;
414 | }
415 | // wait for last crc byte
416 | while (!(SPSR & (1 << SPIF)));
417 | #else // OPTIMIZE_HARDWARE_SPI
418 | while (offset_++ < 514) spiRec();
419 | #endif // OPTIMIZE_HARDWARE_SPI
420 | chipSelectHigh();
421 | inBlock_ = 0;
422 | }
423 | }
424 | //------------------------------------------------------------------------------
425 | /** read CID or CSR register */
426 | uint8_t Sd2Card::readRegister(uint8_t cmd, void* buf) {
427 | uint8_t* dst = reinterpret_cast(buf);
428 | if (cardCommand(cmd, 0)) {
429 | error(SD_CARD_ERROR_READ_REG);
430 | goto fail;
431 | }
432 | if (!waitStartBlock()) goto fail;
433 | // transfer data
434 | for (uint16_t i = 0; i < 16; i++) dst[i] = spiRec();
435 | spiRec(); // get first crc byte
436 | spiRec(); // get second crc byte
437 | chipSelectHigh();
438 | return true;
439 |
440 | fail:
441 | chipSelectHigh();
442 | return false;
443 | }
444 | //------------------------------------------------------------------------------
445 | /**
446 | * Set the SPI clock rate.
447 | *
448 | * \param[in] sckRateID A value in the range [0, 6].
449 | *
450 | * The SPI clock will be set to F_CPU/pow(2, 1 + sckRateID). The maximum
451 | * SPI rate is F_CPU/2 for \a sckRateID = 0 and the minimum rate is F_CPU/128
452 | * for \a scsRateID = 6.
453 | *
454 | * \return The value one, true, is returned for success and the value zero,
455 | * false, is returned for an invalid value of \a sckRateID.
456 | */
457 | uint8_t Sd2Card::setSckRate(uint8_t sckRateID) {
458 | if (sckRateID > 6) {
459 | error(SD_CARD_ERROR_SCK_RATE);
460 | return false;
461 | }
462 | // see avr processor datasheet for SPI register bit definitions
463 | if ((sckRateID & 1) || sckRateID == 6) {
464 | SPSR &= ~(1 << SPI2X);
465 | } else {
466 | SPSR |= (1 << SPI2X);
467 | }
468 | SPCR &= ~((1 < SD_READ_TIMEOUT) {
489 | error(SD_CARD_ERROR_READ_TIMEOUT);
490 | goto fail;
491 | }
492 | }
493 | if (status_ != DATA_START_BLOCK) {
494 | error(SD_CARD_ERROR_READ);
495 | goto fail;
496 | }
497 | return true;
498 |
499 | fail:
500 | chipSelectHigh();
501 | return false;
502 | }
503 | //------------------------------------------------------------------------------
504 | /**
505 | * Writes a 512 byte block to an SD card.
506 | *
507 | * \param[in] blockNumber Logical block to be written.
508 | * \param[in] src Pointer to the location of the data to be written.
509 | * \return The value one, true, is returned for success and
510 | * the value zero, false, is returned for failure.
511 | */
512 | uint8_t Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) {
513 | #if SD_PROTECT_BLOCK_ZERO
514 | // don't allow write to first block
515 | if (blockNumber == 0) {
516 | error(SD_CARD_ERROR_WRITE_BLOCK_ZERO);
517 | goto fail;
518 | }
519 | #endif // SD_PROTECT_BLOCK_ZERO
520 |
521 | // use address if not SDHC card
522 | if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
523 | if (cardCommand(CMD24, blockNumber)) {
524 | error(SD_CARD_ERROR_CMD24);
525 | goto fail;
526 | }
527 | if (!writeData(DATA_START_BLOCK, src)) goto fail;
528 |
529 | // wait for flash programming to complete
530 | if (!waitNotBusy(SD_WRITE_TIMEOUT)) {
531 | error(SD_CARD_ERROR_WRITE_TIMEOUT);
532 | goto fail;
533 | }
534 | // response is r2 so get and check two bytes for nonzero
535 | if (cardCommand(CMD13, 0) || spiRec()) {
536 | error(SD_CARD_ERROR_WRITE_PROGRAMMING);
537 | goto fail;
538 | }
539 | chipSelectHigh();
540 | return true;
541 |
542 | fail:
543 | chipSelectHigh();
544 | return false;
545 | }
546 | //------------------------------------------------------------------------------
547 | /** Write one data block in a multiple block write sequence */
548 | uint8_t Sd2Card::writeData(const uint8_t* src) {
549 | // wait for previous write to finish
550 | if (!waitNotBusy(SD_WRITE_TIMEOUT)) {
551 | error(SD_CARD_ERROR_WRITE_MULTIPLE);
552 | chipSelectHigh();
553 | return false;
554 | }
555 | return writeData(WRITE_MULTIPLE_TOKEN, src);
556 | }
557 | //------------------------------------------------------------------------------
558 | // send one block of data for write block or write multiple blocks
559 | uint8_t Sd2Card::writeData(uint8_t token, const uint8_t* src) {
560 | #ifdef OPTIMIZE_HARDWARE_SPI
561 |
562 | // send data - optimized loop
563 | SPDR = token;
564 |
565 | // send two byte per iteration
566 | for (uint16_t i = 0; i < 512; i += 2) {
567 | while (!(SPSR & (1 << SPIF)));
568 | SPDR = src[i];
569 | while (!(SPSR & (1 << SPIF)));
570 | SPDR = src[i+1];
571 | }
572 |
573 | // wait for last data byte
574 | while (!(SPSR & (1 << SPIF)));
575 |
576 | #else // OPTIMIZE_HARDWARE_SPI
577 | spiSend(token);
578 | for (uint16_t i = 0; i < 512; i++) {
579 | spiSend(src[i]);
580 | }
581 | #endif // OPTIMIZE_HARDWARE_SPI
582 | spiSend(0xff); // dummy crc
583 | spiSend(0xff); // dummy crc
584 |
585 | status_ = spiRec();
586 | if ((status_ & DATA_RES_MASK) != DATA_RES_ACCEPTED) {
587 | error(SD_CARD_ERROR_WRITE);
588 | chipSelectHigh();
589 | return false;
590 | }
591 | return true;
592 | }
593 | //------------------------------------------------------------------------------
594 | /** Start a write multiple blocks sequence.
595 | *
596 | * \param[in] blockNumber Address of first block in sequence.
597 | * \param[in] eraseCount The number of blocks to be pre-erased.
598 | *
599 | * \note This function is used with writeData() and writeStop()
600 | * for optimized multiple block writes.
601 | *
602 | * \return The value one, true, is returned for success and
603 | * the value zero, false, is returned for failure.
604 | */
605 | uint8_t Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) {
606 | #if SD_PROTECT_BLOCK_ZERO
607 | // don't allow write to first block
608 | if (blockNumber == 0) {
609 | error(SD_CARD_ERROR_WRITE_BLOCK_ZERO);
610 | goto fail;
611 | }
612 | #endif // SD_PROTECT_BLOCK_ZERO
613 | // send pre-erase count
614 | if (cardAcmd(ACMD23, eraseCount)) {
615 | error(SD_CARD_ERROR_ACMD23);
616 | goto fail;
617 | }
618 | // use address if not SDHC card
619 | if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
620 | if (cardCommand(CMD25, blockNumber)) {
621 | error(SD_CARD_ERROR_CMD25);
622 | goto fail;
623 | }
624 | return true;
625 |
626 | fail:
627 | chipSelectHigh();
628 | return false;
629 | }
630 | //------------------------------------------------------------------------------
631 | /** End a write multiple blocks sequence.
632 | *
633 | * \return The value one, true, is returned for success and
634 | * the value zero, false, is returned for failure.
635 | */
636 | uint8_t Sd2Card::writeStop(void) {
637 | if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail;
638 | spiSend(STOP_TRAN_TOKEN);
639 | if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail;
640 | chipSelectHigh();
641 | return true;
642 |
643 | fail:
644 | error(SD_CARD_ERROR_STOP_TRAN);
645 | chipSelectHigh();
646 | return false;
647 | }
648 |
--------------------------------------------------------------------------------
/Sprinter/SdFat.h:
--------------------------------------------------------------------------------
1 | /* Arduino SdFat Library
2 | * Copyright (C) 2009 by William Greiman
3 | *
4 | * This file is part of the Arduino SdFat Library
5 | *
6 | * This Library is free software: you can redistribute it and/or modify
7 | * it under the terms of the GNU General Public License as published by
8 | * the Free Software Foundation, either version 3 of the License, or
9 | * (at your option) any later version.
10 | *
11 | * This Library is distributed in the hope that it will be useful,
12 | * but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | * GNU General Public License for more details.
15 | *
16 | * You should have received a copy of the GNU General Public License
17 | * along with the Arduino SdFat Library. If not, see
18 | * .
19 | */
20 | #ifndef SdFat_h
21 | #define SdFat_h
22 | /**
23 | * \file
24 | * SdFile and SdVolume classes
25 | */
26 | #include
27 | #include "Sd2Card.h"
28 | #include "FatStructs.h"
29 | #include "Print.h"
30 | //------------------------------------------------------------------------------
31 | /**
32 | * Allow use of deprecated functions if non-zero
33 | */
34 | #define ALLOW_DEPRECATED_FUNCTIONS 1
35 | //------------------------------------------------------------------------------
36 | // forward declaration since SdVolume is used in SdFile
37 | class SdVolume;
38 | //==============================================================================
39 | // SdFile class
40 |
41 | // flags for ls()
42 | /** ls() flag to print modify date */
43 | uint8_t const LS_DATE = 1;
44 | /** ls() flag to print file size */
45 | uint8_t const LS_SIZE = 2;
46 | /** ls() flag for recursive list of subdirectories */
47 | uint8_t const LS_R = 4;
48 |
49 | // use the gnu style oflag in open()
50 | /** open() oflag for reading */
51 | uint8_t const O_READ = 0X01;
52 | /** open() oflag - same as O_READ */
53 | uint8_t const O_RDONLY = O_READ;
54 | /** open() oflag for write */
55 | uint8_t const O_WRITE = 0X02;
56 | /** open() oflag - same as O_WRITE */
57 | uint8_t const O_WRONLY = O_WRITE;
58 | /** open() oflag for reading and writing */
59 | uint8_t const O_RDWR = (O_READ | O_WRITE);
60 | /** open() oflag mask for access modes */
61 | uint8_t const O_ACCMODE = (O_READ | O_WRITE);
62 | /** The file offset shall be set to the end of the file prior to each write. */
63 | uint8_t const O_APPEND = 0X04;
64 | /** synchronous writes - call sync() after each write */
65 | uint8_t const O_SYNC = 0X08;
66 | /** create the file if nonexistent */
67 | uint8_t const O_CREAT = 0X10;
68 | /** If O_CREAT and O_EXCL are set, open() shall fail if the file exists */
69 | uint8_t const O_EXCL = 0X20;
70 | /** truncate the file to zero length */
71 | uint8_t const O_TRUNC = 0X40;
72 |
73 | // flags for timestamp
74 | /** set the file's last access date */
75 | uint8_t const T_ACCESS = 1;
76 | /** set the file's creation date and time */
77 | uint8_t const T_CREATE = 2;
78 | /** Set the file's write date and time */
79 | uint8_t const T_WRITE = 4;
80 | // values for type_
81 | /** This SdFile has not been opened. */
82 | uint8_t const FAT_FILE_TYPE_CLOSED = 0;
83 | /** SdFile for a file */
84 | uint8_t const FAT_FILE_TYPE_NORMAL = 1;
85 | /** SdFile for a FAT16 root directory */
86 | uint8_t const FAT_FILE_TYPE_ROOT16 = 2;
87 | /** SdFile for a FAT32 root directory */
88 | uint8_t const FAT_FILE_TYPE_ROOT32 = 3;
89 | /** SdFile for a subdirectory */
90 | uint8_t const FAT_FILE_TYPE_SUBDIR = 4;
91 | /** Test value for directory type */
92 | uint8_t const FAT_FILE_TYPE_MIN_DIR = FAT_FILE_TYPE_ROOT16;
93 |
94 | /** date field for FAT directory entry */
95 | static inline uint16_t FAT_DATE(uint16_t year, uint8_t month, uint8_t day) {
96 | return (year - 1980) << 9 | month << 5 | day;
97 | }
98 | /** year part of FAT directory date field */
99 | static inline uint16_t FAT_YEAR(uint16_t fatDate) {
100 | return 1980 + (fatDate >> 9);
101 | }
102 | /** month part of FAT directory date field */
103 | static inline uint8_t FAT_MONTH(uint16_t fatDate) {
104 | return (fatDate >> 5) & 0XF;
105 | }
106 | /** day part of FAT directory date field */
107 | static inline uint8_t FAT_DAY(uint16_t fatDate) {
108 | return fatDate & 0X1F;
109 | }
110 | /** time field for FAT directory entry */
111 | static inline uint16_t FAT_TIME(uint8_t hour, uint8_t minute, uint8_t second) {
112 | return hour << 11 | minute << 5 | second >> 1;
113 | }
114 | /** hour part of FAT directory time field */
115 | static inline uint8_t FAT_HOUR(uint16_t fatTime) {
116 | return fatTime >> 11;
117 | }
118 | /** minute part of FAT directory time field */
119 | static inline uint8_t FAT_MINUTE(uint16_t fatTime) {
120 | return(fatTime >> 5) & 0X3F;
121 | }
122 | /** second part of FAT directory time field */
123 | static inline uint8_t FAT_SECOND(uint16_t fatTime) {
124 | return 2*(fatTime & 0X1F);
125 | }
126 | /** Default date for file timestamps is 1 Jan 2000 */
127 | uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1;
128 | /** Default time for file timestamp is 1 am */
129 | uint16_t const FAT_DEFAULT_TIME = (1 << 11);
130 | //------------------------------------------------------------------------------
131 | /**
132 | * \class SdFile
133 | * \brief Access FAT16 and FAT32 files on SD and SDHC cards.
134 | */
135 | class SdFile : public Print {
136 | public:
137 | /** Create an instance of SdFile. */
138 | SdFile(void) : type_(FAT_FILE_TYPE_CLOSED) {}
139 | /**
140 | * writeError is set to true if an error occurs during a write().
141 | * Set writeError to false before calling print() and/or write() and check
142 | * for true after calls to print() and/or write().
143 | */
144 | bool writeError;
145 | /**
146 | * Cancel unbuffered reads for this file.
147 | * See setUnbufferedRead()
148 | */
149 | void clearUnbufferedRead(void) {
150 | flags_ &= ~F_FILE_UNBUFFERED_READ;
151 | }
152 | uint8_t close(void);
153 | uint8_t contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
154 | uint8_t createContiguous(SdFile* dirFile,
155 | const char* fileName, uint32_t size);
156 | /** \return The current cluster number for a file or directory. */
157 | uint32_t curCluster(void) const {return curCluster_;}
158 | /** \return The current position for a file or directory. */
159 | uint32_t curPosition(void) const {return curPosition_;}
160 | /**
161 | * Set the date/time callback function
162 | *
163 | * \param[in] dateTime The user's call back function. The callback
164 | * function is of the form:
165 | *
166 | * \code
167 | * void dateTime(uint16_t* date, uint16_t* time) {
168 | * uint16_t year;
169 | * uint8_t month, day, hour, minute, second;
170 | *
171 | * // User gets date and time from GPS or real-time clock here
172 | *
173 | * // return date using FAT_DATE macro to format fields
174 | * *date = FAT_DATE(year, month, day);
175 | *
176 | * // return time using FAT_TIME macro to format fields
177 | * *time = FAT_TIME(hour, minute, second);
178 | * }
179 | * \endcode
180 | *
181 | * Sets the function that is called when a file is created or when
182 | * a file's directory entry is modified by sync(). All timestamps,
183 | * access, creation, and modify, are set when a file is created.
184 | * sync() maintains the last access date and last modify date/time.
185 | *
186 | * See the timestamp() function.
187 | */
188 | static void dateTimeCallback(
189 | void (*dateTime)(uint16_t* date, uint16_t* time)) {
190 | dateTime_ = dateTime;
191 | }
192 | /**
193 | * Cancel the date/time callback function.
194 | */
195 | static void dateTimeCallbackCancel(void) {
196 | // use explicit zero since NULL is not defined for Sanguino
197 | dateTime_ = 0;
198 | }
199 | /** \return Address of the block that contains this file's directory. */
200 | uint32_t dirBlock(void) const {return dirBlock_;}
201 | uint8_t dirEntry(dir_t* dir);
202 | /** \return Index of this file's directory in the block dirBlock. */
203 | uint8_t dirIndex(void) const {return dirIndex_;}
204 | static void dirName(const dir_t& dir, char* name);
205 | /** \return The total number of bytes in a file or directory. */
206 | uint32_t fileSize(void) const {return fileSize_;}
207 | /** \return The first cluster number for a file or directory. */
208 | uint32_t firstCluster(void) const {return firstCluster_;}
209 | /** \return True if this is a SdFile for a directory else false. */
210 | uint8_t isDir(void) const {return type_ >= FAT_FILE_TYPE_MIN_DIR;}
211 | /** \return True if this is a SdFile for a file else false. */
212 | uint8_t isFile(void) const {return type_ == FAT_FILE_TYPE_NORMAL;}
213 | /** \return True if this is a SdFile for an open file/directory else false. */
214 | uint8_t isOpen(void) const {return type_ != FAT_FILE_TYPE_CLOSED;}
215 | /** \return True if this is a SdFile for a subdirectory else false. */
216 | uint8_t isSubDir(void) const {return type_ == FAT_FILE_TYPE_SUBDIR;}
217 | /** \return True if this is a SdFile for the root directory. */
218 | uint8_t isRoot(void) const {
219 | return type_ == FAT_FILE_TYPE_ROOT16 || type_ == FAT_FILE_TYPE_ROOT32;
220 | }
221 | void ls(uint8_t flags = 0, uint8_t indent = 0);
222 | uint8_t makeDir(SdFile* dir, const char* dirName);
223 | uint8_t open(SdFile* dirFile, uint16_t index, uint8_t oflag);
224 | uint8_t open(SdFile* dirFile, const char* fileName, uint8_t oflag);
225 |
226 | uint8_t openRoot(SdVolume* vol);
227 | static void printDirName(const dir_t& dir, uint8_t width);
228 | static void printFatDate(uint16_t fatDate);
229 | static void printFatTime(uint16_t fatTime);
230 | static void printTwoDigits(uint8_t v);
231 | /**
232 | * Read the next byte from a file.
233 | *
234 | * \return For success read returns the next byte in the file as an int.
235 | * If an error occurs or end of file is reached -1 is returned.
236 | */
237 | int16_t read(void) {
238 | uint8_t b;
239 | return read(&b, 1) == 1 ? b : -1;
240 | }
241 | int16_t read(void* buf, uint16_t nbyte);
242 | int8_t readDir(dir_t* dir);
243 | static uint8_t remove(SdFile* dirFile, const char* fileName);
244 | uint8_t remove(void);
245 | /** Set the file's current position to zero. */
246 | void rewind(void) {
247 | curPosition_ = curCluster_ = 0;
248 | }
249 | uint8_t rmDir(void);
250 | uint8_t rmRfStar(void);
251 | /** Set the files position to current position + \a pos. See seekSet(). */
252 | uint8_t seekCur(uint32_t pos) {
253 | return seekSet(curPosition_ + pos);
254 | }
255 | /**
256 | * Set the files current position to end of file. Useful to position
257 | * a file for append. See seekSet().
258 | */
259 | uint8_t seekEnd(void) {return seekSet(fileSize_);}
260 | uint8_t seekSet(uint32_t pos);
261 | /**
262 | * Use unbuffered reads to access this file. Used with Wave
263 | * Shield ISR. Used with Sd2Card::partialBlockRead() in WaveRP.
264 | *
265 | * Not recommended for normal applications.
266 | */
267 | void setUnbufferedRead(void) {
268 | if (isFile()) flags_ |= F_FILE_UNBUFFERED_READ;
269 | }
270 | uint8_t timestamp(uint8_t flag, uint16_t year, uint8_t month, uint8_t day,
271 | uint8_t hour, uint8_t minute, uint8_t second);
272 | uint8_t sync(void);
273 | /** Type of this SdFile. You should use isFile() or isDir() instead of type()
274 | * if possible.
275 | *
276 | * \return The file or directory type.
277 | */
278 | uint8_t type(void) const {return type_;}
279 | uint8_t truncate(uint32_t size);
280 | /** \return Unbuffered read flag. */
281 | uint8_t unbufferedRead(void) const {
282 | return flags_ & F_FILE_UNBUFFERED_READ;
283 | }
284 | /** \return SdVolume that contains this file. */
285 | SdVolume* volume(void) const {return vol_;}
286 | #if ARDUINO >= 100
287 | size_t write(uint8_t b);
288 | #else
289 | void write(uint8_t b);
290 | #endif
291 | int16_t write(const void* buf, uint16_t nbyte);
292 | void write(const char* str);
293 | void write_P(PGM_P str);
294 | void writeln_P(PGM_P str);
295 | //------------------------------------------------------------------------------
296 | #if ALLOW_DEPRECATED_FUNCTIONS
297 | // Deprecated functions - suppress cpplint warnings with NOLINT comment
298 | /** \deprecated Use:
299 | * uint8_t SdFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
300 | */
301 | uint8_t contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) { // NOLINT
302 | return contiguousRange(&bgnBlock, &endBlock);
303 | }
304 | /** \deprecated Use:
305 | * uint8_t SdFile::createContiguous(SdFile* dirFile,
306 | * const char* fileName, uint32_t size)
307 | */
308 | uint8_t createContiguous(SdFile& dirFile, // NOLINT
309 | const char* fileName, uint32_t size) {
310 | return createContiguous(&dirFile, fileName, size);
311 | }
312 |
313 | /**
314 | * \deprecated Use:
315 | * static void SdFile::dateTimeCallback(
316 | * void (*dateTime)(uint16_t* date, uint16_t* time));
317 | */
318 | static void dateTimeCallback(
319 | void (*dateTime)(uint16_t& date, uint16_t& time)) { // NOLINT
320 | oldDateTime_ = dateTime;
321 | dateTime_ = dateTime ? oldToNew : 0;
322 | }
323 | /** \deprecated Use: uint8_t SdFile::dirEntry(dir_t* dir); */
324 | uint8_t dirEntry(dir_t& dir) {return dirEntry(&dir);} // NOLINT
325 | /** \deprecated Use:
326 | * uint8_t SdFile::makeDir(SdFile* dir, const char* dirName);
327 | */
328 | uint8_t makeDir(SdFile& dir, const char* dirName) { // NOLINT
329 | return makeDir(&dir, dirName);
330 | }
331 | /** \deprecated Use:
332 | * uint8_t SdFile::open(SdFile* dirFile, const char* fileName, uint8_t oflag);
333 | */
334 | uint8_t open(SdFile& dirFile, // NOLINT
335 | const char* fileName, uint8_t oflag) {
336 | return open(&dirFile, fileName, oflag);
337 | }
338 | /** \deprecated Do not use in new apps */
339 | uint8_t open(SdFile& dirFile, const char* fileName) { // NOLINT
340 | return open(dirFile, fileName, O_RDWR);
341 | }
342 | /** \deprecated Use:
343 | * uint8_t SdFile::open(SdFile* dirFile, uint16_t index, uint8_t oflag);
344 | */
345 | uint8_t open(SdFile& dirFile, uint16_t index, uint8_t oflag) { // NOLINT
346 | return open(&dirFile, index, oflag);
347 | }
348 | /** \deprecated Use: uint8_t SdFile::openRoot(SdVolume* vol); */
349 | uint8_t openRoot(SdVolume& vol) {return openRoot(&vol);} // NOLINT
350 |
351 | /** \deprecated Use: int8_t SdFile::readDir(dir_t* dir); */
352 | int8_t readDir(dir_t& dir) {return readDir(&dir);} // NOLINT
353 | /** \deprecated Use:
354 | * static uint8_t SdFile::remove(SdFile* dirFile, const char* fileName);
355 | */
356 | static uint8_t remove(SdFile& dirFile, const char* fileName) { // NOLINT
357 | return remove(&dirFile, fileName);
358 | }
359 | //------------------------------------------------------------------------------
360 | // rest are private
361 | private:
362 | static void (*oldDateTime_)(uint16_t& date, uint16_t& time); // NOLINT
363 | static void oldToNew(uint16_t* date, uint16_t* time) {
364 | uint16_t d;
365 | uint16_t t;
366 | oldDateTime_(d, t);
367 | *date = d;
368 | *time = t;
369 | }
370 | #endif // ALLOW_DEPRECATED_FUNCTIONS
371 | private:
372 | // bits defined in flags_
373 | // should be 0XF
374 | static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC);
375 | // available bits
376 | static uint8_t const F_UNUSED = 0X30;
377 | // use unbuffered SD read
378 | static uint8_t const F_FILE_UNBUFFERED_READ = 0X40;
379 | // sync of directory entry required
380 | static uint8_t const F_FILE_DIR_DIRTY = 0X80;
381 |
382 | // make sure F_OFLAG is ok
383 | #if ((F_UNUSED | F_FILE_UNBUFFERED_READ | F_FILE_DIR_DIRTY) & F_OFLAG)
384 | #error flags_ bits conflict
385 | #endif // flags_ bits
386 |
387 | // private data
388 | uint8_t flags_; // See above for definition of flags_ bits
389 | uint8_t type_; // type of file see above for values
390 | uint32_t curCluster_; // cluster for current file position
391 | uint32_t curPosition_; // current file position in bytes from beginning
392 | uint32_t dirBlock_; // SD block that contains directory entry for file
393 | uint8_t dirIndex_; // index of entry in dirBlock 0 <= dirIndex_ <= 0XF
394 | uint32_t fileSize_; // file size in bytes
395 | uint32_t firstCluster_; // first cluster of file
396 | SdVolume* vol_; // volume where file is located
397 |
398 | // private functions
399 | uint8_t addCluster(void);
400 | uint8_t addDirCluster(void);
401 | dir_t* cacheDirEntry(uint8_t action);
402 | static void (*dateTime_)(uint16_t* date, uint16_t* time);
403 | static uint8_t make83Name(const char* str, uint8_t* name);
404 | uint8_t openCachedEntry(uint8_t cacheIndex, uint8_t oflags);
405 | dir_t* readDirCache(void);
406 | };
407 | //==============================================================================
408 | // SdVolume class
409 | /**
410 | * \brief Cache for an SD data block
411 | */
412 | union cache_t {
413 | /** Used to access cached file data blocks. */
414 | uint8_t data[512];
415 | /** Used to access cached FAT16 entries. */
416 | uint16_t fat16[256];
417 | /** Used to access cached FAT32 entries. */
418 | uint32_t fat32[128];
419 | /** Used to access cached directory entries. */
420 | dir_t dir[16];
421 | /** Used to access a cached MasterBoot Record. */
422 | mbr_t mbr;
423 | /** Used to access to a cached FAT boot sector. */
424 | fbs_t fbs;
425 | };
426 | //------------------------------------------------------------------------------
427 | /**
428 | * \class SdVolume
429 | * \brief Access FAT16 and FAT32 volumes on SD and SDHC cards.
430 | */
431 | class SdVolume {
432 | public:
433 | /** Create an instance of SdVolume */
434 | SdVolume(void) :allocSearchStart_(2), fatType_(0) {}
435 | /** Clear the cache and returns a pointer to the cache. Used by the WaveRP
436 | * recorder to do raw write to the SD card. Not for normal apps.
437 | */
438 | static uint8_t* cacheClear(void) {
439 | cacheFlush();
440 | cacheBlockNumber_ = 0XFFFFFFFF;
441 | return cacheBuffer_.data;
442 | }
443 | /**
444 | * Initialize a FAT volume. Try partition one first then try super
445 | * floppy format.
446 | *
447 | * \param[in] dev The Sd2Card where the volume is located.
448 | *
449 | * \return The value one, true, is returned for success and
450 | * the value zero, false, is returned for failure. Reasons for
451 | * failure include not finding a valid partition, not finding a valid
452 | * FAT file system or an I/O error.
453 | */
454 | uint8_t init(Sd2Card* dev) { return init(dev, 1) ? true : init(dev, 0);}
455 | uint8_t init(Sd2Card* dev, uint8_t part);
456 |
457 | // inline functions that return volume info
458 | /** \return The volume's cluster size in blocks. */
459 | uint8_t blocksPerCluster(void) const {return blocksPerCluster_;}
460 | /** \return The number of blocks in one FAT. */
461 | uint32_t blocksPerFat(void) const {return blocksPerFat_;}
462 | /** \return The total number of clusters in the volume. */
463 | uint32_t clusterCount(void) const {return clusterCount_;}
464 | /** \return The shift count required to multiply by blocksPerCluster. */
465 | uint8_t clusterSizeShift(void) const {return clusterSizeShift_;}
466 | /** \return The logical block number for the start of file data. */
467 | uint32_t dataStartBlock(void) const {return dataStartBlock_;}
468 | /** \return The number of FAT structures on the volume. */
469 | uint8_t fatCount(void) const {return fatCount_;}
470 | /** \return The logical block number for the start of the first FAT. */
471 | uint32_t fatStartBlock(void) const {return fatStartBlock_;}
472 | /** \return The FAT type of the volume. Values are 12, 16 or 32. */
473 | uint8_t fatType(void) const {return fatType_;}
474 | /** \return The number of entries in the root directory for FAT16 volumes. */
475 | uint32_t rootDirEntryCount(void) const {return rootDirEntryCount_;}
476 | /** \return The logical block number for the start of the root directory
477 | on FAT16 volumes or the first cluster number on FAT32 volumes. */
478 | uint32_t rootDirStart(void) const {return rootDirStart_;}
479 | /** return a pointer to the Sd2Card object for this volume */
480 | static Sd2Card* sdCard(void) {return sdCard_;}
481 | //------------------------------------------------------------------------------
482 | #if ALLOW_DEPRECATED_FUNCTIONS
483 | // Deprecated functions - suppress cpplint warnings with NOLINT comment
484 | /** \deprecated Use: uint8_t SdVolume::init(Sd2Card* dev); */
485 | uint8_t init(Sd2Card& dev) {return init(&dev);} // NOLINT
486 |
487 | /** \deprecated Use: uint8_t SdVolume::init(Sd2Card* dev, uint8_t vol); */
488 | uint8_t init(Sd2Card& dev, uint8_t part) { // NOLINT
489 | return init(&dev, part);
490 | }
491 | #endif // ALLOW_DEPRECATED_FUNCTIONS
492 | //------------------------------------------------------------------------------
493 | private:
494 | // Allow SdFile access to SdVolume private data.
495 | friend class SdFile;
496 |
497 | // value for action argument in cacheRawBlock to indicate read from cache
498 | static uint8_t const CACHE_FOR_READ = 0;
499 | // value for action argument in cacheRawBlock to indicate cache dirty
500 | static uint8_t const CACHE_FOR_WRITE = 1;
501 |
502 | static cache_t cacheBuffer_; // 512 byte cache for device blocks
503 | static uint32_t cacheBlockNumber_; // Logical number of block in the cache
504 | static Sd2Card* sdCard_; // Sd2Card object for cache
505 | static uint8_t cacheDirty_; // cacheFlush() will write block if true
506 | static uint32_t cacheMirrorBlock_; // block number for mirror FAT
507 | //
508 | uint32_t allocSearchStart_; // start cluster for alloc search
509 | uint8_t blocksPerCluster_; // cluster size in blocks
510 | uint32_t blocksPerFat_; // FAT size in blocks
511 | uint32_t clusterCount_; // clusters in one FAT
512 | uint8_t clusterSizeShift_; // shift to convert cluster count to block count
513 | uint32_t dataStartBlock_; // first data block number
514 | uint8_t fatCount_; // number of FATs on volume
515 | uint32_t fatStartBlock_; // start block for first FAT
516 | uint8_t fatType_; // volume type (12, 16, OR 32)
517 | uint16_t rootDirEntryCount_; // number of entries in FAT16 root dir
518 | uint32_t rootDirStart_; // root start block for FAT16, cluster for FAT32
519 | //----------------------------------------------------------------------------
520 | uint8_t allocContiguous(uint32_t count, uint32_t* curCluster);
521 | uint8_t blockOfCluster(uint32_t position) const {
522 | return (position >> 9) & (blocksPerCluster_ - 1);}
523 | uint32_t clusterStartBlock(uint32_t cluster) const {
524 | return dataStartBlock_ + ((cluster - 2) << clusterSizeShift_);}
525 | uint32_t blockNumber(uint32_t cluster, uint32_t position) const {
526 | return clusterStartBlock(cluster) + blockOfCluster(position);}
527 | static uint8_t cacheFlush(void);
528 | static uint8_t cacheRawBlock(uint32_t blockNumber, uint8_t action);
529 | static void cacheSetDirty(void) {cacheDirty_ |= CACHE_FOR_WRITE;}
530 | static uint8_t cacheZeroBlock(uint32_t blockNumber);
531 | uint8_t chainSize(uint32_t beginCluster, uint32_t* size) const;
532 | uint8_t fatGet(uint32_t cluster, uint32_t* value) const;
533 | uint8_t fatPut(uint32_t cluster, uint32_t value);
534 | uint8_t fatPutEOC(uint32_t cluster) {
535 | return fatPut(cluster, 0x0FFFFFFF);
536 | }
537 | uint8_t freeChain(uint32_t cluster);
538 | uint8_t isEOC(uint32_t cluster) const {
539 | return cluster >= (fatType_ == 16 ? FAT16EOC_MIN : FAT32EOC_MIN);
540 | }
541 | uint8_t readBlock(uint32_t block, uint8_t* dst) {
542 | return sdCard_->readBlock(block, dst);}
543 | uint8_t readData(uint32_t block, uint16_t offset,
544 | uint16_t count, uint8_t* dst) {
545 | return sdCard_->readData(block, offset, count, dst);
546 | }
547 | uint8_t writeBlock(uint32_t block, const uint8_t* dst) {
548 | return sdCard_->writeBlock(block, dst);
549 | }
550 | };
551 | #endif // SdFat_h
552 |
--------------------------------------------------------------------------------