Project

General

Profile

Revision 453e1532

ID453e15321117615fb21e22e5e487ad41aaa3d5b6
Parent 0c873a67
Child 6331ce9f

Added by unknown about 10 years ago

Updated the arduino code to integrate with brake and xbee code

View differences:

arduino/RCbuggyMega/RCbuggyMega.ino
4 4
 The circuit:
5 5
 * RX is digital pin 2 (connect to TX of XBee)
6 6
 * TX is digital pin 3 (connect to RX of XBee)
7
 
8
 * changes made:
9
 * @author: Auds (ayeoh)
7 10

  
8 11
 */
9 12

  
......
12 15

  
13 16
#define BRAKE_PIN 8
14 17
#define BRAKE_INDICATOR_PIN 5
18
#define XBEE_LED_PIN 4
15 19

  
16 20
#define SERVO_PIN 9
17
#define STEERING_CENTER 133
18 21

  
19 22
Servo myservo;  // create servo object to control a servo
20 23

  
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 24
void setup()  {
35 25
  Serial.begin(9600);
36 26
  Serial1.begin(9600);
37 27

  
38
  pinMode(4, OUTPUT);
28
  xbee_init(XBEE_LED_PIN);
39 29

  
40 30
  // initialize the brake with brake pin and led brake pin
41 31
  brake_init(brakePin, brakeLedPin);
......
55 45
    // read message from xbee
56 46
    data = Serial1.read();
57 47

  
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
    }
48
    parse(data);
86 49

  
87 50
    // 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;
51
    debugMessage();
96 52

  
97 53
  } // end receive message
98 54

  
99 55
  // brake if it has been greater than 3 seconds since we last got a message
100 56
  if( (millis() - timer) > 5000L ) {
101
    digitalWrite(8, 0);
102
    digitalWrite(5, HIGH);
57
    brake_drop();
103 58
    exit(1);
104 59
  }
105 60

  
61
  /* Stuff I was told not to care about
106 62
  if((millis() - timer) > 2000L) {
107 63
    digitalWrite(12, HIGH);
108 64
  }
109 65
  else {
110 66
    digitalWrite(12, LOW);
111
  }
112

  
67
  }*/
68
  
69
  int brake = getBrake();
113 70
  // make brake LED light up if brakes should be down
114 71
  if( brake == 0 ) {
115
    digitalWrite(5, HIGH);
116
  }
117
  else {
118
    digitalWrite(5, LOW);
72
    brake_drop();
73
  }else {
74
    brake_raise();
119 75
  }
120 76

  
121
  // send parsed signal to brakes and servo
122
  digitalWrite(8, brake);
123

  
124
  // sets the servo position
77
  int steeringAngle = getSteeringAngle();
78
 
79
 s // sets the servo position
125 80
  myservo.write(steeringAngle);
126 81
}
127 82

  
arduino/RCbuggyMega/xbee.c
1 1
/**
2
 * Code relating to
2
 * Code relating to something I'm not sure yet
3
 * @author Audrey Yeoh (ayeoh)
4
 *
5
 */
6

  
7
#include <Arduino.h>
8
#include "xbee.h"
9

  
10
#define STEERING_CENTER 133
11

  
12
// holds the data read from the serial xbee
13
static char data;
14

  
15
// holds the message itself
16
static String message;
17

  
18
static int pingPong = 1;
19
static int startFound = 0;
20
static int midFound = 0;
21
static int endFound = 1;
22
static char intbuf[32];
23

  
24
static int steeringAngle = STEERING_CENTER;
25
static int brake = 0;
26

  
27
static int led;
28

  
29
void xbee_init(int ledPin){
30
  pinMode(ledPin, OUTPUT);
31
  led = ledPin;
32
}
33

  
34
// parses the data from the xbee serial
35
void parse(char data){
36
  switch(data){
37
    case 'A':
38
      startFound = 1;
39
      midFound = 0;
40
      endFound = 0;
41
      message = "";
42
      break;
43

  
44
    case 'B':
45
      startFound = 0;
46
      midFound = 1;
47
      endFound = 0;
48
      break;
49
    case 'C':
50
      startFound = 0;
51
      midFound = 0;
52
      endFound =1;
53
      break;
54
    default: // all other cases
55
      if (startFound){
56
        message = message + data;
57

  
58
      }else if (midFound){
59
        if (data == '1'){
60
          brake = 1;
61
        }else{
62
          brake = 0;
63
        }
64
        message.toCharArray(intbuf, sizeof(intbuf));
65
        steeringAngle = atoi(intbuf);
66
      }
67
      break;
68
  }
69
}
70

  
71

  
72
int getSteeringAngle(){
73
  return steeringAngle;
74
}
75

  
76
int getBrake(){
77
	return brake;
78
}
79

  
80
// flops an led everytime a message is received.
81
// Helps to debug whether messages are received
82
void debugMessage(){
83
  if (pingPong == 0){
84
    digitalWrite(led, LOW);
85
  }else{
86
    digitalWrite(led, HIGH);
87
  }
88

  
89
  pingPong = 1 - pingPong;
90
}
arduino/RCbuggyMega/xbee.h
1
/**
2
 * Code relating to something I'm not sure yet
3
 * @author Audrey Yeoh (ayeoh)
4
 *
5
 */
6

  
7
#ifndef _XBEE_H_
8
#define _XBEE_H_
9

  
10
void xbee_init(int ledPin);
11

  
12
void parse(char data);
13

  
14
int getSteeringAngle();
15

  
16
int getBrake();
17

  
18
void debugMessage();
19

  
20
#endif

Also available in: Unified diff