/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 test/receiver/pulse-width-x8/main.ino

  • Committer: dan
  • Date: 2016-04-10 17:28:24 UTC
  • Revision ID: dan-20160410172824-ev6xuubiua9rdp21
Fixed GND pin type on various components from power output to power input. Resolves ladybug check errors in escheema

Show diffs side-by-side

added added

removed removed

Lines of Context:
 
1
//
 
2
// main.ino
 
3
//
 
4
// Testing to see if we can read all 8 channels, multiplexed together on to two
 
5
// interrupts (odd channels on one, and even on the other).  We read the
 
6
// channels by measuring the pulse width.
 
7
//
 
8
// Ideally, it would be nice if we could read the raw PPM stream from the
 
9
// receiver.  Sometimes you can open up your receiver and get to this stream,
 
10
// but we have been unable.  And since this isn't guaranteed to ever be
 
11
// available, reading the analogue outputs is certainly more portable.  So, we
 
12
// are multiplexing the separate channels to two streams of pulses, like this:
 
13
//
 
14
//                  ch1  ch3  ch5  ch7  ch2  ch4  ch6  ch8
 
15
//                   |    |    |    |    |    |    |    |
 
16
//                   ▼    ▼    ▼    ▼    ▼    ▼    ▼    ▼
 
17
//                   ¯    ¯    ¯    ¯    ¯    ¯    ¯    ¯
 
18
//            ___    |    |    |    |    |    |    |    |     ___
 
19
//    GND ---|___|---+----+----+----+    +----+----+----+----|___|--- GND
 
20
//             R                    |    |                     R
 
21
//             ____________________ | __ | _____________________
 
22
//                                  |    |
 
23
//                           pin 2  o    o  pin 3
 
24
//                    (interrupt 0)        (interrupt 1)
 
25
//
 
26
// The two resistors in the circuit are pull-down resistors (so, say 100kΩ).
 
27
// Without them, the Arduino is unable to read the pulse wave at all.
 
28
//
 
29
// (Note that on our receiver, and contrary to the above diagram, the channels
 
30
// are not actually sent in order.  Channels 2 and 3 are reversed.  To this end,
 
31
// the order that channels are received can be adjusted below.)
 
32
 
 
33
 
 
34
#include <limits.h>
 
35
 
 
36
 
 
37
// minimum pulse width (in ms), used to weed out crappy signals
 
38
#define MIN_PULSE_WIDTH 1000UL
 
39
 
 
40
// maximum pulse width (in ms), used to weed out crappy signals
 
41
#define MAX_PULSE_WIDTH 2000UL
 
42
 
 
43
// number of channels
 
44
#define NUM_CHANNELS 8
 
45
 
 
46
// minimum frame gap time (in ms), used to check that the frame gap is where we
 
47
// expect it to be and that we have read the channels properly
 
48
#define MIN_FRAME_GAP_WIDTH ( 4000UL + MIN_PULSE_WIDTH )
 
49
 
 
50
// the width of the display of a single channel (in chars)
 
51
#define GRAPH_SIZE 7
 
52
 
 
53
// the channel's expected range for use in drawing (should be similar to
 
54
// {MAX,MIN}_PULSE_WIDTH values)
 
55
#define GRAPH_MIN 1000
 
56
#define GRAPH_MAX 2000
 
57
 
 
58
 
 
59
// channel sequence order
 
60
const int channel_order_[] = { 1, 3, 2, 4, 5, 6, 7, 8 };
 
61
 
 
62
// set to the time of the last pulse edges
 
63
static unsigned long new_pulse_up_[2] = { 0, 0 };
 
64
static unsigned long new_pulse_down_ = 0;
 
65
static char new_pulse_interrupt_;
 
66
 
 
67
 
 
68
// ISR to handle the PPM signals
 
69
inline void signal_handler( int interrupt, int pin )
 
70
{
 
71
        // record rising/falling edge
 
72
        if( digitalRead( pin ) )
 
73
                new_pulse_up_[ interrupt ] = micros();
 
74
        else {
 
75
                new_pulse_down_ = micros();
 
76
 
 
77
                // record which interrupt just had a falling edge
 
78
                new_pulse_interrupt_ = interrupt;
 
79
        }
 
80
}
 
81
void signal_handler_0()
 
82
{
 
83
        signal_handler( 0, 2 );
 
84
}
 
85
void signal_handler_1()
 
86
{
 
87
        signal_handler( 1, 3 );
 
88
}
 
89
 
 
90
 
 
91
void setup()
 
92
{
 
93
        // set up an interrupts
 
94
        attachInterrupt( 0, signal_handler_0, CHANGE );
 
95
        attachInterrupt( 1, signal_handler_1, CHANGE );
 
96
        digitalWrite( 2, LOW );
 
97
        digitalWrite( 3, LOW );
 
98
 
 
99
        Serial.begin( 9600 );
 
100
}
 
101
 
 
102
 
 
103
unsigned long calculate_duration( unsigned long then, unsigned long now )
 
104
{
 
105
        return now - then;
 
106
        
 
107
        if( now < then )
 
108
                return now + ( ULONG_MAX - then );
 
109
        else
 
110
                return now - then;
 
111
}
 
112
 
 
113
 
 
114
bool read_channels( unsigned long channel_values[] )
 
115
{
 
116
        static unsigned long last_pulse_down = 0;
 
117
        static int next_channel = 0;
 
118
 
 
119
        // capture pulse values atomically
 
120
        noInterrupts();
 
121
        unsigned long pulse_up = new_pulse_up_[ new_pulse_interrupt_ ];
 
122
        unsigned long pulse_down = new_pulse_down_;
 
123
        char new_pulse_interrupt = new_pulse_interrupt_;
 
124
        interrupts();
 
125
 
 
126
        // if the amount of time that has passed since the last falling edge is
 
127
        // greater than the frame gap, reset the next channel so that we can start
 
128
        // reading them again
 
129
        if( next_channel &&
 
130
                new_pulse_interrupt == 1 &&
 
131
                calculate_duration( pulse_down, micros() ) > MIN_FRAME_GAP_WIDTH )
 
132
        {
 
133
                // reset the next channel (which restarts reading them)
 
134
                next_channel = 0;
 
135
        }
 
136
 
 
137
        // check for a new complete pulse
 
138
        if( pulse_down != last_pulse_down )
 
139
        {
 
140
                // are there still pulses to read?
 
141
                if( next_channel < NUM_CHANNELS )
 
142
                {
 
143
                        unsigned long duration =
 
144
                                calculate_duration( pulse_up, pulse_down );
 
145
 
 
146
                        // does this pulse look ok?
 
147
                        if( duration >= MIN_PULSE_WIDTH &&
 
148
                                duration <= MAX_PULSE_WIDTH )
 
149
                        {
 
150
                                // store channel value
 
151
                                int channel = channel_order_[ next_channel ] - 1;
 
152
                                channel_values[ channel ] = duration;
 
153
 
 
154
                                // we got a channel
 
155
                                next_channel++;
 
156
                        }
 
157
                        else {
 
158
                                // set invalid channel number (to indicate error)
 
159
                                next_channel = NUM_CHANNELS + 1;
 
160
                        }
 
161
                }
 
162
 
 
163
                last_pulse_down = pulse_down;
 
164
        }
 
165
 
 
166
        // if we've read a frame, invalidate the frame (so we don't report it a
 
167
        // second time) and return true
 
168
        if( next_channel == NUM_CHANNELS ) {
 
169
                next_channel++;
 
170
                return true;
 
171
        }
 
172
        
 
173
        return false;
 
174
}
 
175
 
 
176
 
 
177
void draw_graph( unsigned long channel_values[] )
 
178
{
 
179
        // init graph
 
180
        static char graph[ GRAPH_SIZE + 2 ];
 
181
        static char inited_graph = false;
 
182
        if( !inited_graph ) {
 
183
                for( int a = 1; a < GRAPH_SIZE + 1; a++ )
 
184
                        graph[ a ] = '_';
 
185
                graph[ 0 ] = '|';
 
186
                graph[ GRAPH_SIZE + 1 ] = 0;
 
187
                inited_graph = true;
 
188
        }
 
189
 
 
190
        // draw channels
 
191
        for( int a = 0; a < NUM_CHANNELS; a++ ) {
 
192
                unsigned long value = max( 0,
 
193
                        min( channel_values[ a ], GRAPH_MAX ) - GRAPH_MIN );
 
194
                int pos = ( GRAPH_SIZE ) * value / ( GRAPH_MAX - GRAPH_MIN );
 
195
                graph[ pos + 1 ] = '^';
 
196
                Serial.print( graph );
 
197
                graph[ pos + 1 ] = '_';
 
198
        }
 
199
        Serial.println( "|" );
 
200
}
 
201
 
 
202
 
 
203
void loop()
 
204
{
 
205
        unsigned long channel_values[ NUM_CHANNELS ];
 
206
 
 
207
        while( true )
 
208
        {
 
209
                if( read_channels( channel_values ) )
 
210
                        draw_graph( channel_values );
 
211
        }
 
212
}