Repetier-Firmware  0.91
src/ArduinoAVR/Repetier/HAL.h
Go to the documentation of this file.
00001 /*
00002     This file is part of Repetier-Firmware.
00003 
00004     Repetier-Firmware is free software: you can redistribute it and/or modify
00005     it under the terms of the GNU General Public License as published by
00006     the Free Software Foundation, either version 3 of the License, or
00007     (at your option) any later version.
00008 
00009     Repetier-Firmware is distributed in the hope that it will be useful,
00010     but WITHOUT ANY WARRANTY; without even the implied warranty of
00011     MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00012     GNU General Public License for more details.
00013 
00014     You should have received a copy of the GNU General Public License
00015     along with Repetier-Firmware.  If not, see <http://www.gnu.org/licenses/>.
00016 
00017     This firmware is a nearly complete rewrite of the sprinter firmware
00018     by kliment (https://github.com/kliment/Sprinter)
00019     which based on Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
00020 
00021   Functions in this file are used to communicate using ascii or repetier protocol.
00022 */
00023 
00024 #ifndef HAL_H
00025 #define HAL_H
00026 
00033 #include <avr/pgmspace.h>
00034 #include <avr/io.h>
00035 #if CPU_ARCH==ARCH_AVR
00036 #include <avr/io.h>
00037 #else
00038 #define PROGMEM
00039 #define PGM_P const char *
00040 #define PSTR(s) s
00041 #define pgm_read_byte_near(x) (*(char*)x)
00042 #define pgm_read_byte(x) (*(char*)x)
00043 #endif
00044 
00045 #define PACK
00046 
00047 #define FSTRINGVALUE(var,value) const char var[] PROGMEM = value;
00048 #define FSTRINGVAR(var) static const char var[] PROGMEM;
00049 #define FSTRINGPARAM(var) PGM_P var
00050 
00051 #include <avr/eeprom.h>
00052 #include <avr/wdt.h>
00056 #define TIMER0_PRESCALE 64
00057 
00058 #define ANALOG_PRESCALER _BV(ADPS0)|_BV(ADPS1)|_BV(ADPS2)
00059 
00060 #if MOTHERBOARD==8 || MOTHERBOARD==9 || CPU_ARCH!=ARCH_AVR
00061 #define EXTERNALSERIAL
00062 #endif
00063 //#define EXTERNALSERIAL  // Force using arduino serial
00064 #ifndef EXTERNALSERIAL
00065 #define  HardwareSerial_h // Don't use standard serial console
00066 #endif
00067 #include <inttypes.h>
00068 #include "Print.h"
00069 
00070 #if defined(ARDUINO) && ARDUINO >= 100
00071 #include "Arduino.h"
00072 #else
00073 #include "WProgram.h"
00074 #define COMPAT_PRE1
00075 #endif
00076 #if CPU_ARCH==ARCH_AVR
00077 #include "fastio.h"
00078 #else
00079 #define READ(IO)  digitalRead(IO)
00080 #define WRITE(IO, v)  digitalWrite(IO, v)
00081 #define SET_INPUT(IO)  pinMode(IO, INPUT)
00082 #define SET_OUTPUT(IO)  pinMode(IO, OUTPUT)
00083 #endif
00084 
00085 #define BEGIN_INTERRUPT_PROTECTED {uint8_t sreg=SREG;__asm volatile( "cli" ::: "memory" );
00086 #define END_INTERRUPT_PROTECTED SREG=sreg;}
00087 #define ESCAPE_INTERRUPT_PROTECTED SREG=sreg;
00088 
00089 #define EEPROM_OFFSET               0
00090 #define SECONDS_TO_TICKS(s) (unsigned long)(s*(float)F_CPU)
00091 #define ANALOG_REDUCE_BITS 0
00092 #define ANALOG_REDUCE_FACTOR 1
00093 
00094 #define MAX_RAM 32767
00095 
00096 #define bit_clear(x,y) x&= ~(1<<y) //cbi(x,y)
00097 #define bit_set(x,y)   x|= (1<<y)//sbi(x,y)
00098 
00100 #define I2C_READ    1
00101 
00102 #define I2C_WRITE   0
00103 
00104 
00105 typedef unsigned int speed_t;
00106 typedef unsigned long ticks_t;
00107 typedef unsigned long millis_t;
00108 
00109 #define FAST_INTEGER_SQRT
00110 
00111 #ifndef EXTERNALSERIAL
00112 // Implement serial communication for one stream only!
00113 /*
00114   HardwareSerial.h - Hardware serial library for Wiring
00115   Copyright (c) 2006 Nicholas Zambetti.  All right reserved.
00116 
00117   This library is free software; you can redistribute it and/or
00118   modify it under the terms of the GNU Lesser General Public
00119   License as published by the Free Software Foundation; either
00120   version 2.1 of the License, or (at your option) any later version.
00121 
00122   This library is distributed in the hope that it will be useful,
00123   but WITHOUT ANY WARRANTY; without even the implied warranty of
00124   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00125   Lesser General Public License for more details.
00126 
00127   You should have received a copy of the GNU Lesser General Public
00128   License along with this library; if not, write to the Free Software
00129   Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
00130 
00131   Modified 28 September 2010 by Mark Sproul
00132 
00133   Modified to use only 1 queue with fixed length by Repetier
00134 */
00135 
00136 #define SERIAL_BUFFER_SIZE 128
00137 #define SERIAL_BUFFER_MASK 127
00138 #define SERIAL_TX_BUFFER_SIZE 64
00139 #define SERIAL_TX_BUFFER_MASK 63
00140 
00141 struct ring_buffer
00142 {
00143     unsigned char buffer[SERIAL_BUFFER_SIZE];
00144     volatile uint8_t head;
00145     volatile uint8_t tail;
00146 };
00147 struct ring_buffer_tx
00148 {
00149     unsigned char buffer[SERIAL_TX_BUFFER_SIZE];
00150     volatile uint8_t head;
00151     volatile uint8_t tail;
00152 };
00153 
00154 class RFHardwareSerial : public Print
00155 {
00156 public:
00157     ring_buffer *_rx_buffer;
00158     ring_buffer_tx *_tx_buffer;
00159     volatile uint8_t *_ubrrh;
00160     volatile uint8_t *_ubrrl;
00161     volatile uint8_t *_ucsra;
00162     volatile uint8_t *_ucsrb;
00163     volatile uint8_t *_udr;
00164     uint8_t _rxen;
00165     uint8_t _txen;
00166     uint8_t _rxcie;
00167     uint8_t _udrie;
00168     uint8_t _u2x;
00169 public:
00170     RFHardwareSerial(ring_buffer *rx_buffer, ring_buffer_tx *tx_buffer,
00171                      volatile uint8_t *ubrrh, volatile uint8_t *ubrrl,
00172                      volatile uint8_t *ucsra, volatile uint8_t *ucsrb,
00173                      volatile uint8_t *udr,
00174                      uint8_t rxen, uint8_t txen, uint8_t rxcie, uint8_t udrie, uint8_t u2x);
00175     void begin(unsigned long);
00176     void end();
00177     virtual int available(void);
00178     virtual int peek(void);
00179     virtual int read(void);
00180     virtual void flush(void);
00181 #ifdef COMPAT_PRE1
00182     virtual void write(uint8_t);
00183 #else
00184     virtual size_t write(uint8_t);
00185 #endif
00186     using Print::write; // pull in write(str) and write(buf, size) from Print
00187     operator bool();
00188     int outputUnused(void); // Used for output in interrupts
00189 };
00190 extern RFHardwareSerial RFSerial;
00191 #define RFSERIAL RFSerial
00192 //extern ring_buffer tx_buffer;
00193 #define WAIT_OUT_EMPTY while(tx_buffer.head != tx_buffer.tail) {}
00194 #else
00195 #define RFSERIAL Serial
00196 #endif
00197 
00198 #define OUT_P_I(p,i) Com::printF(PSTR(p),(int)(i))
00199 #define OUT_P_I_LN(p,i) Com::printFLN(PSTR(p),(int)(i))
00200 #define OUT_P_L(p,i) Com::printF(PSTR(p),(long)(i))
00201 #define OUT_P_L_LN(p,i) Com::printFLN(PSTR(p),(long)(i))
00202 #define OUT_P_F(p,i) Com::printF(PSTR(p),(float)(i))
00203 #define OUT_P_F_LN(p,i) Com::printFLN(PSTR(p),(float)(i))
00204 #define OUT_P_FX(p,i,x) Com::printF(PSTR(p),(float)(i),x)
00205 #define OUT_P_FX_LN(p,i,x) Com::printFLN(PSTR(p),(float)(i),x)
00206 #define OUT_P(p) Com::printF(PSTR(p))
00207 #define OUT_P_LN(p) Com::printFLN(PSTR(p))
00208 #define OUT_ERROR_P(p) Com::printErrorF(PSTR(p))
00209 #define OUT_ERROR_P_LN(p) {Com::printErrorF(PSTR(p));Com::println();}
00210 #define OUT(v) Com::print(v)
00211 #define OUT_LN Com::println()
00212 
00213 class HAL
00214 {
00215 public:
00216     HAL();
00217     virtual ~HAL();
00218     static inline void hwSetup(void)
00219     {}
00220     // return val'val
00221     static uint16_t integerSqrt(long a);
00229     static inline long Div4U2U(unsigned long a,unsigned int b)
00230     {
00231 #if CPU_ARCH==ARCH_AVR
00232         // r14/r15 remainder
00233         // r16 counter
00234         __asm__ __volatile__ (
00235             "clr r14 \n\t"
00236             "sub r15,r15 \n\t"
00237             "tst %D0 \n\t"
00238             "brne do32%= \n\t"
00239             "tst %C0 \n\t"
00240             "breq donot24%= \n\t"
00241             "rjmp do24%= \n\t"
00242             "donot24%=:" "ldi r16,17 \n\t" // 16 Bit divide
00243             "d16u_1%=:" "rol %A0 \n\t"
00244             "rol %B0 \n\t"
00245             "dec r16 \n\t"
00246             "brne       d16u_2%= \n\t"
00247             "rjmp end%= \n\t"
00248             "d16u_2%=:" "rol r14 \n\t"
00249             "rol r15 \n\t"
00250             "sub r14,%A2 \n\t"
00251             "sbc r15,%B2 \n\t"
00252             "brcc       d16u_3%= \n\t"
00253             "add r14,%A2 \n\t"
00254             "adc r15,%B2 \n\t"
00255             "clc \n\t"
00256             "rjmp d16u_1%= \n\t"
00257             "d16u_3%=:" "sec \n\t"
00258             "rjmp d16u_1%= \n\t"
00259             "do32%=:" // divide full 32 bit
00260             "rjmp do32B%= \n\t"
00261             "do24%=:" // divide 24 bit
00262 
00263             "ldi r16,25 \n\t" // 24 Bit divide
00264             "d24u_1%=:" "rol %A0 \n\t"
00265             "rol %B0 \n\t"
00266             "rol %C0 \n\t"
00267             "dec r16 \n\t"
00268             "brne       d24u_2%= \n\t"
00269             "rjmp end%= \n\t"
00270             "d24u_2%=:" "rol r14 \n\t"
00271             "rol r15 \n\t"
00272             "sub r14,%A2 \n\t"
00273             "sbc r15,%B2 \n\t"
00274             "brcc       d24u_3%= \n\t"
00275             "add r14,%A2 \n\t"
00276             "adc r15,%B2 \n\t"
00277             "clc \n\t"
00278             "rjmp d24u_1%= \n\t"
00279             "d24u_3%=:" "sec \n\t"
00280             "rjmp d24u_1%= \n\t"
00281 
00282             "do32B%=:" // divide full 32 bit
00283 
00284             "ldi r16,33 \n\t" // 32 Bit divide
00285             "d32u_1%=:" "rol %A0 \n\t"
00286             "rol %B0 \n\t"
00287             "rol %C0 \n\t"
00288             "rol %D0 \n\t"
00289             "dec r16 \n\t"
00290             "brne       d32u_2%= \n\t"
00291             "rjmp end%= \n\t"
00292             "d32u_2%=:" "rol r14 \n\t"
00293             "rol r15 \n\t"
00294             "sub r14,%A2 \n\t"
00295             "sbc r15,%B2 \n\t"
00296             "brcc       d32u_3%= \n\t"
00297             "add r14,%A2 \n\t"
00298             "adc r15,%B2 \n\t"
00299             "clc \n\t"
00300             "rjmp d32u_1%= \n\t"
00301             "d32u_3%=:" "sec \n\t"
00302             "rjmp d32u_1%= \n\t"
00303 
00304             "end%=:" // end
00305             :"=&r"(a)
00306             :"0"(a),"r"(b)
00307             :"r14","r15","r16"
00308         );
00309         return a;
00310 #else
00311         return a/b;
00312 #endif
00313     }
00314     static inline unsigned long U16SquaredToU32(unsigned int val)
00315     {
00316         long res;
00317         __asm__ __volatile__ ( // 15 Ticks
00318             "mul %A1,%A1 \n\t"
00319             "movw %A0,r0 \n\t"
00320             "mul %B1,%B1 \n\t"
00321             "movw %C0,r0 \n\t"
00322             "mul %A1,%B1 \n\t"
00323             "clr %A1 \n\t"
00324             "add %B0,r0 \n\t"
00325             "adc %C0,r1 \n\t"
00326             "adc %D0,%A1 \n\t"
00327             "add %B0,r0 \n\t"
00328             "adc %C0,r1 \n\t"
00329             "adc %D0,%A1 \n\t"
00330             "clr r1 \n\t"
00331             : "=&r"(res),"=r"(val)
00332             : "1"(val)
00333         );
00334         return res;
00335     }
00336     static inline unsigned int ComputeV(long timer,long accel)
00337     {
00338 #if CPU_ARCH==ARCH_AVR
00339         unsigned int res;
00340         // 38 Ticks
00341         __asm__ __volatile__ ( // 0 = res, 1 = timer, 2 = accel %D2=0 ,%A1 are unused is free
00342             // Result LSB first: %A0, %B0, %A1
00343             "mul %B1,%A2 \n\t"
00344             "mov %A0,r1 \n\t"
00345             "mul %B1,%C2 \n\t"
00346             "mov %B0,r0 \n\t"
00347             "mov %A1,r1 \n\t"
00348             "mul %B1,%B2 \n\t"
00349             "add %A0,r0 \n\t"
00350             "adc %B0,r1 \n\t"
00351             "adc %A1,%D2 \n\t"
00352             "mul %C1,%A2 \n\t"
00353             "add %A0,r0 \n\t"
00354             "adc %B0,r1 \n\t"
00355             "adc %A1,%D2 \n\t"
00356             "mul %C1,%B2 \n\t"
00357             "add %B0,r0 \n\t"
00358             "adc %A1,r1 \n\t"
00359             "mul %D1,%A2 \n\t"
00360             "add %B0,r0 \n\t"
00361             "adc %A1,r1 \n\t"
00362             "mul %C1,%C2 \n\t"
00363             "add %A1,r0 \n\t"
00364             "mul %D1,%B2 \n\t"
00365             "add %A1,r0 \n\t"
00366             "lsr %A1 \n\t"
00367             "ror %B0 \n\t"
00368             "ror %A0 \n\t"
00369             "lsr %A1 \n\t"
00370             "ror %B0 \n\t"
00371             "ror %A0 \n\t"
00372             "clr r1 \n\t"
00373             :"=&r"(res),"=r"(timer),"=r"(accel)
00374             :"1"(timer),"2"(accel)
00375             : );
00376         // unsigned int v = ((timer>>8)*cur->accel)>>10;
00377         return res;
00378 #else
00379         return ((timer>>8)*accel)>>10;
00380 #endif
00381     }
00382 // Multiply two 16 bit values and return 32 bit result
00383     static inline unsigned long mulu16xu16to32(unsigned int a,unsigned int b)
00384     {
00385         unsigned long res;
00386         // 18 Ticks = 1.125 us
00387         __asm__ __volatile__ ( // 0 = res, 1 = timer, 2 = accel %D2=0 ,%A1 are unused is free
00388             // Result LSB first: %A0, %B0, %A1
00389             "clr r18 \n\t"
00390             "mul %B2,%B1 \n\t" // mul hig bytes
00391             "movw %C0,r0 \n\t"
00392             "mul %A1,%A2 \n\t" // mul low bytes
00393             "movw %A0,r0 \n\t"
00394             "mul %A1,%B2 \n\t"
00395             "add %B0,r0 \n\t"
00396             "adc %C0,r1 \n\t"
00397             "adc %D0,r18 \n\t"
00398             "mul %B1,%A2 \n\t"
00399             "add %B0,r0 \n\t"
00400             "adc %C0,r1 \n\t"
00401             "adc %D0,r18 \n\t"
00402             "clr r1 \n\t"
00403             :"=&r"(res),"=r"(a),"=r"(b)
00404             :"1"(a),"2"(b)
00405             :"r18" );
00406         // return (long)a*b;
00407         return res;
00408     }
00409 // Multiply two 16 bit values and return 32 bit result
00410     static inline unsigned int mulu6xu16shift16(unsigned int a,unsigned int b)
00411     {
00412 #if CPU_ARCH==ARCH_AVR
00413         unsigned int res;
00414         // 18 Ticks = 1.125 us
00415         __asm__ __volatile__ ( // 0 = res, 1 = timer, 2 = accel %D2=0 ,%A1 are unused is free
00416             // Result LSB first: %A0, %B0, %A1
00417             "clr r18 \n\t"
00418             "mul %B2,%B1 \n\t" // mul hig bytes
00419             "movw %A0,r0 \n\t"
00420             "mul %A1,%A2 \n\t" // mul low bytes
00421             "mov r19,r1 \n\t"
00422             "mul %A1,%B2 \n\t"
00423             "add r19,r0 \n\t"
00424             "adc %A0,r1 \n\t"
00425             "adc %B0,r18 \n\t"
00426             "mul %B1,%A2 \n\t"
00427             "add r19,r0 \n\t"
00428             "adc %A0,r1 \n\t"
00429             "adc %B0,r18 \n\t"
00430             "clr r1 \n\t"
00431             :"=&r"(res),"=r"(a),"=r"(b)
00432             :"1"(a),"2"(b)
00433             :"r18","r19" );
00434         return res;
00435 #else
00436         return ((long)a*b)>>16;
00437 #endif
00438     }
00439     static inline void digitalWrite(uint8_t pin,uint8_t value)
00440     {
00441         ::digitalWrite(pin,value);
00442     }
00443     static inline uint8_t digitalRead(uint8_t pin)
00444     {
00445         return ::digitalRead(pin);
00446     }
00447     static inline void pinMode(uint8_t pin,uint8_t mode)
00448     {
00449         ::pinMode(pin,mode);
00450     }
00451     static long CPUDivU2(unsigned int divisor);
00452     static inline void delayMicroseconds(unsigned int delayUs)
00453     {
00454         ::delayMicroseconds(delayUs);
00455     }
00456     static inline void delayMilliseconds(unsigned int delayMs)
00457     {
00458         ::delay(delayMs);
00459     }
00460     static inline void tone(uint8_t pin,int duration)
00461     {
00462         ::tone(pin,duration);
00463     }
00464     static inline void noTone(uint8_t pin)
00465     {
00466         ::noTone(pin);
00467     }
00468     static inline void eprSetByte(unsigned int pos,uint8_t value)
00469     {
00470         eeprom_write_byte((unsigned char *)(EEPROM_OFFSET+pos), value);
00471     }
00472     static inline void eprSetInt16(unsigned int pos,int16_t value)
00473     {
00474         eeprom_write_word((unsigned int*)(EEPROM_OFFSET+pos),value);
00475     }
00476     static inline void eprSetInt32(unsigned int pos,int32_t value)
00477     {
00478         eeprom_write_dword((uint32_t*)(EEPROM_OFFSET+pos),value);
00479     }
00480     static inline void eprSetFloat(unsigned int pos,float value)
00481     {
00482         eeprom_write_block(&value,(void*)(EEPROM_OFFSET+pos), 4);
00483     }
00484     static inline uint8_t eprGetByte(unsigned int pos)
00485     {
00486         return eeprom_read_byte ((unsigned char *)(EEPROM_OFFSET+pos));
00487     }
00488     static inline int16_t eprGetInt16(unsigned int pos)
00489     {
00490         return eeprom_read_word((uint16_t *)(EEPROM_OFFSET+pos));
00491     }
00492     static inline int32_t eprGetInt32(unsigned int pos)
00493     {
00494         return eeprom_read_dword((uint32_t*)(EEPROM_OFFSET+pos));
00495     }
00496     static inline float eprGetFloat(unsigned int pos)
00497     {
00498         float v;
00499         eeprom_read_block(&v,(void *)(EEPROM_OFFSET+pos),4); // newer gcc have eeprom_read_block but not arduino 22
00500         return v;
00501     }
00502     static inline void allowInterrupts()
00503     {
00504         sei();
00505     }
00506     static inline void forbidInterrupts()
00507     {
00508         cli();
00509     }
00510     static inline unsigned long timeInMilliseconds()
00511     {
00512         return millis();
00513     }
00514     static inline char readFlashByte(PGM_P ptr)
00515     {
00516         return pgm_read_byte(ptr);
00517     }
00518     static inline void serialSetBaudrate(long baud)
00519     {
00520         RFSERIAL.begin(baud);
00521     }
00522     static inline bool serialByteAvailable()
00523     {
00524         return RFSERIAL.available()>0;
00525     }
00526     static inline uint8_t serialReadByte()
00527     {
00528         return RFSERIAL.read();
00529     }
00530     static inline void serialWriteByte(char b)
00531     {
00532         RFSERIAL.write(b);
00533     }
00534     static inline void serialFlush()
00535     {
00536         RFSERIAL.flush();
00537     }
00538     static void setupTimer();
00539     static void showStartReason();
00540     static int getFreeRam();
00541     static void resetHardware();
00542 
00543     // SPI related functions
00544     static void spiBegin()
00545     {
00546         SET_INPUT(MISO_PIN);
00547         SET_OUTPUT(MOSI_PIN);
00548         SET_OUTPUT(SCK_PIN);
00549         // SS must be in output mode even it is not chip select
00550         SET_OUTPUT(SDSS);
00551 #if SDSSORIG >- 1
00552         SET_OUTPUT(SDSSORIG);
00553 #endif
00554         // set SS high - may be chip select for another SPI device
00555 #if SET_SPI_SS_HIGH
00556         WRITE(SDSS, HIGH);
00557 #endif  // SET_SPI_SS_HIGH
00558     }
00559     static inline void spiInit(uint8_t spiRate)
00560     {
00561         spiRate = spiRate > 12 ? 6 : spiRate/2;
00562         SET_OUTPUT(SS);
00563         WRITE(SS,HIGH);
00564         SET_OUTPUT(SCK);
00565         SET_OUTPUT(MOSI_PIN);
00566         SET_INPUT(MISO_PIN);
00567 #ifdef  PRR
00568         PRR &= ~(1<<PRSPI);
00569 #elif defined PRR0
00570         PRR0 &= ~(1<<PRSPI);
00571 #endif
00572         // See avr processor documentation
00573         SPCR = (1 << SPE) | (1 << MSTR) | (spiRate >> 1);
00574         SPSR = spiRate & 1 || spiRate == 6 ? 0 : 1 << SPI2X;
00575 
00576     }
00577     static inline uint8_t spiReceive(uint8_t send=0xff)
00578     {
00579         SPDR = send;
00580         while (!(SPSR & (1 << SPIF)));
00581         return SPDR;
00582     }
00583     static inline void spiReadBlock(uint8_t*buf,size_t nbyte)
00584     {
00585         if (nbyte-- == 0) return;
00586         SPDR = 0XFF;
00587         for (size_t i = 0; i < nbyte; i++)
00588         {
00589             while (!(SPSR & (1 << SPIF)));
00590             buf[i] = SPDR;
00591             SPDR = 0XFF;
00592         }
00593         while (!(SPSR & (1 << SPIF)));
00594         buf[nbyte] = SPDR;
00595     }
00596     static inline void spiSend(uint8_t b)
00597     {
00598         SPDR = b;
00599         while (!(SPSR & (1 << SPIF)));
00600     }
00601     static inline void spiSend(const uint8_t* buf , size_t n)
00602     {
00603         if (n == 0) return;
00604         SPDR = buf[0];
00605         if (n > 1)
00606         {
00607             uint8_t b = buf[1];
00608             size_t i = 2;
00609             while (1)
00610             {
00611                 while (!(SPSR & (1 << SPIF)));
00612                 SPDR = b;
00613                 if (i == n) break;
00614                 b = buf[i++];
00615             }
00616         }
00617         while (!(SPSR & (1 << SPIF)));
00618     }
00619 
00620     static inline __attribute__((always_inline))
00621     void spiSendBlock(uint8_t token, const uint8_t* buf)
00622     {
00623         SPDR = token;
00624         for (uint16_t i = 0; i < 512; i += 2)
00625         {
00626             while (!(SPSR & (1 << SPIF)));
00627             SPDR = buf[i];
00628             while (!(SPSR & (1 << SPIF)));
00629             SPDR = buf[i + 1];
00630         }
00631         while (!(SPSR & (1 << SPIF)));
00632     }
00633 
00634     // I2C Support
00635 
00636     static void i2cInit(unsigned long clockSpeedHz);
00637     static unsigned char i2cStart(unsigned char address);
00638     static void i2cStartWait(unsigned char address);
00639     static void i2cStop(void);
00640     static unsigned char i2cWrite( unsigned char data );
00641     static unsigned char i2cReadAck(void);
00642     static unsigned char i2cReadNak(void);
00643 
00644     // Watchdog support
00645 
00646     inline static void startWatchdog()
00647     {
00648         wdt_enable(WDTO_1S);
00649     };
00650     inline static void stopWatchdog()
00651     {
00652         wdt_disable();
00653     }
00654     inline static void pingWatchdog()
00655     {
00656         wdt_reset();
00657     };
00658     inline static float maxExtruderTimerFrequency()
00659     {
00660         return (float)F_CPU/TIMER0_PRESCALE;
00661     }
00662 #if FEATURE_SERVO
00663     static unsigned int servoTimings[4];
00664     static void servoMicroseconds(uint8_t servo,int ms);
00665 #endif
00666     static void analogStart();
00667 protected:
00668 private:
00669 };
00670 /*#if MOTHERBOARD==6 || MOTHERBOARD==62 || MOTHERBOARD==7
00671 #if MOTHERBOARD!=7
00672 #define SIMULATE_PWM
00673 #endif
00674 #define EXTRUDER_TIMER_VECTOR TIMER2_COMPA_vect
00675 #define EXTRUDER_OCR OCR2A
00676 #define EXTRUDER_TCCR TCCR2A
00677 #define EXTRUDER_TIMSK TIMSK2
00678 #define EXTRUDER_OCIE OCIE2A
00679 #define PWM_TIMER_VECTOR TIMER2_COMPB_vect
00680 #define PWM_OCR OCR2B
00681 #define PWM_TCCR TCCR2B
00682 #define PWM_TIMSK TIMSK2
00683 #define PWM_OCIE OCIE2B
00684 #else*/
00685 #define EXTRUDER_TIMER_VECTOR TIMER0_COMPA_vect
00686 #define EXTRUDER_OCR OCR0A
00687 #define EXTRUDER_TCCR TCCR0A
00688 #define EXTRUDER_TIMSK TIMSK0
00689 #define EXTRUDER_OCIE OCIE0A
00690 #define PWM_TIMER_VECTOR TIMER0_COMPB_vect
00691 #define PWM_OCR OCR0B
00692 #define PWM_TCCR TCCR0A
00693 #define PWM_TIMSK TIMSK0
00694 #define PWM_OCIE OCIE0B
00695 //#endif
00696 #endif // HAL_H
 All Data Structures Namespaces Files Functions Variables Typedefs Friends Defines