Skip to content

Commit

Permalink
Added last year's brake code
Browse files Browse the repository at this point in the history
As far as I can tell, this is the code that is currently on buggy. Speak
now/soon, or forever hold your peace.
  • Loading branch information
Matt Sebek committed Sep 7, 2014
1 parent d0f9b9c commit 6b942eb
Show file tree
Hide file tree
Showing 10 changed files with 535 additions and 0 deletions.
132 changes: 132 additions & 0 deletions arduino_src/RCBuggyBackup.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
/*
Makes Arduino receive input from xbee and parse data.
The circuit:
* RX is digital pin 2 (connect to TX of XBee)
* TX is digital pin 3 (connect to RX of XBee)
*/

//#include <SoftwareSerial.h>
#include <Servo.h>

#define BRAKE_PIN 8
#define BRAKE_INDICATOR_PIN 5

#define SERVO_PIN 9
#define STEERING_CENTER 133

#define XBEE_MSG_REC 4

Servo myservo; // create servo object to control a servo

unsigned long timer = 0L;
char data;
String message;
char intbuf[32];
int brake = 0;
int steeringAngle = STEERING_CENTER;
int pingPong = 1;
int startfound = 0;
int midfound = 0;
int endfound = 1;

//code that keeps loop time constant each loop
int hz = 40;
int print_period = 1000 / hz;
unsigned long last_time = 0;

void setup() {
Serial.begin(9600);
Serial1.begin(9600);

pinMode(XBEE_MSG_REC, OUTPUT);

// initialize the brake with brake pin and led brake pin
brake_init(brakePin, brakeLedPin);


myservo.attach(SERVO_PIN); // attaches the servo on pin 9 to the servo object
myservo.write(STEEING_CENTER);
}

void loop() {

// receive and parse message from xbee
if(Serial1.available() > 0) {

timer = millis();

// read message from xbee
data = Serial1.read();

// parse message data
if (data == 'A') {
startfound = 1;
midfound = 0;
endfound = 0;
message = "";
}
else if (data == 'B') {
startfound = 0;
midfound = 1;
endfound = 0;
}
else if (data == 'C') {
startfound = 0;
midfound = 0;
endfound = 1;
}
else if (startfound) {
message = message + data;
}
else if (midfound) {
if(data == '1')
brake = 1;
else
brake = 0;
message.toCharArray(intbuf, sizeof(intbuf));
steeringAngle = atoi(intbuf);
}

// flop external LED everytime message is recieved
if ( pingPong == 0 ) {
digitalWrite(4, LOW);
}
else {
digitalWrite(4, HIGH);
}

pingPong = 1 - pingPong;

} // end receive message

// brake if it has been greater than 3 seconds since we last got a message
if( (millis() - timer) > 5000L ) {
digitalWrite(8, 0);
digitalWrite(5, HIGH);
exit(1);
}

if((millis() - timer) > 2000L) {
digitalWrite(12, HIGH);
}
else {
digitalWrite(12, LOW);
}

// make brake LED light up if brakes should be down
if( brake == 0 ) {
digitalWrite(5, HIGH);
}
else {
digitalWrite(5, LOW);
}

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

// sets the servo position
myservo.write(steeringAngle);
}

87 changes: 87 additions & 0 deletions arduino_src/RadioBuggyMega.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
/**
* @file RadioBuggyMega.ino
* @author Haley Dalzell (haylee)
* @author Zach Dawson (zachyzach)
* @author Matt Sebek (msebek)
*/
#include <Servo.h>

#define BRAKE_PIN 8
#define BRAKE_INDICATOR_PIN 5

#define ENCODER_PIN 7

#define STEERING_PIN 9
#define STEERING_CENTER 133

#define THR_PIN 2
#define AIL_PIN 3

#define XBEE_MSG_REC 4

#define XBEE_DANGER 12

unsigned long timer = 0L;
static char data; // used to pass things into xbee
int brake = 0;


enum STATE { START, RC_CON, RC_DC, BBB_CON };

void setup() {
Serial.begin(9600);
Serial1.begin(9600);

pinMode(XBEE_MSG_REC, OUTPUT);

// Initialize Buggy
// Pins 2 and 3: pin 2 is thr, pin 3 is ail
receiver_init();
brake_init(BRAKE_PIN, BRAKE_INDICATOR_PIN);
steering_init(STEERING_PIN);
encoder_init(ENCODER_PIN);

// Set up loop
last_time = millis();
}

int convert_rc_to_steering(int rc_angle) {
int out = (input/4)+(90*3/4)+39;
if(out < 105 || out > 160) {
Serial.println("FAKFAKFAK SERVO OUT OF RANGE");
Serial.println(out);
out = 129;
}
}

//code that keeps loop time constant each loop
static int hz = 40;
static int print_period = 1000 / hz;
static unsigned long last_time = 0;

static int rc_angle;
static int rc_thr;
void loop() {

if(rc_available[THR_INDEX]) {
rc_angle = receiver_get_angle(THR_INDEX);
}

steering_set(convert_rc_to_steering(rc_angle));

if(rc_available[AIL_INDEX]) {
rc_thr receiver_get_angle(THR_PIN);
}

// Loop
encoder_loop();
xbee_loop();

// If timer expired, then do ROS things
if((last_time - millis()) > 0) {
Serial.println("Loop!");


}

}
33 changes: 33 additions & 0 deletions arduino_src/brake.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
/**
* @file brake.c
* @author Audrey Yeoh (ayeoh)
* @author Matt Sebek (msebek)
*/
#include <Arduino.h>
#include "brake.h"

static int brake_pin;
// Indicator LED pin number
static int indicator_pin;

void brake_init(int brakePin, int indicatorLed) {
pinMode(brake_pin, OUTPUT);
pinMode(indicatorLed, OUTPUT);
brake_pin = brakePin;
indicator_pin = indicatorLed;
}

// Note: High-voltage raises the brake.
// Raises the brake
// Do not call before brake_init
void brake_raise() {
digitalWrite(brake_pin, HIGH);
digitalWrite(indicator_pin, LOW);
}

// Drops the brake
// Do not call before brake_init
void brake_drop() {
digitalWrite(brake_pin, LOW);
digitalWrite(indicator_pin, HIGH);
}
19 changes: 19 additions & 0 deletions arduino_src/brake.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
/**
* @file brake.h
* @author Audrey Yeoh (ayeoh)
* @author Matt Sebek (msebek)
*
* Initializes, raises, drops, and gets-state of
* the brakes.
*
*/
#ifndef _BRAKE_H_
#define _BRAKE_H_

void brake_init(int brakePin, int indicatorLedPin);

void brake_raise();

void brake_drop();

#endif
36 changes: 36 additions & 0 deletions arduino_src/encoder.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
/**
* @file encoder.c
* @author Audrey Yeoh (ayeoh)
* @author Matt Sebek (msebek0
*/

static int input_pin;

static int count=0;
// 1 if was high, 0 if was low
static int state=0;

void encoder_init(int encoder_pin) {
input_pin = encoder_pin;
pinMode(input_pin, INPUT);
}

// Every X ms, publish. (or perish!!)
void encoder_publish() {
if (last_time < (millis() - print_period)) {
Serial.println(count);
last_time = millis();
}
}

int encoder_get_count() {
return count;
}

// Lightweight, checks low-pri encoder loop
void encoder_loop(){
if (state != digital_read(input_pin)){
count++;
state = !state;
}
}
15 changes: 15 additions & 0 deletions arduino_src/encoder.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/**
* @file encoder.h
* @author Audrey Yeoh (ayeoh)
* @author Matt Sebek (msebek0
*/

void encoder_init(int encoder_pin);

// Every X ms, publish.
void encoder_publish();

int encoder_get_count();

// Lightweight, checks low-pri encoder loop
void encoder_loop();
Loading

0 comments on commit 6b942eb

Please sign in to comment.