RBE1001Lib
All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros
IRdecoder.cpp
Go to the documentation of this file.
1 #include <IRdecoder.h>
2 
3 /* Interprets an IR remote with NEC encoding. See IRdecoder.h for more explanation. */
4 
5 void handleIRsensor(void)
6 {
8 }
9 
10 void IRDecoder::init(void)
11 {
12  pinMode(irPin, INPUT);
13  attachInterrupt(digitalPinToInterrupt(irPin), ::handleIRsensor, CHANGE);
14 }
15 
17 {
18  uint32_t currUS = micros();
19 
20  if(!digitalRead(irPin)) // FALLING edge
21  {
22  fallingEdge = currUS;
23  }
24 
25  else // RISING edge
26  {
27  risingEdge = currUS;
28 
29  //and process
30  uint32_t delta = risingEdge - fallingEdge; //length of pulse, in us
31  uint32_t codeLength = risingEdge - lastRisingEdge;
32  lastRisingEdge = risingEdge;
33 
34  if(delta > 8500 && delta < 9500) // received a start pulse
35  {
36  index = 0;
38  return;
39  }
40 
41  /* a pulse is supposed to be 562.5 us, but it varies based on the RC device, plus
42  * the receiver is NOT optimized for IR remotes --
43  * it's actually optimized for sensitivity. So I set the maximum accepted pulse
44  * length to 700us. On the ESP32 (others?), the pulse is sometimes coming in at ~515 us,
45  * so lowering the bottom to 500.
46  */
47 
48  else if(delta < 500 || delta > 700) // pulse wasn't right length => error
49  {
50  state = IR_ERROR;
51  return;
52  }
53 
54  else if(state == IR_PREAMBLE)
55  {
56  //preamble is 4.5 ms, but we have to add the ~560 us burst to it
57  if(codeLength < 5300 && codeLength > 4800) //preamble
58  {
59  currCode = 0;
60  state = IR_ACTIVE;
61  }
62 
63  //repeat code is a 2.25 ms space + 560 us burst
64  else if(codeLength < 3300 && codeLength > 2700) //repeat code
65  {
66  state = IR_REPEAT;
67  if(((currCode ^ (currCode >> 8)) & 0x00ff0000) != 0x00ff0000) {state = IR_ERROR;} //but recheck code!
68  else lastReceiveTime = millis(); //not really used
69  }
70  }
71 
72  else if(state == IR_ACTIVE)
73  {
74  //short burst is nominally 1.125 ms
75  if(codeLength < 1300 && codeLength > 900) //short = 0
76  {
77  index++;
78  }
79 
80  //long burst is nominally 2.25 ms
81  else if(codeLength < 2500 && codeLength > 2000) //long = 1
82  {
83  currCode += ((uint32_t)1 << index);
84  index++;
85  }
86 
87  else //error
88  {
89  state = IR_ERROR;
90  }
91 
92  if(index == 32) //full set of bits
93  {
94  //first, check for errors (kinda' ugly, but it works)
95  if(((currCode ^ (currCode >> 8)) & 0x00ff0000) != 0x00ff0000) {state = IR_ERROR;}
96 
97  else //we're good to go
98  {
100  lastReceiveTime = millis();
101  }
102  }
103  }
104  }
105 }
volatile uint32_t lastRisingEdge
Definition: IRdecoder.h:53
volatile uint32_t risingEdge
Definition: IRdecoder.h:51
uint8_t irPin
Definition: IRdecoder.h:41
void init(void)
Definition: IRdecoder.cpp:10
void handleIRsensor(void)
Definition: IRdecoder.cpp:5
volatile uint32_t fallingEdge
Definition: IRdecoder.h:50
volatile uint8_t index
Definition: IRdecoder.h:48
volatile uint32_t currCode
Definition: IRdecoder.h:47
IRDecoder decoder
void handleIRsensor(void)
Definition: IRdecoder.cpp:16
volatile uint32_t lastReceiveTime
Definition: IRdecoder.h:45
IR_STATE state
Definition: IRdecoder.h:43