robobuggy / arduino / RCbuggyMegaBeforeModular / RCbuggyMega.ino @ c5d6b0e8
History | View | Annotate | Download (2.9 KB)
1 |
/* |
---|---|
2 |
* @file RCbuggyMega |
3 |
* @brief Receives data from XBee, and uses this data to control the buggy. |
4 |
* |
5 |
* Pinout circuit: |
6 |
* Serial1: Used for XBee |
7 |
* RX is digital pin 2 (connect to TX of XBee) |
8 |
* TX is digital pin 3 (connect to RX of XBee) |
9 |
* |
10 |
* Serial: Used for Programming/Debugging |
11 |
* Connect for debugging. |
12 |
* |
13 |
*/ |
14 |
#include <Servo.h> |
15 |
Servo myservo; // create servo object to control a servo |
16 |
|
17 |
#define XBEE_BAUD 9600 |
18 |
#define DEBUG_BAUD 9600 |
19 |
#define PIN_LED_XBEE_INDICATOR 4 |
20 |
#define PIN_LED_BRAKE_DEPLOYED 5 |
21 |
// comes on after two seconds of lost connection |
22 |
#define PIN_LED_LOSS_CONNECTION 12 |
23 |
|
24 |
#define PIN_BRAKE_DEPLOY_OUT 8 |
25 |
|
26 |
#define PIN_SERVO_OUT 9 |
27 |
|
28 |
// Default value for the wheel. |
29 |
#define SERVO_WHEEL_DEFAULT 133 |
30 |
|
31 |
#define PIN_HALL_EFFECT_IN 10 |
32 |
|
33 |
// Packet-sending variables |
34 |
unsigned long timer = 0L; |
35 |
char data; |
36 |
String message; |
37 |
char intbuf[32]; |
38 |
|
39 |
// Buggy variables |
40 |
int brake = 0; |
41 |
int steeringAngle = 135; |
42 |
int pingPong = 1; |
43 |
|
44 |
// String parsing variables |
45 |
int startfound = 0; |
46 |
int midfound = 0; |
47 |
int endfound = 1; |
48 |
|
49 |
void setup() { |
50 |
// Initialize debug serial and xbee serial. |
51 |
Serial.begin(DEBUG_BAUD); |
52 |
Serial1.begin(XBEE_BAUD); |
53 |
|
54 |
// Initialize the pins |
55 |
pinMode(PIN_LED_XBEE_INDICATOR, OUTPUT); |
56 |
pinMode(PIN_LED_BRAKE_DEPLOYED, OUTPUT); |
57 |
pinMode(PIN_BRAKE_DEPLOY_OUT, OUTPUT); |
58 |
myservo.attach(PIN_SERVO_OUT); // attaches the servo on pin 9 to the servo object |
59 |
myservo.write(133); |
60 |
} |
61 |
|
62 |
void loop() { |
63 |
|
64 |
// Receive and parse message from xbee |
65 |
if(Serial1.available() > 0) { |
66 |
timer = millis(); |
67 |
// read message from xbee |
68 |
data = Serial1.read(); |
69 |
// parse message data |
70 |
if (data == 'A') { |
71 |
startfound = 1; |
72 |
midfound = 0; |
73 |
endfound = 0; |
74 |
message = ""; |
75 |
} |
76 |
else if (data == 'B') { |
77 |
startfound = 0; |
78 |
midfound = 1; |
79 |
endfound = 0; |
80 |
} |
81 |
else if (data == 'C') { |
82 |
startfound = 0; |
83 |
midfound = 0; |
84 |
endfound = 1; |
85 |
} |
86 |
else if (startfound) { |
87 |
message = message + data; |
88 |
} |
89 |
else if (midfound) { |
90 |
if(data == '1') |
91 |
brake = 1; |
92 |
else |
93 |
brake = 0; |
94 |
message.toCharArray(intbuf, sizeof(intbuf)); |
95 |
steeringAngle = atoi(intbuf); |
96 |
} |
97 |
|
98 |
// flop external LED everytime message is recieved |
99 |
if ( pingPong == 0 ) { |
100 |
digitalWrite(4, LOW); |
101 |
} |
102 |
else { |
103 |
digitalWrite(4, HIGH); |
104 |
} |
105 |
|
106 |
pingPong = 1 - pingPong; |
107 |
|
108 |
} // end receive message |
109 |
|
110 |
// brake if it has been greater than 3 seconds since we last got a message |
111 |
if( (millis() - timer) > 5000L ) { |
112 |
digitalWrite(8, 0); |
113 |
digitalWrite(5, HIGH); |
114 |
exit(1); |
115 |
} |
116 |
|
117 |
if((millis() - timer) > 2000L) { |
118 |
digitalWrite(12, HIGH); |
119 |
} |
120 |
else { |
121 |
digitalWrite(12, LOW); |
122 |
} |
123 |
|
124 |
// make brake LED light up if brakes should be down |
125 |
if( brake == 0 ) { |
126 |
digitalWrite(5, HIGH); |
127 |
} |
128 |
else { |
129 |
digitalWrite(5, LOW); |
130 |
} |
131 |
|
132 |
// send parsed signal to brakes and servo |
133 |
digitalWrite(8, brake); |
134 |
|
135 |
// sets the servo position |
136 |
myservo.write(steeringAngle); |
137 |
} |