/elec/quadcopter

To get this branch, use:
bzr branch http://bzr.ed.am/elec/quadcopter

« back to all changes in this revision

Viewing changes to src/rc-interface/receiver.cc

  • Committer: Tim Marston
  • Date: 2014-02-05 22:15:49 UTC
  • Revision ID: tim@ed.am-20140205221549-jmrvij7zyl1cn8j9
stabalised the PPM output on the rc-interface board

Show diffs side-by-side

added added

removed removed

 
1
//
 
2
// receiver.cc
 
3
//
 
4
 
 
5
 
 
6
#include "receiver.h"
 
7
#include "config.h"
 
8
#include "common.h"
 
9
#include <Arduino.h>
 
10
#include <limits.h>
 
11
 
 
12
 
 
13
// channel sequence order
 
14
static const int channel_order_[] = { CHANNEL_ORDER };
 
15
 
 
16
// set to the time of the last pulse edges
 
17
static unsigned long new_pulse_up_[2] = { 0, 0 };
 
18
static unsigned long new_pulse_down_ = 0;
 
19
static char new_pulse_interrupt_;
 
20
 
 
21
 
 
22
// ISR to handle the PPM signals
 
23
inline void signal_handler( int interrupt, int pin )
 
24
{
 
25
        // record rising/falling edge
 
26
        if( digitalRead( pin ) )
 
27
                new_pulse_up_[ interrupt ] = micros();
 
28
        else {
 
29
                new_pulse_down_ = micros();
 
30
 
 
31
                // record which interrupt just had a falling edge
 
32
                new_pulse_interrupt_ = interrupt;
 
33
        }
 
34
}
 
35
 
 
36
 
 
37
static void signal_handler_0()
 
38
{
 
39
        signal_handler( 0, 2 );
 
40
}
 
41
 
 
42
 
 
43
static void signal_handler_1()
 
44
{
 
45
        signal_handler( 1, 3 );
 
46
}
 
47
 
 
48
 
 
49
void Receiver::setup()
 
50
{
 
51
        // set up an interrupts
 
52
        attachInterrupt( 0, signal_handler_0, CHANGE );
 
53
        attachInterrupt( 1, signal_handler_1, CHANGE );
 
54
        digitalWrite( 2, LOW );
 
55
        digitalWrite( 3, LOW );
 
56
}
 
57
 
 
58
 
 
59
bool Receiver::read_channels( int channel_values[] )
 
60
{
 
61
        static unsigned long last_pulse_down = 0;
 
62
        static int next_channel = 0;
 
63
 
 
64
        // capture pulse values atomically
 
65
        noInterrupts();
 
66
        unsigned long pulse_up = new_pulse_up_[ (int)new_pulse_interrupt_ ];
 
67
        unsigned long pulse_down = new_pulse_down_;
 
68
        char new_pulse_interrupt = new_pulse_interrupt_;
 
69
        interrupts();
 
70
 
 
71
        // if the amount of time that has passed since the last falling edge is
 
72
        // greater than the frame gap, reset the next channel so that we can start
 
73
        // reading them again
 
74
        if( next_channel &&
 
75
                new_pulse_interrupt == 1 &&
 
76
                calculate_duration( pulse_down, micros() ) > MIN_FRAME_GAP_WIDTH )
 
77
        {
 
78
                // reset the next channel (which restarts reading them)
 
79
                next_channel = 0;
 
80
        }
 
81
 
 
82
        // check for a new complete pulse
 
83
        if( pulse_down != last_pulse_down )
 
84
        {
 
85
                // are there still pulses to read?
 
86
                if( next_channel < NUM_CHANNELS )
 
87
                {
 
88
                        unsigned long duration =
 
89
                                calculate_duration( pulse_up, pulse_down );
 
90
 
 
91
                        // does this pulse look ok?
 
92
                        if( duration >= MIN_PULSE_WIDTH &&
 
93
                                duration <= MAX_PULSE_WIDTH )
 
94
                        {
 
95
                                // store channel value
 
96
                                int channel = channel_order_[ next_channel ] - 1;
 
97
                                channel_values[ channel ] = MAX_CHANNEL_VALUE *
 
98
                                        ( duration - MIN_PULSE_WIDTH ) /
 
99
                                        ( MAX_PULSE_WIDTH - MIN_PULSE_WIDTH );
 
100
 
 
101
                                // we got a channel
 
102
                                next_channel++;
 
103
                        }
 
104
                        else {
 
105
                                // set invalid channel number (to indicate error)
 
106
                                next_channel = NUM_CHANNELS + 1;
 
107
                        }
 
108
                }
 
109
 
 
110
                last_pulse_down = pulse_down;
 
111
        }
 
112
 
 
113
        // if we've read a frame, invalidate the frame (so we don't report it a
 
114
        // second time) and return true
 
115
        if( next_channel == NUM_CHANNELS ) {
 
116
                next_channel++;
 
117
                return true;
 
118
        }
 
119
        
 
120
        return false;
 
121
}