robobuggy / arduino / RCbuggyMega / RCbuggyMega.ino @ 08263708
History | View | Annotate | Download (2.3 KB)
1 |
/* |
---|---|
2 |
Makes Arduino receive input from xbee and parse data. |
3 |
|
4 |
The circuit: |
5 |
* RX is digital pin 2 (connect to TX of XBee) |
6 |
* TX is digital pin 3 (connect to RX of XBee) |
7 |
|
8 |
*/ |
9 |
|
10 |
//#include <SoftwareSerial.h> |
11 |
#include <Servo.h> |
12 |
|
13 |
Servo myservo; // create servo object to control a servo |
14 |
|
15 |
//SoftwareSerial xbee(2, 3); // RX, TX |
16 |
unsigned long timer = 0L; |
17 |
char data; |
18 |
String message; |
19 |
char intbuf[32]; |
20 |
int brake = 0; |
21 |
int steeringAngle = 135; |
22 |
int pingPong = 1; |
23 |
int startfound = 0; |
24 |
int midfound = 0; |
25 |
int endfound = 1; |
26 |
|
27 |
void setup() { |
28 |
Serial.begin(9600); |
29 |
//Serial.println( "Arduino started sending bytes via XBee" ); |
30 |
Serial1.begin(9600); |
31 |
|
32 |
pinMode(4, OUTPUT); |
33 |
pinMode(5, OUTPUT); |
34 |
pinMode(8, OUTPUT); |
35 |
myservo.attach(9); // attaches the servo on pin 9 to the servo object |
36 |
myservo.write(133); |
37 |
} |
38 |
|
39 |
void loop() { |
40 |
|
41 |
// receive and parse message from xbee |
42 |
if(Serial1.available() > 0) { |
43 |
|
44 |
timer = millis(); |
45 |
|
46 |
// read message from xbee |
47 |
data = Serial1.read(); |
48 |
|
49 |
// parse message data |
50 |
if (data == 'A') { |
51 |
startfound = 1; |
52 |
midfound = 0; |
53 |
endfound = 0; |
54 |
message = ""; |
55 |
} |
56 |
else if (data == 'B') { |
57 |
startfound = 0; |
58 |
midfound = 1; |
59 |
endfound = 0; |
60 |
} |
61 |
else if (data == 'C') { |
62 |
startfound = 0; |
63 |
midfound = 0; |
64 |
endfound = 1; |
65 |
} |
66 |
else if (startfound) { |
67 |
message = message + data; |
68 |
} |
69 |
else if (midfound) { |
70 |
if(data == '1') |
71 |
brake = 1; |
72 |
else |
73 |
brake = 0; |
74 |
message.toCharArray(intbuf, sizeof(intbuf)); |
75 |
steeringAngle = atoi(intbuf); |
76 |
} |
77 |
|
78 |
// flop external LED everytime message is recieved |
79 |
if ( pingPong == 0 ) { |
80 |
digitalWrite(4, LOW); |
81 |
} |
82 |
else { |
83 |
digitalWrite(4, HIGH); |
84 |
} |
85 |
|
86 |
pingPong = 1 - pingPong; |
87 |
|
88 |
} // end receive message |
89 |
|
90 |
// brake if it has been greater than 3 seconds since we last got a message |
91 |
if( (millis() - timer) > 5000L ) { |
92 |
digitalWrite(8, 0); |
93 |
digitalWrite(5, HIGH); |
94 |
exit(1); |
95 |
} |
96 |
|
97 |
if((millis() - timer) > 2000L) { |
98 |
digitalWrite(12, HIGH); |
99 |
} |
100 |
else { |
101 |
digitalWrite(12, LOW); |
102 |
} |
103 |
|
104 |
// make brake LED light up if brakes should be down |
105 |
if( brake == 0 ) { |
106 |
digitalWrite(5, HIGH); |
107 |
} |
108 |
else { |
109 |
digitalWrite(5, LOW); |
110 |
} |
111 |
|
112 |
// send parsed signal to brakes and servo |
113 |
digitalWrite(8, brake); |
114 |
|
115 |
// sets the servo position |
116 |
myservo.write(steeringAngle); |
117 |
} |
118 |
|