robobuggy / arduino / RCbuggyMega / RCbuggyMega.ino @ c5d6b0e8
History | View | Annotate | Download (2.44 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 |
int brakePin = 8; |
28 |
int brakeLedPin = 5; |
29 |
|
30 |
void setup() { |
31 |
Serial.begin(9600); |
32 |
//Serial.println( "Arduino started sending bytes via XBee" ); |
33 |
Serial1.begin(9600); |
34 |
|
35 |
pinMode(4, OUTPUT); |
36 |
pinMode(5, OUTPUT); |
37 |
pinMode(8, OUTPUT); |
38 |
|
39 |
brake_init(brakePin, brakeLedPin); // initialize the brake with brake pin and led brake pin |
40 |
|
41 |
myservo.attach(9); // attaches the servo on pin 9 to the servo object |
42 |
myservo.write(133); |
43 |
} |
44 |
|
45 |
void loop() { |
46 |
|
47 |
// receive and parse message from xbee |
48 |
if(Serial1.available() > 0) { |
49 |
|
50 |
timer = millis(); |
51 |
|
52 |
// read message from xbee |
53 |
data = Serial1.read(); |
54 |
|
55 |
// parse message data |
56 |
if (data == 'A') { |
57 |
startfound = 1; |
58 |
midfound = 0; |
59 |
endfound = 0; |
60 |
message = ""; |
61 |
} |
62 |
else if (data == 'B') { |
63 |
startfound = 0; |
64 |
midfound = 1; |
65 |
endfound = 0; |
66 |
} |
67 |
else if (data == 'C') { |
68 |
startfound = 0; |
69 |
midfound = 0; |
70 |
endfound = 1; |
71 |
} |
72 |
else if (startfound) { |
73 |
message = message + data; |
74 |
} |
75 |
else if (midfound) { |
76 |
if(data == '1') |
77 |
brake = 1; |
78 |
else |
79 |
brake = 0; |
80 |
message.toCharArray(intbuf, sizeof(intbuf)); |
81 |
steeringAngle = atoi(intbuf); |
82 |
} |
83 |
|
84 |
// flop external LED everytime message is recieved |
85 |
if ( pingPong == 0 ) { |
86 |
digitalWrite(4, LOW); |
87 |
} |
88 |
else { |
89 |
digitalWrite(4, HIGH); |
90 |
} |
91 |
|
92 |
pingPong = 1 - pingPong; |
93 |
|
94 |
} // end receive message |
95 |
|
96 |
// brake if it has been greater than 3 seconds since we last got a message |
97 |
if( (millis() - timer) > 5000L ) { |
98 |
digitalWrite(8, 0); |
99 |
digitalWrite(5, HIGH); |
100 |
exit(1); |
101 |
} |
102 |
|
103 |
if((millis() - timer) > 2000L) { |
104 |
digitalWrite(12, HIGH); |
105 |
} |
106 |
else { |
107 |
digitalWrite(12, LOW); |
108 |
} |
109 |
|
110 |
// make brake LED light up if brakes should be down |
111 |
if( brake == 0 ) { |
112 |
digitalWrite(5, HIGH); |
113 |
} |
114 |
else { |
115 |
digitalWrite(5, LOW); |
116 |
} |
117 |
|
118 |
// send parsed signal to brakes and servo |
119 |
digitalWrite(8, brake); |
120 |
|
121 |
// sets the servo position |
122 |
myservo.write(steeringAngle); |
123 |
} |
124 |
|