Project

General

Profile

Statistics
| Branch: | Revision:

robobuggy / arduino / RadioBuggyMega / RadioBuggyMega.ino @ 0c80370b

History | View | Annotate | Download (2.51 KB)

1
/**
2
 * @file RadioBuggyMega.ino
3
 * @author Haley Dalzell (haylee)
4
 * @author Zach Dawson (zachyzach)
5
 * @author Matt Sebek (msebek)
6
 */
7
#include "receiver.h"
8
#include "brake.h"
9
#include "encoder.h"
10
#include "watchdog.h"
11
#include "filter.h"
12

    
13

    
14
#define BRAKE_PIN 8
15
#define BRAKE_INDICATOR_PIN 5
16

    
17
#define ENCODER_PIN 7
18

    
19
#define STEERING_PIN 9
20
#define STEERING_CENTER 133
21

    
22
#define THR_PIN 2
23
#define AIL_PIN 3
24

    
25
#define XBEE_MSG_REC 4
26

    
27
#define XBEE_DANGER 12
28

    
29
#define TIME_THRESH 1000
30

    
31
unsigned long timer = 0L;
32
static char data; // used to pass things into xbee
33
static unsigned long last_time;
34

    
35
// Initialize filter for 
36
struct filter_state ail_state;
37
struct filter_state thr_state;
38

    
39
#define LED_DANGER_PIN 12
40

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

    
43
// TODO: FIX IT WHEN IT STOPS FAILING. MAKE CODE BREAK BETTER
44

    
45
void watchdog_fail(){
46
 brake_drop(); 
47
 Serial.println("Watchdog Fail! -------------------");
48
 digitalWrite(LED_DANGER_PIN, HIGH);
49
}
50

    
51

    
52

    
53
void setup()  {
54
  Serial.begin(9600);
55
  Serial1.begin(9600);
56

    
57
  //pinMode(XBEE_MSG_REC, OUTPUT);
58

    
59
  // Initialize Buggy
60
  // Pins 2 and 3: pin 2 is thr, pin 3 is ail
61
  receiver_init();
62
  filter_init(&ail_state);
63
  filter_init(&thr_state);
64
  watchdog_init(TIME_THRESH, &watchdog_fail);
65
  brake_init(BRAKE_PIN, BRAKE_INDICATOR_PIN);
66
  steering_init(STEERING_PIN, 120, 133, 145);
67
  encoder_init(ENCODER_PIN);
68
  
69
  pinMode(LED_DANGER_PIN, OUTPUT);
70

    
71
  // Set up loop
72
  //last_time = millis();
73
}
74

    
75
int convert_rc_to_steering(int rc_angle) {
76
  int out = (rc_angle/4)+(90*3/4)+39;
77
  if(out < 105 || out > 160) {
78
    Serial.println("FAKFAKFAK SERVO OUT OF RANGE");
79
    Serial.println(out);
80
    out = 129;
81
  }
82
  return out;
83
}
84

    
85
//code that keeps loop time constant each loop
86
static int hz = 40;
87
static int print_period = 1000 / hz;
88

    
89
static int rc_angle;
90
static int rc_thr;
91
static int steer_angle;
92

    
93
void loop() {
94

    
95
  if(filter_loop(&thr_state, rc_available[THR_INDEX])) {
96
    watchdog_feed();
97
    rc_angle = receiver_get_angle(THR_INDEX);
98
    steer_angle = convert_rc_to_steering(rc_angle);
99
    steering_set(steer_angle);
100
  }
101
  
102
  if(filter_loop(&ail_state, rc_available[AIL_INDEX])) {
103
    watchdog_feed();
104
    rc_thr = receiver_get_angle(AIL_INDEX);
105
    // TODO make this code...less...something
106
    if(rc_thr < 90) {
107
      brake_drop(); 
108
    } else {
109
      brake_raise();  
110
    }
111
  }
112
  
113
  // Loop
114
  watchdog_loop();
115
  encoder_loop();
116
  //xbee_loop();
117

    
118
  // If timer expired, then do ROS things
119
  if((last_time - millis()) > 0) {
120
    Serial.print(steer_angle);
121
    Serial.print("    ");
122
    Serial.println(encoder_get_count());
123
  }
124

    
125
}