Project

General

Profile

Statistics
| Branch: | Revision:

robobuggy / arduino / RCbuggyMega / RCbuggyMega.ino @ 02df64f0

History | View | Annotate | Download (2.88 KB)

1 08263708 Haley
/*
2 02df64f0 Matt Sebek
 * @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 08263708 Haley
 */
14
#include <Servo.h> 
15
Servo myservo;  // create servo object to control a servo 
16
17 02df64f0 Matt Sebek
#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 08263708 Haley
unsigned long timer = 0L;
35
char data;
36
String message;
37
char intbuf[32];
38 02df64f0 Matt Sebek
39
// Buggy variables
40 08263708 Haley
int brake = 0;
41
int steeringAngle = 135;
42
int pingPong = 1;
43 02df64f0 Matt Sebek
44
// String parsing variables
45 08263708 Haley
int startfound = 0;
46
int midfound = 0;
47
int endfound = 1;
48
49
void setup()  {
50 02df64f0 Matt Sebek
  // Initialize debug serial and xbee serial. 
51
  Serial.begin(DEBUG_BAUD);
52
  Serial1.begin(XBEE_BAUD);
53 08263708 Haley
54 02df64f0 Matt Sebek
  pinMode(PIN_LED_XBEE_INDICATOR, OUTPUT);
55
  pinMode(PIN_LED_BRAKE_DEPLOYED, OUTPUT);
56
  pinMode(PIN_BRAKE_DEPLOY_OUT, OUTPUT);
57
  myservo.attach(PIN_SERVO_OUT);  // attaches the servo on pin 9 to the servo object 
58 08263708 Haley
  myservo.write(133);
59
}
60
61
void loop()  {
62
63
  // receive and parse message from xbee
64
  if(Serial1.available() > 0) { 
65
66
    timer = millis();
67
68
    // read message from xbee
69
    data = Serial1.read();
70
71
    // parse message data
72
    if (data == 'A') {
73
      startfound = 1;
74
      midfound = 0;
75
      endfound = 0;
76
      message = "";
77
    }
78
    else if (data == 'B') {
79
      startfound = 0;
80
      midfound = 1;
81
      endfound = 0;
82
    }
83
    else if (data == 'C') {
84
      startfound = 0;
85
      midfound = 0;
86
      endfound = 1;
87
    }
88
    else if (startfound) {
89
      message = message + data;
90
    }
91
    else if (midfound) {
92
      if(data == '1')
93
        brake = 1;
94
      else
95
        brake = 0;
96
      message.toCharArray(intbuf, sizeof(intbuf));
97
      steeringAngle = atoi(intbuf);
98
    }  
99
100
    // flop external LED everytime message is recieved
101
    if ( pingPong == 0 ) {
102
      digitalWrite(4, LOW);
103
    } 
104
    else {
105
      digitalWrite(4, HIGH);
106
    }
107
108
    pingPong = 1 - pingPong;
109
110
  } // end receive message
111
112
  // brake if it has been greater than 3 seconds since we last got a message
113
  if( (millis() - timer) > 5000L ) {
114
    digitalWrite(8, 0);
115
    digitalWrite(5, HIGH);
116
    exit(1);
117
  }
118
119
  if((millis() - timer) > 2000L) {
120
    digitalWrite(12, HIGH);
121
  }
122
  else {
123
    digitalWrite(12, LOW);
124
  }
125
126
  // make brake LED light up if brakes should be down
127
  if( brake == 0 ) {
128
    digitalWrite(5, HIGH);
129
  } 
130
  else {
131
    digitalWrite(5, LOW);
132
  }
133
134
  // send parsed signal to brakes and servo
135
  digitalWrite(8, brake);
136
137
  // sets the servo position
138
  myservo.write(steeringAngle);
139
}