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