Project

General

Profile

Statistics
| Branch: | Revision:

robobuggy / arduino / InterruptRCRecieverReference / PinChangeInt / Examples / PinChangeIntTest / PinChangeIntTest.pde @ c5d6b0e8

History | View | Annotate | Download (14.7 KB)

1
// PinChangeIntTest
2
// version 1.0 Wed Feb 15 07:25:09 CST 2012
3
// Version 1.1 Fri Jun 22 19:10:50 CDT 2012 minor tweaks to eliminate compiler warnings.  Also, there were bugfixes in ByteBuffer.
4
//                                          I had some "cli()" without "sei()" in there.
5
// See the Wiki at http://code.google.com/p/arduino-pinchangeint/wiki for more information.
6
// This sketch requires the ByteBuffer library, which is found in the PinChangeInt zipfile.
7
//-------- define these in your sketch, if applicable ----------------------------------------------------------
8
//-------- This must go ahead of the #include statement --------------------------------------------------------
9
// You can reduce the memory footprint of this handler by declaring that there will be no pin change interrupts
10
// on any one or two of the three ports.  If only a single port remains, the handler will be declared inline
11
// reducing the size and latency of the handler.
12
// #define NO_PORTB_PINCHANGES // to indicate that port b will not be used for pin change interrupts
13
// #define NO_PORTC_PINCHANGES // to indicate that port c will not be used for pin change interrupts
14
// #define NO_PORTD_PINCHANGES // to indicate that port d will not be used for pin change interrupts
15
// You can reduce the code size by 20-50 bytes, and you can speed up the interrupt routine
16
// slightly by declaring that you don't care if the static variables PCintPort::pinState and/or
17
// PCintPort::arduinoPin are set and made available to your interrupt routine.
18
// #define NO_PIN_STATE        // to indicate that you don't need the pinState
19
// #define NO_PIN_NUMBER       // to indicate that you don't need the arduinoPin
20
// if there is only one PCInt vector in use the code can be inlined
21
// reducing latency and code size
22
// define DISABLE_PCINT_MULTI_SERVICE below to limit the handler to servicing a single interrupt per invocation.
23
// #define       DISABLE_PCINT_MULTI_SERVICE
24
// The following is intended for testing purposes.  If defined, then a variable PCintPort::pinMode can be read
25
// in your interrupt subroutine.  It is not defined by default:
26
// #define PINMODE
27
//-------- define the above in your sketch, if applicable ------------------------------------------------------
28
#define PINMODE
29
#define FLASH
30
#include <ByteBuffer.h>
31
#include <PinChangeInt.h>
32

    
33
// This example demonstrates a configuration of 6 interrupting pins and 3 interrupt functions.
34
// A variety of interrupting pins have been chosen, so as to test all PORTs on the Arduino.
35
// The pins are as follows:
36
#define tPIN1 2  // port D
37
#define tPIN2 3
38
#define tPIN3 11 // Port B
39
#define tPIN4 12
40
#define tPIN5 A3 // Port C, also can be given as "17"
41
#define tPIN6 A4 // starts and stops the count
42
// All pins send interrupts.  Arduino pins 2 and A4 (tPIN1,6) interrupt on FALLING.
43
// Arduino pins 3 and 12 (tPIN2,4) interrupt on RISING.
44
// Arduino pins 11 and A3 (tPIN5) interrupts on CHANGE.
45
// quicfunc0 is attached to Arduino pins 2, 3, 11, and 12 (tPIN1-4)
46
// quicfunc1 is attached to Arduino pin A3 (tPIN5)
47
// quicfunc2 is attached to Arduino pin A4 (tPIN6).
48
// NOTE:
49
// For the Analog Input pins used as digital input pins, you can use numbers such as 14, 15, 16, etc.
50
// or you can use A0, A1, A2, etc. (the Arduino code comes with #define's for the Analog Input pin
51
// names and will properly recognize e.g., pinMode(A0, INPUT));
52

    
53
// HOW IT WORKS
54
// The interrupt on Arduino pin A4 (tPIN6) will, when triggered, start the counting of interrupts.  
55
// The array interrupt_count0[20] is updated in the interrupts; each cell keeps track of the number
56
// of interrupts on one of the 20 available interrupt pins on the Arduino.  Every second in the main
57
// loop the array is scanned and registered interrupts are reported for all pins interrupted since
58
// the previous second.  If no interrupts, the output is quiet.
59

    
60
// tPIN6 is special.  Not only does it start the counting of the interrups, but it turns on and off
61
// interrupts on pins 2, 11, and A3/17 (tPIN1, tPIN3, tPIN5).  All pins start by interrupting, but after
62
// the count is turned on and then turned off, the 3 pins are detached from interrupts.
63
// Everytime thereafter when the count is turned off the 3 pins are detached.  They are reattached
64
// when turned on.
65

    
66
// Output is copied to a buffer, because we can't do a Serial.print() statement in an interrupt
67
// routine.  The main loop checks  for entries in the buffer and prints them if found.
68
// Output looks like this:
69
// -F- - an interrupt triggered by a falling signal occurred.
70
// +R+ - an interrupt triggered by a rising signal occurred.
71
// *C* - an interrupt triggered by a change in signal occurred.
72
// f#p#-P# - f# shows the interrupt subroutine that was called: 0, 1, or 2
73
//         - p# shows the pin number that triggered the interrupt
74
//         - P# shows the port that this pin number is attached to. 2 is PORTB, 3 is PORTC, 4 is PORTD
75

    
76
// HOW TO CONNECT
77
// Each pin gets a momentary contact switch connected to it.  One side of the switch should connect
78
// to ground.  The other side of the switch connects to the Arduino pin.  For my purposes, I am using
79
// two rotary encoders.  Each encoder contains 3 switches.  But 6 regular pushbuttons would work, too.
80

    
81
/* WHAT TO LOOK FOR
82
 Output is sent to the serial line, so the Arduino IDE's serial terminal should be opened.
83
 Upon startup, press tPINS1-5.  You will see output like this:
84
-F-f0p2-P4 (counting off)
85
..*C*f0p11-P2 (counting off)
86
+R+f0p3-P4 (counting off)
87
 This shows that
88
 1. an interrupt was triggered on a falling signal (*F*).  It called (f0) function 0, which is quicfunc0.
89
    The triggering pin was (p2) Arduuino pin 2, which is on (P4) Port 4 (PORTD).  Counting of this interrupt is
90
    off, so you will not see any output from the main loop.
91
 2. Two dots appeared.  Dots came from iterations of loop(), so these 2 dots show that the two interrupts happened 2 seconds apart.
92
 3. an interrupt was triggered on a change in signal (*C*).  It called quicfunc0, from Arduino pin 11, on Port 2 (PORTB).
93
    The interrupt was not counted.
94
 4. an interrupt was triggered on a rising signal (+R+).  It called quicfunc0, from Arduino pin 3, on Purt 4 (PORTD).
95
    The pin should have started out at the high level, so likely the signal fell during onother interrupt, and now
96
    the rise has been caught.
97
    
98
 Now press the button attached to tPIN6 (in our case, A4 or D18).  You will see something like this:
99
-F-START! f2p18-P3
100
.Count for pin A4 is 1
101
 This shows that
102
 1. The counting machanism (START!) was triggered by a folling signal (-F-) on pin 18 (p18) which is in Port 3 (P3) (which == PORTC) and
103
    function f2 was called (f2).
104
 2. A dot appeared, which came from loop() because a second passed.
105
 3. The count for p18 or A4 was displayed.
106
 
107
 Now you will see messages for all the pins that you manipulate, for example:
108
*C*f0p11-P2
109
+R+f0p3-P4
110
*C*f0p11-P2
111
+R+f0p3-P4
112
*C*f0p11-P2
113
.Count for pin D3 is 6
114
Count for pin D11 is 9
115
.+R+f0p3-P4
116
-F-f0p2-P4
117
.Count for pin D2 is 1
118
Count for pin D3 is 1
119
 These codes reflect the interrupts, as described above.  This output will take place until you press tPIN6:
120
-F-f2: STOP! Counting off.
121
Interrupt OFF on tPIN1 (2) tPIN3 (11) tPIN5 (17)
122
 Then you will see output like this:
123
.....................+R+f0p12-P2 (counting off)
124
.+R+f0p12-P2 (counting off)
125
+R+f0p12-P2 (counting off)
126
+R+f0p12-P2 (counting off)
127
 and tPIN1, tPIN3, and tPIN5 will not trigger interrupts.
128
*/
129
// NOTES
130
// Output overwrites:
131
// It's possible during moderately fast interrupts to see your print output get garbled; eg,
132
// +R+f0p12-P2 (+R+f0p12-P2 (counting +R+f0p12-P2 (cou+R+f0p12-P+R+f0p12
133
// This is because the print of the buffer takes place inside a while loop, and it can
134
// be interrupted and new data inserted into the buffer at a midpoint of the buffer's text.
135
// Just by spinning my rotary encoders I can readily generate over 200 interrupts per second
136
// on a pin, which is easily fast enough to overrun Serial output at 115,200 bps.
137
// The lesson here?  ...Interrupts are tricky, and interrupt service routines should be fast.
138
// Just sayin'.
139

    
140
// Pins:
141
// We want to use pins from each of ports B, C and D.  So choose wisely.  Ports are shown in
142
// this diagram of the ATmega328P chip.  PD0 means "Port D, pin 0".  PC3 means "Port C, Pin 3",
143
// PB2 means "Port B, pin 2" and so on.  The corresponding Arduino pins are in parentheses.
144
// So PB2 is Arduino pin D 10, for example.
145
/*
146
                  +-\/-+
147
            PC6  1|    |28  PC5 (AI 5)
148
      (D 0) PD0  2|    |27  PC4 (AI 4)
149
      (D 1) PD1  3|    |26  PC3 (AI 3)
150
      (D 2) PD2  4|    |25  PC2 (AI 2)
151
 PWM+ (D 3) PD3  5|    |24  PC1 (AI 1)
152
      (D 4) PD4  6|    |23  PC0 (AI 0)
153
            VCC  7|    |22  GND
154
            GND  8|    |21  AREF
155
            PB6  9|    |20  AVCC
156
            PB7 10|    |19  PB5 (D 13)
157
 PWM+ (D 5) PD5 11|    |18  PB4 (D 12)
158
 PWM+ (D 6) PD6 12|    |17  PB3 (D 11) PWM
159
      (D 7) PD7 13|    |16  PB2 (D 10) PWM
160
      (D 8) PB0 14|    |15  PB1 (D 9) PWM
161
                  +----+
162
*/
163

    
164
uint8_t pins[6]={ tPIN1, tPIN2, tPIN3, tPIN4, tPIN5, tPIN6 };
165
uint8_t ports[6]={ 0, 0, 0, 0, 0, 0 };
166

    
167
uint8_t latest_interrupted_pin;
168
uint8_t interrupt_count[20]={0}; // 20 possible arduino pins
169
uint8_t port;
170
uint8_t mode;
171

    
172
ByteBuffer printBuffer(80);
173
char charArray[16];
174
char numBuffer[4] = { 0, 0, 0, 0 };
175
uint8_t printFull=0;
176

    
177
volatile boolean start=0;
178
volatile boolean initial=true;
179
long begintime=0;
180
long now=0;
181

    
182
void uint8ToString(char *outString, uint8_t number) {
183
  uint8_t hundreds=0;
184
  uint8_t tens=0;
185
  uint8_t ones=0;
186

    
187
  while (number >= 100 ) {
188
    hundreds++;
189
    number-=100;
190
  }
191
  while (number >= 10 ) {
192
    tens++;
193
    number-=10;
194
  }
195
  ones=number;
196
  ones+=48;
197
  if (hundreds > 0) { hundreds+=48; tens+=48; outString[0]=hundreds; outString[1]=tens; outString[2]=ones; outString[3]=0; }
198
  else if (tens > 0) {  tens+=48; outString[0]=tens; outString[1]=ones; outString[2]=0; }
199
  else { outString[0]=ones; outString[1]=0; };
200
}
201

    
202
void showMode() {
203
  switch (mode) {
204
  case FALLING:
205
    printBuffer.putString((char *) "-F-");
206
  break;
207
  case RISING:
208
    printBuffer.putString((char *) "+R+");
209
  break;
210
  case CHANGE:
211
    printBuffer.putString((char *) "*C*");
212
  break;
213
  }
214
}
215

    
216
void quicfunc0() {
217
  latest_interrupted_pin=PCintPort::arduinoPin;
218
  mode=PCintPort::pinmode;
219
  showMode();
220
  if (start==1) {
221
    interrupt_count[latest_interrupted_pin]++;
222
  }
223
  uint8ToString(numBuffer, latest_interrupted_pin);
224
  printBuffer.putString((char *) "f0p"); printBuffer.putString(numBuffer); printBuffer.putString((char *) "-P");
225
  uint8ToString(numBuffer, digitalPinToPort(latest_interrupted_pin));
226
  printBuffer.putString(numBuffer);
227
  if (start !=1) printBuffer.putString((char *) " (counting off)");
228
  printBuffer.putString((char *) "\n");
229
};
230

    
231
void quicfunc1() {
232
  latest_interrupted_pin=PCintPort::arduinoPin;
233
  mode=PCintPort::pinmode;
234
  showMode();
235
  if (start==1) {
236
    interrupt_count[latest_interrupted_pin]++;
237
  }
238
  uint8ToString(numBuffer, latest_interrupted_pin);
239
  printBuffer.putString((char *) "f1p"); printBuffer.putString(numBuffer); printBuffer.putString((char *) "-P");
240
  uint8ToString(numBuffer, digitalPinToPort(latest_interrupted_pin));
241
  printBuffer.putString(numBuffer);
242
  if (start !=1) printBuffer.putString((char *) " (counting off)");
243
  printBuffer.putString((char *) "\n");
244
};
245

    
246
void quicfunc2() {
247
  latest_interrupted_pin=PCintPort::arduinoPin;
248
  mode=PCintPort::pinmode;
249
  showMode();
250
  if (start == 1) {
251
    printBuffer.putString((char *) "f2: STOP! Counting off.\n");
252
    printBuffer.putString((char *) "Interrupt OFF on tPIN1 ("); uint8ToString(numBuffer, tPIN1), printBuffer.putString(numBuffer);
253
    printBuffer.putString((char *) ") tPIN3 (");uint8ToString(numBuffer, tPIN3), printBuffer.putString(numBuffer);
254
    printBuffer.putString((char *) ") tPIN5 (");uint8ToString(numBuffer, tPIN5), printBuffer.putString(numBuffer);
255
    printBuffer.putString((char *) ")\n");
256
    PCintPort::detachInterrupt(tPIN1); PCintPort::detachInterrupt(tPIN3); PCintPort::detachInterrupt(tPIN5); 
257
    start=0;
258
  } else {
259
    start=1;
260
    interrupt_count[latest_interrupted_pin]++;
261
    printBuffer.putString((char *) "START! f2p");
262
    uint8ToString(numBuffer, latest_interrupted_pin);
263
    printBuffer.putString(numBuffer); printBuffer.putString((char *) "-P");
264
    uint8ToString(numBuffer, digitalPinToPort(latest_interrupted_pin));
265
    printBuffer.putString(numBuffer); printBuffer.putString((char *) "\n");
266
    if (! initial) {
267
      PCintPort::attachInterrupt(tPIN1, &quicfunc0, FALLING);
268
      PCintPort::attachInterrupt(tPIN3, &quicfunc0, CHANGE);
269
      PCintPort::attachInterrupt(tPIN5, &quicfunc1, CHANGE);
270
    } else {
271
      initial=false;
272
    }                                                                                                
273
  }
274
};
275

    
276
uint8_t i;
277
void setup() {
278
  Serial.begin(115200);
279
  delay(250);
280
  Serial.println("Test");
281
  delay(500);
282
  for (i=0; i < 7; i++) {
283
    pinMode(pins[i], INPUT); digitalWrite(pins[i], HIGH);
284
    ports[i]=digitalPinToPort(pins[i]);
285
    switch (pins[i]) {
286
    case tPIN1:
287
        PCintPort::attachInterrupt(pins[i], &quicfunc0, FALLING);
288
    break;
289
    case tPIN3:
290
        PCintPort::attachInterrupt(pins[i], &quicfunc0, CHANGE);
291
    break;
292
    case tPIN2:
293
    case tPIN4:
294
        PCintPort::attachInterrupt(pins[i], &quicfunc0, RISING);
295
    break;
296
    case tPIN5:
297
        PCintPort::attachInterrupt(pins[i], &quicfunc1, CHANGE);
298
    break;
299
    case tPIN6:
300
        PCintPort::attachInterrupt(pins[i], &quicfunc2, FALLING);
301
    break;
302
    }
303
  }
304
  //Serial.println(printBuffer.getCapacity(), DEC);
305
  //Serial.println("*---------------------------------------*");
306
  Serial.print("*---*");
307
  delay(250);
308
  begintime=millis();
309
}
310

    
311
void loop() {
312
  now=millis();
313
  uint8_t count;
314
  char outChar;
315
  // uint8_t bufsize;
316
  //if (printBuffer.getSize() != 0) { Serial.print("SZ:"); Serial.println (printBuffer.getSize(), DEC); };
317
  //bufsize=printBuffer.getSize();
318
  //if (bufsize > 0) { Serial.print("S:"); Serial.println(bufsize); }
319
  while ((outChar=(char)printBuffer.get()) != 0) Serial.print(outChar);
320
  if ((now - begintime) > 1000) {
321
    Serial.print(".");
322
    if (printBuffer.checkError()) {
323
      Serial.println("NOTICE: Some output lost due to filled buffer.");
324
    }
325
    for (i=0; i < 20; i++) {
326
      if (interrupt_count[i] != 0) {
327
        count=interrupt_count[i];
328
        interrupt_count[i]=0;
329
        Serial.print("Count for pin ");
330
        if (i < 14) {
331
          Serial.print("D");
332
          Serial.print(i, DEC);
333
        } else {
334
          Serial.print("A");
335
          Serial.print(i-14, DEC);
336
        }
337
        Serial.print(" is ");
338
        Serial.println(count, DEC);
339
      }
340
    }
341
    begintime=millis();
342
  }
343
}
344