wpi-32u4-library
IRdecoder.cpp
Go to the documentation of this file.
1#include <IRdecoder.h>
2#include <FastGPIO.h>
3#include <pcint.h>
4
5/* Interprets an IR remote with NEC encoding. See IRdecoder.h for more explanation. */
6
7void handleIRsensor(void)
8{
10}
11
13{
14 pinMode(pin, INPUT);
15
16 if(digitalPinToInterrupt(pin) != NOT_AN_INTERRUPT)
17 {
18 Serial.println("Attaching ISR");
19 attachInterrupt(digitalPinToInterrupt(pin), ::handleIRsensor, CHANGE);
20 }
21 else if(digitalPinToPCInterrupt(pin) != NOT_AN_INTERRUPT)
22 {
23 Serial.println("Attaching PC_ISR");
25 }
26 else
27 {
28 Serial.println("Not an interrupt pin!");
29 }
30}
31
33{
34 uint32_t currUS = micros();
35
36 //if(!FastGPIO::Pin<14>::isInputHigh()) // could use FastGPIO for speed
37 if(!digitalRead(pin)) // FALLING edge
38 {
39 fallingEdge = currUS;
40 }
41
42 else // RISING edge
43 {
44 risingEdge = currUS;
45
46 //and process
47 uint32_t delta = risingEdge - fallingEdge; //length of pulse, in us
48 uint32_t codeLength = risingEdge - lastRisingEdge;
50
51 // bits[index] = delta; //used for debugging; obsolete
52
53 if(delta > 8500 && delta < 9500) // received a start pulse
54 {
55 index = 0;
57 return;
58 }
59
60 //a pulse is supposed to be 562.5 us, but I found that it averaged 620us or so
61 //with the sensor that we're using, which is NOT optimized for IR remotes --
62 //it's actually optimized for sensitivity. So I set the maximum accepted pulse
63 //length to 700us
64
65 else if(delta < 500 || delta > 700) // if the pulse isn't the right width -> set error
66 {
68 currCode = -1;
69
70 return;
71 }
72
73 else if(state == IR_PREAMBLE)
74 {
75 if(codeLength < 5300 && codeLength > 4800) //preamble
76 {
77 currCode = 0;
79 }
80
81 else if(codeLength < 3300 && codeLength > 2700) //repeat code
82 {
84 if(((currCode ^ (currCode >> 8)) & 0x00ff0000) != 0x00ff0000) {state = IR_ERROR;}
85 lastReceiveTime = millis(); //not really used
86 }
87 }
88
89 else if(state == IR_ACTIVE)
90 {
91 if(codeLength < 1300 && codeLength > 900) //short = 0
92 {
93 index++;
94 }
95
96 else if(codeLength < 2500 && codeLength > 2000) //long = 1
97 {
98 currCode += ((uint32_t)1 << index);
99 index++;
100 }
101
102 else //error
103 {
104 state = IR_ERROR;
105 }
106
107 if(index == 32) //full set of bits
108 {
109 //first, check for errors
110 if(((currCode ^ (currCode >> 8)) & 0x00ff0000) != 0x00ff0000) state = IR_ERROR;
111
112 else //we're good to go
113 {
115 lastReceiveTime = millis();
116 }
117 }
118 }
119 }
120}
void handleIRsensor(void)
Definition: IRdecoder.cpp:7
IRDecoder decoder
volatile uint32_t risingEdge
Definition: IRdecoder.h:43
volatile uint32_t lastReceiveTime
Definition: IRdecoder.h:37
void handleIRsensor(void)
Definition: IRdecoder.cpp:32
volatile uint32_t currCode
Definition: IRdecoder.h:39
volatile uint8_t index
Definition: IRdecoder.h:40
void init(void)
Definition: IRdecoder.cpp:12
volatile uint32_t lastRisingEdge
Definition: IRdecoder.h:45
uint8_t pin
Definition: IRdecoder.h:23
@ IR_ACTIVE
Definition: IRdecoder.h:30
@ IR_PREAMBLE
Definition: IRdecoder.h:28
@ IR_COMPLETE
Definition: IRdecoder.h:31
@ IR_REPEAT
Definition: IRdecoder.h:29
@ IR_ERROR
Definition: IRdecoder.h:32
volatile uint32_t fallingEdge
Definition: IRdecoder.h:42
IR_STATE state
Definition: IRdecoder.h:35
uint8_t digitalPinToPCInterrupt(uint8_t pin)
Definition: pcint.cpp:53
void attachPCInt(uint8_t pcInt, void(*pcisr)(void))
Attaches a function to a pin change interrupt.
Definition: pcint.cpp:12