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


lizi_arduino
Author(s): RoboTiCan
autogenerated on Wed Aug 26 2015 12:24:22