RBE1001Lib
IRdecoder.h
Go to the documentation of this file.
1 #include <Arduino.h>
2 
3 /*
4  * A class to interpret IR remotes with NEC encoding. NEC encoding sends four bytes:
5  *
6  * [device ID, ~divice ID, key code, ~key code]
7  *
8  * Sending the inverse allow for easy error checking (and reduces saturation in the receiver).
9  *
10  * Codes are send in little endian; this library reverses upon reception, so the first bit received
11  * is in the LSB of currCode. That means that the key code is found in bits [23..16] of currCode
12  *
13  * https://techdocs.altium.com/display/FPGA/NEC+Infrared+Transmission+Protocol
14  *
15  * This does not interpret the codes into which key was pressed. That needs to be
16  * mapped on a remote by remote basis.
17  */
18 
19 /*
20  * TO DO:
21  * - (MED) Possibly indicate repeat code instead of just "refreshing" the latest code?
22  * - (LOW) Consider a better way to indicate that a valid code has been entered;
23  * returning -1 is OK if we return a 16-bit number (so 255 is a valid code),
24  * but there may be a more elegant solution.
25  * - (MED) Add ability to use PCINT library to this generic library. Use a derived class?
26  */
27 
28 class IRDecoder
29 {
30 private:
31  enum IR_STATE
32  {
33  IR_READY, //idle, returns to this state after you request a code
34  IR_PREAMBLE, //received the start burst, waiting for first bit
35  IR_REPEAT, //received repeat code (part of NEC protocol); last code will be returned
36  IR_ACTIVE, //have some bits, but not yet complete
37  IR_COMPLETE, //a valid code has been received
39  }; //an error occurred; won't return a valid code
40 
41  uint8_t irPin;
42 
43  IR_STATE state = IR_READY; //a simple state machine for managing reception
44 
45  volatile uint32_t lastReceiveTime = 0; //not really used -- could be used to sunset codes
46 
47  volatile uint32_t currCode = 0; //the most recently received valid code
48  volatile uint8_t index = 0; //for tracking which bit we're on
49 
50  volatile uint32_t fallingEdge = 0;
51  volatile uint32_t risingEdge = 0;
52 
53  volatile uint32_t lastRisingEdge = 0; //used for tracking spacing between rising edges, i.e., bit value
54 
55 public:
56  IRDecoder(uint8_t pin) : irPin(pin) {}
57  void init(void); //call this in the setup()
58  void handleIRsensor(void); //ISR
59 
60  uint32_t getCode(void) //returns the most recent valid code; returns zero if there was an error or nothing new
61  {
62  if (state == IR_COMPLETE || state == IR_REPEAT)
63  {
64  state = IR_READY;
65  return currCode;
66  }
67  else
68  return 0;
69  }
70 
71  int16_t getKeyCode(bool acceptRepeat = false) //returns the most recent key code; returns -1 on error (not sure if 0 can be a code or not!!!)
72  {
73  if (state == IR_COMPLETE || (acceptRepeat == true && state == IR_REPEAT))
74  {
75  state = IR_READY;
76  return (currCode >> 16) & 0x0ff;
77  }
78  //else if(state == IR_ERROR) return currCode; //for debugging, if needed
79  else
80  return -1;
81  }
82 };
83 
84 class IRDecoder32U4 : public IRDecoder
85 {
86  IRDecoder32U4(uint8_t pin) : IRDecoder(pin) {}
87 };
88 
89 extern IRDecoder decoder;
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
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
IRDecoder32U4(uint8_t pin)
Definition: IRdecoder.h:86
int16_t getKeyCode(bool acceptRepeat=false)
Definition: IRdecoder.h:71
void handleIRsensor(void)
Definition: IRdecoder.cpp:16
volatile uint32_t lastReceiveTime
Definition: IRdecoder.h:45
IRDecoder(uint8_t pin)
Definition: IRdecoder.h:56
int pin
Definition: ToneExample.ino:7
uint32_t getCode(void)
Definition: IRdecoder.h:60
IR_STATE state
Definition: IRdecoder.h:43