Sunday, August 2, 2009

Arduino IR Receiver with Interrupts



Infra Red Receiver with the use of Pin Change Interrupt

Infrared remote control receiver implemented using pin change interrupt. This implementation allows the main loop to perform other tasks while the receiver code collects incoming IR message bits in the background. This method was used to receive IR control message send to the iSOBOT robot from its remote. It is runnin on Arduino Mini Pro with AVR m168 CPU.

Problem Definition

The IR remote receiver is observing output of the IR sensor/demodulator which signals presents or absents of modulated IR. The output of the sensor is connected to a pin of the CPU which is then read by the software and interpreted by as bits of the message. To recognize the beginning of the message and to interpret the waveform generated by, the code has to measure time between signal transition. Beginning of the message is signaled as 2.5ms burst of IR while 0 and 1 are coded as length of silence between 0.5ms IR bursts (0- 0.5 ms silence while 1 is 1ms silence). See IR waveforms and protocol description.

Classic Approach

The code below is uses a polling approach. When it waits for the signal change it simply reads (polls) the signal until a change is observed. While this is straight forward and very simply, it occupies the CPU in 100%. Here is an implementation of example:



// helper functions

unsigned long elapsedSince(unsigned long since, unsigned long now)
{
return since &lh; now ? now-since : 0xFFFFFFFFUL - (now - since);
}

unsigned long elapsedSince(unsigned long since)
{
return elapsedSince( since, micros() );
}

// iSOBOT IR protocol timing
#define TimeStart 2500
#define TimeZero 500
#define TimeOne 1000
#define TimeOff 500

// check if the time was in range +/- 25%
#define IS_X(t,x) ((t > 3*(x)/4) && (t < 5*(x)/4))
#define IS_0(t) IS_X(t,TimeZero)
#define IS_1(t) IS_X(t,TimeOne)
#define IS_S(t) IS_X(t,TimeStart)
#define IS_O(t) IS_X(t,TimeOff)

//////////////////////////////////////////////////////////////////////
// polling/blocking version of IR receiver
//////////////////////////////////////////////////////////////////////

//////////////////////////////////////////////////////////////////////
// waits for IR carrier transitions (on->off & off->on)
// returns duration of the specified state (HIGH->IR transmitting; LOW->IR off)
// returns 0 if timeout
unsigned irRecvSignal(byte waitFor)
{
while(digitalRead(PIN_IR)==(waitFor==LOW?HIGH:LOW)) {};
unsigned long start = micros();
while(digitalRead(PIN_IR)==waitFor) {};
return elapsedSince(start);
}

////////////////////////////////////////////////////////////////////////
// receives all 22 bits of the messagge
long irRecv()
{
Serial.println("Waiting...");
unsigned time = irRecvSignal(LOW);
if( !IS_S(time) )
{
Serial.println("False Start");
Serial.println(time);
return 0;
}
long bits = 0;
byte len = 22;
for(int i = 0; i < len; i++ )
{
bits <<= 1;
time = irRecvSignal(HIGH);
if( IS_1(time) )
{
bits |= 1;
}
else if( IS_0(time) )
{
bits |= 0;
}
else
{
Serial.println("Bad Bit");
Serial.println(time);
return 0;
}
// check type of message (when recved) to guess the message length (either 22 ot 30 bits)
if( bit == 3 )
{
byte msgtype = bits & 0x3;
if( msgtype == 0 ) len = 30;
}
}
return bits;
}


The jest of the polling happens in the loops in irRecvSignal(byte waitFor) function.
The time duration is measured with Arduino's time function micros() returning number of microseconds since the CPU was started. Note that the number of microseconds will wrap around, which I am compensating for in elapsedSince() function.

When I want to receive a message I just call irRecv().


void loop()
{
...
long msg = irRecv();
...
}


This call will block until a message is received. Hence, nothing else in the main loop will be executed while I wait for IR message (ie wait for the irRecv() to return).

Interrupts

So, I have one CPU here but I'd like to perform more then one task at a time. One way is to "distract" or "interrupt" the main code and "switch" to something else for a moment is to you interrupts. Since the IR receiver cares only about changes in the IR signal and these changes are relatively infrequent, the cost of interrupting the main task will be small. At the worst case the IR signal changes every 500us which on 16MHz CPU AVR allows for about 8000 instructions to be executed in between. Granted, there is some overhead cost of interrupting (multitasking is hard for humans as well) but it should be rather small esp. since in this case the IR message are also sent infrequently.

Solution

Ok, so here is the code I came up with. It is more complicated than the polling version. Since the interrupt code is/should be active only for brief moments, the state of receiving a message must be preserved between its actions. I used a state machine to implement this functionality (by "state machine" I mean that one single function is invoke on IR signal change but this function "switches" into different state depending on its current state and elapsed time since last invocation).



// pin state change interrupt based IR receiver
// observing the IR pin changes, measure time between interrupts
// use state machine to decide what to do

enum
{
ISR_IDLE, // nothing is/was happening (quiet)
ISR_START, // start of sequence, was waiting for a header signal
ISR_BIT_ON, // transsmitting a bit (IR carrier turned on)
ISR_BIT_OFF // in an OFF bit slot (IR carrier turned off)
}
isrState = ISR_IDLE;

unsigned long isrLastTimeStamp;
unsigned long isrRcvCmd;
unsigned long isrNewCmd;
byte isrBitLen = 22;
byte isrBitCnt;


ISR( PCINT2_vect )
{
// PIN_IR == #2 --> PD2;
// receiving a modulated IR signal makes the pin go low (active low)
byte transmitting = (PIND & (1<<2)) == 0;

// compute elapsed time since last change
unsigned elapsed;
{
unsigned long timeStamp = micros();
elapsed = elapsedSince(isrLastTimeStamp,timeStamp);
isrLastTimeStamp = timeStamp;
}
switch( isrState )
{
case ISR_IDLE :
if( transmitting ) isrState = ISR_START;
break;
case ISR_START:
isrBitCnt = 0;
isrNewCmd = 0;
isrBitLen = 22;
if( !transmitting && IS_S(elapsed) )
isrState = ISR_BIT_ON; // bits are now rolling
else
isrState = ISR_IDLE; // wrong timing of start or pin state
break;
case ISR_BIT_ON:
if( transmitting )
{
isrState = ISR_BIT_OFF;
isrNewCmd <<= 1;
isrBitCnt ++;
if( IS_1(elapsed) )
{
isrNewCmd |= 1;
}
else if( IS_0(elapsed) )
{
// isrNewCmd |= 0;
}
else
isrState = ISR_START; // bad timing, start over
if( isrBitCnt == 7 ) // we have received 6 bit header (now expecting 7th bit)
{
isrBitLen = (isrNewCmd & (3<<3)) == 0 ? 30 : 22; // 2 vs 3 byte commands
}
}
else isrState = ISR_IDLE; // bad state (should never get here...)
break;
case ISR_BIT_OFF:
if( !transmitting && IS_O(elapsed) )
{
if( isrBitCnt == isrBitLen ) // is this the end?
{
isrState = ISR_IDLE;
isrRcvCmd = isrNewCmd;
}
else
isrState = ISR_BIT_ON; // keep bits rolling
}
else
if( IS_S(elapsed) )
isrState = ISR_START;
else
isrState = ISR_IDLE;
break;
}
}


To link a function to an interrupt I used
ISR( PCINT2_vect )
(assigns it to the INT2 interrupt vector which is linked to the pin I used for IR signal).

And the rest of it

Here is a function returning a new message:


long irRecv()
{
byte oldSREG = SREG;
cli();
long cmd = isrRcvCmd;
isrRcvCmd = 0;
SREG = oldSREG;
return cmd;
}


This is a non-blocking function. If there was nothing, it returns 0 (there is no message that would result in a 0). When a message code is read, a 0 is stuffed back into isrRcvCmd to clear it so next time I read it I do not get a repeat. I also turn off interrupts for the duration of the "read and zero" of isrRcvCmd so I do not conflict with the interrupt code "interrupting" my read. Note that:
long cmd = isrRcvCmd;
is not "atomic" ie it consists of several CPU instructions and hence it may be interrupted in the middle and ended up returning an inconsistent value.

So now I can really do more stuff in main loop:


void loop
{
unsigned long rcv = irRecv();
if(rcv)
{
// got a message
Serial.print("recv ");
Serial.println(rcv,HEX);
}
Serial.print('.');
... do whatever you like
}


Configuring Interrupt
I have connected the IR sensor to pin D2 (#2 in Arduino convention). The pin change interrupts are not enabled by default so I needed to configure it in setup:


void setup()
{
...
PCICR |= 4; // enable PCIE2 which services PCINT18
PCMSK2 |= 4; // enable PCINT18 --> Pin Change Interrupt of PD2
...
}


3 comments:

Manuel said...

Your solution to handle the interrupts seems very elegant.

I'm trying to run your solution using breaks and I get compiler error messages. I currently use Duemilanove.
Could you post the entire code, including the includes?

Thank you very much

LukeZ said...

I'm not sure why you have two versions of the elapsedSince function, only the top one should be used, or the second one renamed.

There is also a typo (you wrote "&lh;" instead of "&lt"). So, the formula should read:

return since < now ? now-since : 0xFFFFFFFFUL - (now - since);

coolgone said...

Great ! could you post entire code please ?