Encoder.h
Go to the documentation of this file.
00001 /* Encoder Library, for measuring quadrature encoded signals
00002  * http://www.pjrc.com/teensy/td_libs_Encoder.html
00003  * Copyright (c) 2011,2013 PJRC.COM, LLC - Paul Stoffregen <paul@pjrc.com>
00004  *
00005  * Version 1.1 - expand to support boards with up to 60 interrupts
00006  * Version 1.0 - initial release
00007  * 
00008  * Permission is hereby granted, free of charge, to any person obtaining a copy
00009  * of this software and associated documentation files (the "Software"), to deal
00010  * in the Software without restriction, including without limitation the rights
00011  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00012  * copies of the Software, and to permit persons to whom the Software is
00013  * furnished to do so, subject to the following conditions:
00014  * 
00015  * The above copyright notice and this permission notice shall be included in
00016  * all copies or substantial portions of the Software.
00017  * 
00018  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00019  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00020  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00021  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00022  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00023  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00024  * THE SOFTWARE.
00025  */
00026 
00027 
00028 #ifndef Encoder_h_
00029 #define Encoder_h_
00030 
00031 #if defined(ARDUINO) && ARDUINO >= 100
00032 #include "Arduino.h"
00033 #elif defined(WIRING)
00034 #include "Wiring.h"
00035 #else
00036 #include "WProgram.h"
00037 #include "pins_arduino.h"
00038 #endif
00039 
00040 #include "utility/direct_pin_read.h"
00041 
00042 #if defined(ENCODER_USE_INTERRUPTS) || !defined(ENCODER_DO_NOT_USE_INTERRUPTS)
00043 #define ENCODER_USE_INTERRUPTS
00044 #define ENCODER_ARGLIST_SIZE CORE_NUM_INTERRUPT
00045 #include "utility/interrupt_pins.h"
00046 #ifdef ENCODER_OPTIMIZE_INTERRUPTS
00047 #include "utility/interrupt_config.h"
00048 #endif
00049 #else
00050 #define ENCODER_ARGLIST_SIZE 0
00051 #endif
00052 
00053 
00054 
00055 // All the data needed by interrupts is consolidated into this ugly struct
00056 // to facilitate assembly language optimizing of the speed critical update.
00057 // The assembly code uses auto-incrementing addressing modes, so the struct
00058 // must remain in exactly this order.
00059 typedef struct {
00060   volatile IO_REG_TYPE * pin1_register;
00061   volatile IO_REG_TYPE * pin2_register;
00062   IO_REG_TYPE            pin1_bitmask;
00063   IO_REG_TYPE            pin2_bitmask;
00064   uint8_t                state;
00065   int32_t                position;
00066 } Encoder_internal_state_t;
00067 
00068 class Encoder
00069 {
00070 public:
00071   Encoder(uint8_t pin1, uint8_t pin2)
00072   {
00073 #ifdef INPUT_PULLUP
00074     pinMode(pin1, INPUT_PULLUP);
00075     pinMode(pin2, INPUT_PULLUP);
00076 #else
00077     pinMode(pin1, INPUT);
00078     digitalWrite(pin1, HIGH);
00079     pinMode(pin2, INPUT);
00080     digitalWrite(pin2, HIGH);
00081 #endif
00082     encoder.pin1_register = PIN_TO_BASEREG(pin1);
00083     encoder.pin1_bitmask = PIN_TO_BITMASK(pin1);
00084     encoder.pin2_register = PIN_TO_BASEREG(pin2);
00085     encoder.pin2_bitmask = PIN_TO_BITMASK(pin2);
00086     encoder.position = 0;
00087     // allow time for a passive R-C filter to charge
00088     // through the pullup resistors, before reading
00089     // the initial state
00090     delayMicroseconds(2000);
00091     uint8_t s = 0;
00092     if (DIRECT_PIN_READ(encoder.pin1_register, encoder.pin1_bitmask)) s |= 1;
00093     if (DIRECT_PIN_READ(encoder.pin2_register, encoder.pin2_bitmask)) s |= 2;
00094     encoder.state = s;
00095 #ifdef ENCODER_USE_INTERRUPTS
00096     interrupts_in_use = attach_interrupt(pin1, &encoder);
00097     interrupts_in_use += attach_interrupt(pin2, &encoder);
00098 #endif
00099     //update_finishup();  // to force linker to include the code (does not work)
00100   }
00101 
00102 
00103 #ifdef ENCODER_USE_INTERRUPTS
00104   inline int32_t read()
00105   {
00106     if (interrupts_in_use < 2) {
00107       noInterrupts();
00108       update(&encoder);
00109     } else {
00110       noInterrupts();
00111     }
00112     int32_t ret = encoder.position;
00113     interrupts();
00114     return ret;
00115   }
00116   inline void write(int32_t p)
00117   {
00118     noInterrupts();
00119     encoder.position = p;
00120     interrupts();
00121   }
00122 #else
00123   inline int32_t read()
00124   {
00125     update(&encoder);
00126     return encoder.position;
00127   }
00128   inline void write(int32_t p)
00129   {
00130     encoder.position = p;
00131   }
00132 #endif
00133 private:
00134   Encoder_internal_state_t encoder;
00135 #ifdef ENCODER_USE_INTERRUPTS
00136   uint8_t interrupts_in_use;
00137 #endif
00138 public:
00139   static Encoder_internal_state_t * interruptArgs[ENCODER_ARGLIST_SIZE];
00140 
00141 //                           _______         _______       
00142 //               Pin1 ______|       |_______|       |______ Pin1
00143 // negative <---         _______         _______         __      --> positive
00144 //               Pin2 __|       |_______|       |_______|   Pin2
00145 
00146   //    new     new     old     old
00147   //    pin2    pin1    pin2    pin1    Result
00148   //    ----    ----    ----    ----    ------
00149   //    0       0       0       0       no movement
00150   //    0       0       0       1       +1
00151   //    0       0       1       0       -1
00152   //    0       0       1       1       +2  (assume pin1 edges only)
00153   //    0       1       0       0       -1
00154   //    0       1       0       1       no movement
00155   //    0       1       1       0       -2  (assume pin1 edges only)
00156   //    0       1       1       1       +1
00157   //    1       0       0       0       +1
00158   //    1       0       0       1       -2  (assume pin1 edges only)
00159   //    1       0       1       0       no movement
00160   //    1       0       1       1       -1
00161   //    1       1       0       0       +2  (assume pin1 edges only)
00162   //    1       1       0       1       -1
00163   //    1       1       1       0       +1
00164   //    1       1       1       1       no movement
00165 /*
00166 // Simple, easy-to-read "documentation" version :-)
00167 //
00168 void update(void) {
00169 uint8_t s = state & 3;
00170 if (digitalRead(pin1)) s |= 4;
00171 if (digitalRead(pin2)) s |= 8;
00172 switch (s) {
00173 case 0: case 5: case 10: case 15:
00174 break;
00175 case 1: case 7: case 8: case 14:
00176 position++; break;
00177 case 2: case 4: case 11: case 13:
00178 position--; break;
00179 case 3: case 12:
00180 position += 2; break;
00181 default:
00182 position -= 2; break;
00183 }
00184 state = (s >> 2);
00185 }
00186 */
00187 
00188 private:
00189   static void update(Encoder_internal_state_t *arg)
00190   {
00191 #if defined(__AVR__)
00192     // The compiler believes this is just 1 line of code, so
00193     // it will inline this function into each interrupt
00194     // handler.  That's a tiny bit faster, but grows the code.
00195     // Especially when used with ENCODER_OPTIMIZE_INTERRUPTS,
00196     // the inline nature allows the ISR prologue and epilogue
00197     // to only save/restore necessary registers, for very nice
00198     // speed increase.
00199     asm volatile (
00200       "ld       r30, X+"                "\n\t"
00201       "ld       r31, X+"                "\n\t"
00202       "ld       r24, Z"                 "\n\t"  // r24 = pin1 input
00203       "ld       r30, X+"                "\n\t"
00204       "ld       r31, X+"                "\n\t"
00205       "ld       r25, Z"                 "\n\t"  // r25 = pin2 input
00206       "ld       r30, X+"                "\n\t"  // r30 = pin1 mask
00207       "ld       r31, X+"                "\n\t"  // r31 = pin2 mask
00208       "ld       r22, X"                 "\n\t"  // r22 = state
00209       "andi     r22, 3"                 "\n\t"
00210       "and      r24, r30"               "\n\t"
00211       "breq     L%=1"                   "\n\t"  // if (pin1)
00212       "ori      r22, 4"                 "\n\t"  //      state |= 4
00213       "L%=1:"   "and    r25, r31"               "\n\t"
00214       "breq     L%=2"                   "\n\t"  // if (pin2)
00215       "ori      r22, 8"                 "\n\t"  //      state |= 8
00216       "L%=2:" "ldi      r30, lo8(pm(L%=table))" "\n\t"
00217       "ldi      r31, hi8(pm(L%=table))" "\n\t"
00218       "add      r30, r22"               "\n\t"
00219       "adc      r31, __zero_reg__"      "\n\t"
00220       "asr      r22"                    "\n\t"
00221       "asr      r22"                    "\n\t"
00222       "st       X+, r22"                "\n\t"  // store new state
00223       "ld       r22, X+"                "\n\t"
00224       "ld       r23, X+"                "\n\t"
00225       "ld       r24, X+"                "\n\t"
00226       "ld       r25, X+"                "\n\t"
00227       "ijmp"                            "\n\t"  // jumps to update_finishup()
00228       // TODO move this table to another static function,
00229       // so it doesn't get needlessly duplicated.  Easier
00230       // said than done, due to linker issues and inlining
00231       "L%=table:"                               "\n\t"
00232       "rjmp     L%=end"                 "\n\t"  // 0
00233       "rjmp     L%=plus1"               "\n\t"  // 1
00234       "rjmp     L%=minus1"              "\n\t"  // 2
00235       "rjmp     L%=plus2"               "\n\t"  // 3
00236       "rjmp     L%=minus1"              "\n\t"  // 4
00237       "rjmp     L%=end"                 "\n\t"  // 5
00238       "rjmp     L%=minus2"              "\n\t"  // 6
00239       "rjmp     L%=plus1"               "\n\t"  // 7
00240       "rjmp     L%=plus1"               "\n\t"  // 8
00241       "rjmp     L%=minus2"              "\n\t"  // 9
00242       "rjmp     L%=end"                 "\n\t"  // 10
00243       "rjmp     L%=minus1"              "\n\t"  // 11
00244       "rjmp     L%=plus2"               "\n\t"  // 12
00245       "rjmp     L%=minus1"              "\n\t"  // 13
00246       "rjmp     L%=plus1"               "\n\t"  // 14
00247       "rjmp     L%=end"                 "\n\t"  // 15
00248       "L%=minus2:"                              "\n\t"
00249       "subi     r22, 2"                 "\n\t"
00250       "sbci     r23, 0"                 "\n\t"
00251       "sbci     r24, 0"                 "\n\t"
00252       "sbci     r25, 0"                 "\n\t"
00253       "rjmp     L%=store"               "\n\t"
00254       "L%=minus1:"                              "\n\t"
00255       "subi     r22, 1"                 "\n\t"
00256       "sbci     r23, 0"                 "\n\t"
00257       "sbci     r24, 0"                 "\n\t"
00258       "sbci     r25, 0"                 "\n\t"
00259       "rjmp     L%=store"               "\n\t"
00260       "L%=plus2:"                               "\n\t"
00261       "subi     r22, 254"               "\n\t"
00262       "rjmp     L%=z"                   "\n\t"
00263       "L%=plus1:"                               "\n\t"
00264       "subi     r22, 255"               "\n\t"
00265       "L%=z:"   "sbci   r23, 255"               "\n\t"
00266       "sbci     r24, 255"               "\n\t"
00267       "sbci     r25, 255"               "\n\t"
00268       "L%=store:"                               "\n\t"
00269       "st       -X, r25"                "\n\t"
00270       "st       -X, r24"                "\n\t"
00271       "st       -X, r23"                "\n\t"
00272       "st       -X, r22"                "\n\t"
00273       "L%=end:"                         "\n"
00274       : : "x" (arg) : "r22", "r23", "r24", "r25", "r30", "r31");
00275 #else
00276     uint8_t p1val = DIRECT_PIN_READ(arg->pin1_register, arg->pin1_bitmask);
00277     uint8_t p2val = DIRECT_PIN_READ(arg->pin2_register, arg->pin2_bitmask);
00278     uint8_t state = arg->state & 3;
00279     if (p1val) state |= 4;
00280     if (p2val) state |= 8;
00281     arg->state = (state >> 2);
00282     switch (state)
00283     {
00284     case 1: case 7: case 8: case 14:
00285       arg->position++;
00286       return;
00287     case 2: case 4: case 11: case 13:
00288       arg->position--;
00289       return;
00290     case 3: case 12:
00291       arg->position += 2;
00292       return;
00293     case 6: case 9:
00294       arg->position += 2;
00295       return;
00296     }
00297 #endif
00298   }
00299 /*
00300   #if defined(__AVR__)
00301   // TODO: this must be a no inline function
00302   // even noinline does not seem to solve difficult
00303   // problems with this.  Oh well, it was only meant
00304   // to shrink code size - there's no performance
00305   // improvement in this, only code size reduction.
00306   __attribute__((noinline)) void update_finishup(void) {
00307   asm volatile (
00308   "ldi  r30, lo8(pm(Ltable))"   "\n\t"
00309   "ldi  r31, hi8(pm(Ltable))"   "\n\t"
00310   "Ltable:"                             "\n\t"
00311   "rjmp L%=end"                 "\n\t"  // 0
00312   "rjmp L%=plus1"               "\n\t"  // 1
00313   "rjmp L%=minus1"              "\n\t"  // 2
00314   "rjmp L%=plus2"               "\n\t"  // 3
00315   "rjmp L%=minus1"              "\n\t"  // 4
00316   "rjmp L%=end"                 "\n\t"  // 5
00317   "rjmp L%=minus2"              "\n\t"  // 6
00318   "rjmp L%=plus1"               "\n\t"  // 7
00319   "rjmp L%=plus1"               "\n\t"  // 8
00320   "rjmp L%=minus2"              "\n\t"  // 9
00321   "rjmp L%=end"                 "\n\t"  // 10
00322   "rjmp L%=minus1"              "\n\t"  // 11
00323   "rjmp L%=plus2"               "\n\t"  // 12
00324   "rjmp L%=minus1"              "\n\t"  // 13
00325   "rjmp L%=plus1"               "\n\t"  // 14
00326   "rjmp L%=end"                 "\n\t"  // 15
00327   "L%=minus2:"                          "\n\t"
00328   "subi r22, 2"                 "\n\t"
00329   "sbci r23, 0"                 "\n\t"
00330   "sbci r24, 0"                 "\n\t"
00331   "sbci r25, 0"                 "\n\t"
00332   "rjmp L%=store"               "\n\t"
00333   "L%=minus1:"                          "\n\t"
00334   "subi r22, 1"                 "\n\t"
00335   "sbci r23, 0"                 "\n\t"
00336   "sbci r24, 0"                 "\n\t"
00337   "sbci r25, 0"                 "\n\t"
00338   "rjmp L%=store"               "\n\t"
00339   "L%=plus2:"                           "\n\t"
00340   "subi r22, 254"               "\n\t"
00341   "rjmp L%=z"                   "\n\t"
00342   "L%=plus1:"                           "\n\t"
00343   "subi r22, 255"               "\n\t"
00344   "L%=z:"       "sbci   r23, 255"               "\n\t"
00345   "sbci r24, 255"               "\n\t"
00346   "sbci r25, 255"               "\n\t"
00347   "L%=store:"                           "\n\t"
00348   "st   -X, r25"                "\n\t"
00349   "st   -X, r24"                "\n\t"
00350   "st   -X, r23"                "\n\t"
00351   "st   -X, r22"                "\n\t"
00352   "L%=end:"                             "\n"
00353   : : : "r22", "r23", "r24", "r25", "r30", "r31");
00354   }
00355   #endif
00356 */
00357 
00358 
00359 #ifdef ENCODER_USE_INTERRUPTS
00360   // this giant function is an unfortunate consequence of Arduino's
00361   // attachInterrupt function not supporting any way to pass a pointer
00362   // or other context to the attached function.
00363   static uint8_t attach_interrupt(uint8_t pin, Encoder_internal_state_t *state)
00364   {
00365     switch (pin)
00366     {
00367 #ifdef CORE_INT0_PIN
00368     case CORE_INT0_PIN:
00369       interruptArgs[0] = state;
00370       attachInterrupt(0, isr0, CHANGE);
00371       break;
00372 #endif
00373 #ifdef CORE_INT1_PIN
00374     case CORE_INT1_PIN:
00375       interruptArgs[1] = state;
00376       attachInterrupt(1, isr1, CHANGE);
00377       break;
00378 #endif
00379 #ifdef CORE_INT2_PIN
00380     case CORE_INT2_PIN:
00381       interruptArgs[2] = state;
00382       attachInterrupt(2, isr2, CHANGE);
00383       break;
00384 #endif
00385 #ifdef CORE_INT3_PIN
00386     case CORE_INT3_PIN:
00387       interruptArgs[3] = state;
00388       attachInterrupt(3, isr3, CHANGE);
00389       break;
00390 #endif
00391 #ifdef CORE_INT4_PIN
00392     case CORE_INT4_PIN:
00393       interruptArgs[4] = state;
00394       attachInterrupt(4, isr4, CHANGE);
00395       break;
00396 #endif
00397 #ifdef CORE_INT5_PIN
00398     case CORE_INT5_PIN:
00399       interruptArgs[5] = state;
00400       attachInterrupt(5, isr5, CHANGE);
00401       break;
00402 #endif
00403 #ifdef CORE_INT6_PIN
00404     case CORE_INT6_PIN:
00405       interruptArgs[6] = state;
00406       attachInterrupt(6, isr6, CHANGE);
00407       break;
00408 #endif
00409 #ifdef CORE_INT7_PIN
00410     case CORE_INT7_PIN:
00411       interruptArgs[7] = state;
00412       attachInterrupt(7, isr7, CHANGE);
00413       break;
00414 #endif
00415 #ifdef CORE_INT8_PIN
00416     case CORE_INT8_PIN:
00417       interruptArgs[8] = state;
00418       attachInterrupt(8, isr8, CHANGE);
00419       break;
00420 #endif
00421 #ifdef CORE_INT9_PIN
00422     case CORE_INT9_PIN:
00423       interruptArgs[9] = state;
00424       attachInterrupt(9, isr9, CHANGE);
00425       break;
00426 #endif
00427 #ifdef CORE_INT10_PIN
00428     case CORE_INT10_PIN:
00429       interruptArgs[10] = state;
00430       attachInterrupt(10, isr10, CHANGE);
00431       break;
00432 #endif
00433 #ifdef CORE_INT11_PIN
00434     case CORE_INT11_PIN:
00435       interruptArgs[11] = state;
00436       attachInterrupt(11, isr11, CHANGE);
00437       break;
00438 #endif
00439 #ifdef CORE_INT12_PIN
00440     case CORE_INT12_PIN:
00441       interruptArgs[12] = state;
00442       attachInterrupt(12, isr12, CHANGE);
00443       break;
00444 #endif
00445 #ifdef CORE_INT13_PIN
00446     case CORE_INT13_PIN:
00447       interruptArgs[13] = state;
00448       attachInterrupt(13, isr13, CHANGE);
00449       break;
00450 #endif
00451 #ifdef CORE_INT14_PIN
00452     case CORE_INT14_PIN:
00453       interruptArgs[14] = state;
00454       attachInterrupt(14, isr14, CHANGE);
00455       break;
00456 #endif
00457 #ifdef CORE_INT15_PIN
00458     case CORE_INT15_PIN:
00459       interruptArgs[15] = state;
00460       attachInterrupt(15, isr15, CHANGE);
00461       break;
00462 #endif
00463 #ifdef CORE_INT16_PIN
00464     case CORE_INT16_PIN:
00465       interruptArgs[16] = state;
00466       attachInterrupt(16, isr16, CHANGE);
00467       break;
00468 #endif
00469 #ifdef CORE_INT17_PIN
00470     case CORE_INT17_PIN:
00471       interruptArgs[17] = state;
00472       attachInterrupt(17, isr17, CHANGE);
00473       break;
00474 #endif
00475 #ifdef CORE_INT18_PIN
00476     case CORE_INT18_PIN:
00477       interruptArgs[18] = state;
00478       attachInterrupt(18, isr18, CHANGE);
00479       break;
00480 #endif
00481 #ifdef CORE_INT19_PIN
00482     case CORE_INT19_PIN:
00483       interruptArgs[19] = state;
00484       attachInterrupt(19, isr19, CHANGE);
00485       break;
00486 #endif
00487 #ifdef CORE_INT20_PIN
00488     case CORE_INT20_PIN:
00489       interruptArgs[20] = state;
00490       attachInterrupt(20, isr20, CHANGE);
00491       break;
00492 #endif
00493 #ifdef CORE_INT21_PIN
00494     case CORE_INT21_PIN:
00495       interruptArgs[21] = state;
00496       attachInterrupt(21, isr21, CHANGE);
00497       break;
00498 #endif
00499 #ifdef CORE_INT22_PIN
00500     case CORE_INT22_PIN:
00501       interruptArgs[22] = state;
00502       attachInterrupt(22, isr22, CHANGE);
00503       break;
00504 #endif
00505 #ifdef CORE_INT23_PIN
00506     case CORE_INT23_PIN:
00507       interruptArgs[23] = state;
00508       attachInterrupt(23, isr23, CHANGE);
00509       break;
00510 #endif
00511 #ifdef CORE_INT24_PIN
00512     case CORE_INT24_PIN:
00513       interruptArgs[24] = state;
00514       attachInterrupt(24, isr24, CHANGE);
00515       break;
00516 #endif
00517 #ifdef CORE_INT25_PIN
00518     case CORE_INT25_PIN:
00519       interruptArgs[25] = state;
00520       attachInterrupt(25, isr25, CHANGE);
00521       break;
00522 #endif
00523 #ifdef CORE_INT26_PIN
00524     case CORE_INT26_PIN:
00525       interruptArgs[26] = state;
00526       attachInterrupt(26, isr26, CHANGE);
00527       break;
00528 #endif
00529 #ifdef CORE_INT27_PIN
00530     case CORE_INT27_PIN:
00531       interruptArgs[27] = state;
00532       attachInterrupt(27, isr27, CHANGE);
00533       break;
00534 #endif
00535 #ifdef CORE_INT28_PIN
00536     case CORE_INT28_PIN:
00537       interruptArgs[28] = state;
00538       attachInterrupt(28, isr28, CHANGE);
00539       break;
00540 #endif
00541 #ifdef CORE_INT29_PIN
00542     case CORE_INT29_PIN:
00543       interruptArgs[29] = state;
00544       attachInterrupt(29, isr29, CHANGE);
00545       break;
00546 #endif
00547 
00548 #ifdef CORE_INT30_PIN
00549     case CORE_INT30_PIN:
00550       interruptArgs[30] = state;
00551       attachInterrupt(30, isr30, CHANGE);
00552       break;
00553 #endif
00554 #ifdef CORE_INT31_PIN
00555     case CORE_INT31_PIN:
00556       interruptArgs[31] = state;
00557       attachInterrupt(31, isr31, CHANGE);
00558       break;
00559 #endif
00560 #ifdef CORE_INT32_PIN
00561     case CORE_INT32_PIN:
00562       interruptArgs[32] = state;
00563       attachInterrupt(32, isr32, CHANGE);
00564       break;
00565 #endif
00566 #ifdef CORE_INT33_PIN
00567     case CORE_INT33_PIN:
00568       interruptArgs[33] = state;
00569       attachInterrupt(33, isr33, CHANGE);
00570       break;
00571 #endif
00572 #ifdef CORE_INT34_PIN
00573     case CORE_INT34_PIN:
00574       interruptArgs[34] = state;
00575       attachInterrupt(34, isr34, CHANGE);
00576       break;
00577 #endif
00578 #ifdef CORE_INT35_PIN
00579     case CORE_INT35_PIN:
00580       interruptArgs[35] = state;
00581       attachInterrupt(35, isr35, CHANGE);
00582       break;
00583 #endif
00584 #ifdef CORE_INT36_PIN
00585     case CORE_INT36_PIN:
00586       interruptArgs[36] = state;
00587       attachInterrupt(36, isr36, CHANGE);
00588       break;
00589 #endif
00590 #ifdef CORE_INT37_PIN
00591     case CORE_INT37_PIN:
00592       interruptArgs[37] = state;
00593       attachInterrupt(37, isr37, CHANGE);
00594       break;
00595 #endif
00596 #ifdef CORE_INT38_PIN
00597     case CORE_INT38_PIN:
00598       interruptArgs[38] = state;
00599       attachInterrupt(38, isr38, CHANGE);
00600       break;
00601 #endif
00602 #ifdef CORE_INT39_PIN
00603     case CORE_INT39_PIN:
00604       interruptArgs[39] = state;
00605       attachInterrupt(39, isr39, CHANGE);
00606       break;
00607 #endif
00608 #ifdef CORE_INT40_PIN
00609     case CORE_INT40_PIN:
00610       interruptArgs[40] = state;
00611       attachInterrupt(40, isr40, CHANGE);
00612       break;
00613 #endif
00614 #ifdef CORE_INT41_PIN
00615     case CORE_INT41_PIN:
00616       interruptArgs[41] = state;
00617       attachInterrupt(41, isr41, CHANGE);
00618       break;
00619 #endif
00620 #ifdef CORE_INT42_PIN
00621     case CORE_INT42_PIN:
00622       interruptArgs[42] = state;
00623       attachInterrupt(42, isr42, CHANGE);
00624       break;
00625 #endif
00626 #ifdef CORE_INT43_PIN
00627     case CORE_INT43_PIN:
00628       interruptArgs[43] = state;
00629       attachInterrupt(43, isr43, CHANGE);
00630       break;
00631 #endif
00632 #ifdef CORE_INT44_PIN
00633     case CORE_INT44_PIN:
00634       interruptArgs[44] = state;
00635       attachInterrupt(44, isr44, CHANGE);
00636       break;
00637 #endif
00638 #ifdef CORE_INT45_PIN
00639     case CORE_INT45_PIN:
00640       interruptArgs[45] = state;
00641       attachInterrupt(45, isr45, CHANGE);
00642       break;
00643 #endif
00644 #ifdef CORE_INT46_PIN
00645     case CORE_INT46_PIN:
00646       interruptArgs[46] = state;
00647       attachInterrupt(46, isr46, CHANGE);
00648       break;
00649 #endif
00650 #ifdef CORE_INT47_PIN
00651     case CORE_INT47_PIN:
00652       interruptArgs[47] = state;
00653       attachInterrupt(47, isr47, CHANGE);
00654       break;
00655 #endif
00656 #ifdef CORE_INT48_PIN
00657     case CORE_INT48_PIN:
00658       interruptArgs[48] = state;
00659       attachInterrupt(48, isr48, CHANGE);
00660       break;
00661 #endif
00662 #ifdef CORE_INT49_PIN
00663     case CORE_INT49_PIN:
00664       interruptArgs[49] = state;
00665       attachInterrupt(49, isr49, CHANGE);
00666       break;
00667 #endif
00668 #ifdef CORE_INT50_PIN
00669     case CORE_INT50_PIN:
00670       interruptArgs[50] = state;
00671       attachInterrupt(50, isr50, CHANGE);
00672       break;
00673 #endif
00674 #ifdef CORE_INT51_PIN
00675     case CORE_INT51_PIN:
00676       interruptArgs[51] = state;
00677       attachInterrupt(51, isr51, CHANGE);
00678       break;
00679 #endif
00680 #ifdef CORE_INT52_PIN
00681     case CORE_INT52_PIN:
00682       interruptArgs[52] = state;
00683       attachInterrupt(52, isr52, CHANGE);
00684       break;
00685 #endif
00686 #ifdef CORE_INT53_PIN
00687     case CORE_INT53_PIN:
00688       interruptArgs[53] = state;
00689       attachInterrupt(53, isr53, CHANGE);
00690       break;
00691 #endif
00692 #ifdef CORE_INT54_PIN
00693     case CORE_INT54_PIN:
00694       interruptArgs[54] = state;
00695       attachInterrupt(54, isr54, CHANGE);
00696       break;
00697 #endif
00698 #ifdef CORE_INT55_PIN
00699     case CORE_INT55_PIN:
00700       interruptArgs[55] = state;
00701       attachInterrupt(55, isr55, CHANGE);
00702       break;
00703 #endif
00704 #ifdef CORE_INT56_PIN
00705     case CORE_INT56_PIN:
00706       interruptArgs[56] = state;
00707       attachInterrupt(56, isr56, CHANGE);
00708       break;
00709 #endif
00710 #ifdef CORE_INT57_PIN
00711     case CORE_INT57_PIN:
00712       interruptArgs[57] = state;
00713       attachInterrupt(57, isr57, CHANGE);
00714       break;
00715 #endif
00716 #ifdef CORE_INT58_PIN
00717     case CORE_INT58_PIN:
00718       interruptArgs[58] = state;
00719       attachInterrupt(58, isr58, CHANGE);
00720       break;
00721 #endif
00722 #ifdef CORE_INT59_PIN
00723     case CORE_INT59_PIN:
00724       interruptArgs[59] = state;
00725       attachInterrupt(59, isr59, CHANGE);
00726       break;
00727 #endif
00728     default:
00729       return 0;
00730     }
00731     return 1;
00732   }
00733 #endif // ENCODER_USE_INTERRUPTS
00734 
00735 
00736 #if defined(ENCODER_USE_INTERRUPTS) && !defined(ENCODER_OPTIMIZE_INTERRUPTS)
00737 #ifdef CORE_INT0_PIN
00738   static void isr0(void) { update(interruptArgs[0]); }
00739 #endif
00740 #ifdef CORE_INT1_PIN
00741   static void isr1(void) { update(interruptArgs[1]); }
00742 #endif
00743 #ifdef CORE_INT2_PIN
00744   static void isr2(void) { update(interruptArgs[2]); }
00745 #endif
00746 #ifdef CORE_INT3_PIN
00747   static void isr3(void) { update(interruptArgs[3]); }
00748 #endif
00749 #ifdef CORE_INT4_PIN
00750   static void isr4(void) { update(interruptArgs[4]); }
00751 #endif
00752 #ifdef CORE_INT5_PIN
00753   static void isr5(void) { update(interruptArgs[5]); }
00754 #endif
00755 #ifdef CORE_INT6_PIN
00756   static void isr6(void) { update(interruptArgs[6]); }
00757 #endif
00758 #ifdef CORE_INT7_PIN
00759   static void isr7(void) { update(interruptArgs[7]); }
00760 #endif
00761 #ifdef CORE_INT8_PIN
00762   static void isr8(void) { update(interruptArgs[8]); }
00763 #endif
00764 #ifdef CORE_INT9_PIN
00765   static void isr9(void) { update(interruptArgs[9]); }
00766 #endif
00767 #ifdef CORE_INT10_PIN
00768   static void isr10(void) { update(interruptArgs[10]); }
00769 #endif
00770 #ifdef CORE_INT11_PIN
00771   static void isr11(void) { update(interruptArgs[11]); }
00772 #endif
00773 #ifdef CORE_INT12_PIN
00774   static void isr12(void) { update(interruptArgs[12]); }
00775 #endif
00776 #ifdef CORE_INT13_PIN
00777   static void isr13(void) { update(interruptArgs[13]); }
00778 #endif
00779 #ifdef CORE_INT14_PIN
00780   static void isr14(void) { update(interruptArgs[14]); }
00781 #endif
00782 #ifdef CORE_INT15_PIN
00783   static void isr15(void) { update(interruptArgs[15]); }
00784 #endif
00785 #ifdef CORE_INT16_PIN
00786   static void isr16(void) { update(interruptArgs[16]); }
00787 #endif
00788 #ifdef CORE_INT17_PIN
00789   static void isr17(void) { update(interruptArgs[17]); }
00790 #endif
00791 #ifdef CORE_INT18_PIN
00792   static void isr18(void) { update(interruptArgs[18]); }
00793 #endif
00794 #ifdef CORE_INT19_PIN
00795   static void isr19(void) { update(interruptArgs[19]); }
00796 #endif
00797 #ifdef CORE_INT20_PIN
00798   static void isr20(void) { update(interruptArgs[20]); }
00799 #endif
00800 #ifdef CORE_INT21_PIN
00801   static void isr21(void) { update(interruptArgs[21]); }
00802 #endif
00803 #ifdef CORE_INT22_PIN
00804   static void isr22(void) { update(interruptArgs[22]); }
00805 #endif
00806 #ifdef CORE_INT23_PIN
00807   static void isr23(void) { update(interruptArgs[23]); }
00808 #endif
00809 #ifdef CORE_INT24_PIN
00810   static void isr24(void) { update(interruptArgs[24]); }
00811 #endif
00812 #ifdef CORE_INT25_PIN
00813   static void isr25(void) { update(interruptArgs[25]); }
00814 #endif
00815 #ifdef CORE_INT26_PIN
00816   static void isr26(void) { update(interruptArgs[26]); }
00817 #endif
00818 #ifdef CORE_INT27_PIN
00819   static void isr27(void) { update(interruptArgs[27]); }
00820 #endif
00821 #ifdef CORE_INT28_PIN
00822   static void isr28(void) { update(interruptArgs[28]); }
00823 #endif
00824 #ifdef CORE_INT29_PIN
00825   static void isr29(void) { update(interruptArgs[29]); }
00826 #endif
00827 #ifdef CORE_INT30_PIN
00828   static void isr30(void) { update(interruptArgs[30]); }
00829 #endif
00830 #ifdef CORE_INT31_PIN
00831   static void isr31(void) { update(interruptArgs[31]); }
00832 #endif
00833 #ifdef CORE_INT32_PIN
00834   static void isr32(void) { update(interruptArgs[32]); }
00835 #endif
00836 #ifdef CORE_INT33_PIN
00837   static void isr33(void) { update(interruptArgs[33]); }
00838 #endif
00839 #ifdef CORE_INT34_PIN
00840   static void isr34(void) { update(interruptArgs[34]); }
00841 #endif
00842 #ifdef CORE_INT35_PIN
00843   static void isr35(void) { update(interruptArgs[35]); }
00844 #endif
00845 #ifdef CORE_INT36_PIN
00846   static void isr36(void) { update(interruptArgs[36]); }
00847 #endif
00848 #ifdef CORE_INT37_PIN
00849   static void isr37(void) { update(interruptArgs[37]); }
00850 #endif
00851 #ifdef CORE_INT38_PIN
00852   static void isr38(void) { update(interruptArgs[38]); }
00853 #endif
00854 #ifdef CORE_INT39_PIN
00855   static void isr39(void) { update(interruptArgs[39]); }
00856 #endif
00857 #ifdef CORE_INT40_PIN
00858   static void isr40(void) { update(interruptArgs[40]); }
00859 #endif
00860 #ifdef CORE_INT41_PIN
00861   static void isr41(void) { update(interruptArgs[41]); }
00862 #endif
00863 #ifdef CORE_INT42_PIN
00864   static void isr42(void) { update(interruptArgs[42]); }
00865 #endif
00866 #ifdef CORE_INT43_PIN
00867   static void isr43(void) { update(interruptArgs[43]); }
00868 #endif
00869 #ifdef CORE_INT44_PIN
00870   static void isr44(void) { update(interruptArgs[44]); }
00871 #endif
00872 #ifdef CORE_INT45_PIN
00873   static void isr45(void) { update(interruptArgs[45]); }
00874 #endif
00875 #ifdef CORE_INT46_PIN
00876   static void isr46(void) { update(interruptArgs[46]); }
00877 #endif
00878 #ifdef CORE_INT47_PIN
00879   static void isr47(void) { update(interruptArgs[47]); }
00880 #endif
00881 #ifdef CORE_INT48_PIN
00882   static void isr48(void) { update(interruptArgs[48]); }
00883 #endif
00884 #ifdef CORE_INT49_PIN
00885   static void isr49(void) { update(interruptArgs[49]); }
00886 #endif
00887 #ifdef CORE_INT50_PIN
00888   static void isr50(void) { update(interruptArgs[50]); }
00889 #endif
00890 #ifdef CORE_INT51_PIN
00891   static void isr51(void) { update(interruptArgs[51]); }
00892 #endif
00893 #ifdef CORE_INT52_PIN
00894   static void isr52(void) { update(interruptArgs[52]); }
00895 #endif
00896 #ifdef CORE_INT53_PIN
00897   static void isr53(void) { update(interruptArgs[53]); }
00898 #endif
00899 #ifdef CORE_INT54_PIN
00900   static void isr54(void) { update(interruptArgs[54]); }
00901 #endif
00902 #ifdef CORE_INT55_PIN
00903   static void isr55(void) { update(interruptArgs[55]); }
00904 #endif
00905 #ifdef CORE_INT56_PIN
00906   static void isr56(void) { update(interruptArgs[56]); }
00907 #endif
00908 #ifdef CORE_INT57_PIN
00909   static void isr57(void) { update(interruptArgs[57]); }
00910 #endif
00911 #ifdef CORE_INT58_PIN
00912   static void isr58(void) { update(interruptArgs[58]); }
00913 #endif
00914 #ifdef CORE_INT59_PIN
00915   static void isr59(void) { update(interruptArgs[59]); }
00916 #endif
00917 #endif
00918 };
00919 
00920 #if defined(ENCODER_USE_INTERRUPTS) && defined(ENCODER_OPTIMIZE_INTERRUPTS)
00921 #if defined(__AVR__)
00922 #if defined(INT0_vect) && CORE_NUM_INTERRUPT > 0
00923 ISR(INT0_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(0)]); }
00924 #endif
00925 #if defined(INT1_vect) && CORE_NUM_INTERRUPT > 1
00926 ISR(INT1_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(1)]); }
00927 #endif
00928 #if defined(INT2_vect) && CORE_NUM_INTERRUPT > 2
00929 ISR(INT2_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(2)]); }
00930 #endif
00931 #if defined(INT3_vect) && CORE_NUM_INTERRUPT > 3
00932 ISR(INT3_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(3)]); }
00933 #endif
00934 #if defined(INT4_vect) && CORE_NUM_INTERRUPT > 4
00935 ISR(INT4_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(4)]); }
00936 #endif
00937 #if defined(INT5_vect) && CORE_NUM_INTERRUPT > 5
00938 ISR(INT5_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(5)]); }
00939 #endif
00940 #if defined(INT6_vect) && CORE_NUM_INTERRUPT > 6
00941 ISR(INT6_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(6)]); }
00942 #endif
00943 #if defined(INT7_vect) && CORE_NUM_INTERRUPT > 7
00944 ISR(INT7_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(7)]); }
00945 #endif
00946 #endif // AVR
00947 #endif // ENCODER_OPTIMIZE_INTERRUPTS
00948 
00949 
00950 #endif


arduino_interface
Author(s): Joshua Vasquez and Philip Roan. Maintained by Philip Roan
autogenerated on Sat Dec 28 2013 16:49:06