/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/main.ino

  • Committer: dan
  • Date: 2016-04-10 13:40:44 UTC
  • Revision ID: dan-20160410134044-mfr3vlia98tl0cun
Removed missing special library to avoid error warning

Show diffs side-by-side

added added

removed removed

Lines of Context:
 
1
//
 
2
// main.ino
 
3
//
 
4
// This software is intended to be run on a small Arduino (e.g., a Pro Mini),
 
5
// whose purpose is dedicated to talking to the RC system.  That is to say, it
 
6
// listens to the PPM signal from the RC receiver and produces a compatible
 
7
// single for the ESCs to control the motors.  It additionally talks to the main
 
8
// board via a trivial serial protocol.  In so doing, this software relieves the
 
9
// main board (and software running on it) of the task of interfacing with any
 
10
// of the RC system.
 
11
//
 
12
// Receiver
 
13
// --------
 
14
//
 
15
// The 8 channels (from the RC receiver) need to be combined and fed to two
 
16
// interrupts on the Arduino.  They need to be combined in such a way as to
 
17
// alternate pulses between the two interrupts (which are alternately used to
 
18
// read the pulses).  Like this:
 
19
//
 
20
//                  ch1  ch3  ch5  ch7  ch2  ch4  ch6  ch8
 
21
//                   |    |    |    |    |    |    |    |
 
22
//                   ▼    ▼    ▼    ▼    ▼    ▼    ▼    ▼
 
23
//                   ¯    ¯    ¯    ¯    ¯    ¯    ¯    ¯
 
24
//            ___    |    |    |    |    |    |    |    |     ___
 
25
//    GND ---|___|---+----+----+----+    +----+----+----+----|___|--- GND
 
26
//             R                    |    |                     R
 
27
//         ________________________ | __ | _____________________
 
28
//         ARDUINO                  |    |
 
29
//                           pin 2  o    o  pin 3
 
30
//                    (interrupt 0)        (interrupt 1)
 
31
//
 
32
// The two resistors in the circuit are pull-down resistors (so, say 100kΩ).
 
33
// Without them, the Arduino is unable to read the pulse wave at all.
 
34
//
 
35
// Note that your receiver may not send pulses sequentially, in "channel order".
 
36
// If this turns out to be the case, you will need to arrange for the pulses to
 
37
// wire up the channels in an order whereby the pulses arrive alternately
 
38
// between the two interrupts and adjust the channel order in config.h.
 
39
//
 
40
// Motor control
 
41
// -------------
 
42
//
 
43
// The four motor control outputs should be fed directly to the ESCs.
 
44
//
 
45
//                            ESC  ESC  ESC  ESC
 
46
//                             o    o    o    o
 
47
//                             |    |    |    |
 
48
//         ___________________ | __ | __ | __ | _____
 
49
//         ARDUINO             |    |    |    |
 
50
//                      pin 4  o    o    o    o  pin 7
 
51
//
 
52
// SERIAL INTERFACE
 
53
// ----------------
 
54
//
 
55
// The serial interface (pins 0 and 1) talk a very simple protocol.  When a
 
56
// complete set of 8 channel values have been read, it writes 0xffff followed by
 
57
// the 8, 16-bit unsigned channel values.  It expects to recieve 0xffff,
 
58
// followed by 4, 16-bit unsigned channel values.  All channel values are in the
 
59
// range specified in config.h.
 
60
 
 
61
#include "config.h"
 
62
#include "receiver.h"
 
63
#include "motors.h"
 
64
#include "comms.h"
 
65
 
 
66
 
 
67
void flash_led()
 
68
{
 
69
        static bool on = false;
 
70
        on = !on;
 
71
        digitalWrite( LED_PIN, on? HIGH : LOW );
 
72
}
 
73
 
 
74
 
 
75
void setup()
 
76
{
 
77
        // init subsystems
 
78
        Receiver::setup();
 
79
        Motors::setup();
 
80
        Comms::setup();
 
81
 
 
82
        // led
 
83
        pinMode( LED_PIN, OUTPUT );
 
84
        digitalWrite( LED_PIN, LOW );
 
85
}
 
86
 
 
87
void loop()
 
88
{
 
89
        int motor_values[ NUM_MOTORS ];
 
90
        int channel_values[ NUM_CHANNELS ];
 
91
 
 
92
        // reset the motor values
 
93
        for( int a = 0; a < NUM_MOTORS; a++ )
 
94
                motor_values[ a ] = 0;
 
95
 
 
96
        while( true )
 
97
        {
 
98
                // have we read a whole set of channel values?
 
99
                if( Receiver::read_channels( channel_values ) )
 
100
                {
 
101
                        // yes, flash led!
 
102
                        flash_led();
 
103
 
 
104
                        // send channel values to main board
 
105
                        Comms::write_channels( channel_values );
 
106
                }
 
107
 
 
108
                // update motors
 
109
                Motors::update();
 
110
 
 
111
                // read channel values from main board
 
112
                if( Comms::read_channels( motor_values ) )
 
113
                {
 
114
                        // set motor speeds
 
115
                        Motors::set_values( motor_values );
 
116
                }
 
117
 
 
118
                // update motors
 
119
                Motors::update();
 
120
        }
 
121
}