added servo for ultrasonic sensor for better range master
[arduino/rover.git] / rover / rover.ino
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
/**
* @author Razvan Stanga
* 
**/

#include <UltrasonicInterrupt.h>
#include <Servo.h> 

int DEBUG=1;
int ODEBUG=DEBUG;

const float SpeedOfSound     	= 343.2; // ~speed of sound (m/s) in air, at 20°C
const float MicrosecondsPerMillimetre 	= 1000.0 / SpeedOfSound; // microseconds per millimetre - sound travels 1 mm in ~2.9us

const float MicrosecondsToMillimetres  = (1.0 / MicrosecondsPerMillimetre);
const float MicrosecondsToMillimetres2 = MicrosecondsToMillimetres / 2.0; // beam travels the distance twice... so halve the time.

unsigned long lastTime	= 0;

int pingTimer			= 0;
int pingDelay			= 300; // milliseconds between ping pulses
int debugTimer			= 0;
int debugDelay			= 10;
int servoTimer			= 0;
int servoDelay			= 1000;

UltrasonicInterrupt s1;
const int SIGNAL1_PIN	= 2; 	// digital pin connected to the trigger port on the module
const int INTERRUPT1  = 2;    // interrupt
const int INTERRUPT1_PIN  = 0;  // custom interrupt pin, see above
float millimetres_s1 		= 0.0;

Servo FL; int FLPIN = 3; int FLC = 86;
Servo FR; int FRPIN = 5; int FRC = 92;
Servo BL; int BLPIN = 9; int BLC = 93;
Servo BR; int BRPIN = 6; int BRC = 93;
Servo FS; int FSPIN = 11; int FSC = 90; int FST = FSC; int FSM = 1;

int forwardspeed = 20;
int steerspeed = 10;
int backspeed = 10;
bool forward = true;
bool steer = false;
bool back = false;

int deg;

void setup() {

  if (DEBUG) {
    Serial.begin(9600);
  }

  // start s1 sensor instance
  s1.setup(INTERRUPT1, INTERRUPT1_PIN, SIGNAL1_PIN, callback_s1);
  s1.begin();
  
  FL.attach(FLPIN);
  FL.write (FLC);
  FR.attach(FRPIN);
  FR.write (FRC);
  BL.attach(BLPIN);
  BL.write (BLC);
  BR.attach(BRPIN);
  BR.write (BRC);
  
  FS.attach(FSPIN);
  FS.write (FSC);
  
  delay (3000);
  Serial.println ("------- start rover --------");
}

void loop() {
  
  unsigned long time = millis();
  unsigned long dt   = time - lastTime;
  lastTime 	     = time;
  
  pingTimer += dt;
  debugTimer += dt;
  servoTimer += dt;
  if(pingTimer > pingDelay){
    pingTimer = 0;
    s1.ping();
  }

  if(debugTimer > debugDelay){
    debugTimer = 0;
    //DEBUG = ODEBUG;
  } else {
    //DEBUG = 0;
  }

  // do stuff...
  if (FSM==1) {
    int i;
    for (i=40;i<=140;i++) {
      FS.write (i);
      delay (10);
      s1.ping();
      moverover(i);
    }
    for (i=140;i>=40;i--) {
      FS.write (i);
      delay (10);
      s1.ping();    
      moverover(i);
    }
  } else {
    moverover(90);
  }
}

void moverover(int deg){
  if ( millimetres_s1 < 300 ) {
    FSM=0;
    if ( millimetres_s1 < 200 ) {
      goback();
      delay(700);
      if ( deg >= 40 && deg <= 90 ) {
        goleft (1);
      } else if ( deg > 90 && deg <= 140 ) {
        goright(1);
      }
    }
    if (steer) {
      if ( deg >= 40 && deg <= 90 ) {
        if (DEBUG>=1) {
          Serial.println ("obstacle ahead in under 400mm, goleft");
        }
        goleft (2);
      } else if ( deg > 90 && deg <= 140 ) {
        if (DEBUG>=1) {
          Serial.println ("obstacle ahead in under 400mm, goright");
        }          
        goright (2);
      }
      steer = false;
    }
    forward = true; back = true;
  } else {
    FSM=1;
    if (forward) {
      if (DEBUG>=1) {
        Serial.println ("no obstacle ahead, goforward");
      }
      goforward();
      forward = false;
    }
    steer = true; back = true; 
  }
}

void stop () {
  FL.write (FLC);
  FR.write (FRC);
  BL.write (BLC);
  BR.write (BRC);
}

void goright (int sp) {
  FL.write (FLC+steerspeed);
  BL.write (BLC+steerspeed);
  if (sp==2) {
    FR.write (FRC+steerspeed);
    BR.write (BRC-steerspeed);
  }
}

void goleft (int sp) {
  if (sp==2) {
    FL.write (FLC-steerspeed);
    BL.write (BLC-steerspeed);
  }
  FR.write (FRC-steerspeed);  
  BR.write (BRC+steerspeed);
}

void goforward () {
  FL.write (FLC+forwardspeed);
  BL.write (BLC+forwardspeed);
  FR.write (FRC-forwardspeed);  
  BR.write (BRC+forwardspeed);
}

void goback () {
  FL.write (FLC-backspeed);
  BL.write (BLC-backspeed);  
  FR.write (FRC+backspeed);
  BR.write (BRC-backspeed);
}

void gobackleft () {
  FL.write (FLC-backspeed);
  BL.write (BLC-backspeed);  
  FR.write (FRC-backspeed);
  BR.write (BRC+backspeed);
}

void gobackright () {
  FL.write (FLC+backspeed);
  BL.write (BLC+backspeed);  
  FR.write (FRC+backspeed);
  BR.write (BRC-backspeed);
}

/**
* Pulse complete callback handler for UltrasonicInterrupt s1 instance
* @param duration - pulse length in microseconds
*/
void callback_s1(unsigned long duration) {

  millimetres_s1 = MicrosecondsToMillimetres2 * duration;

  if(millimetres_s1 > 4000){
    if (DEBUG>=2){
      Serial.println("s1 out of range");
    }
    // out of range (http://users.ece.utexas.edu/~valvano/Datasheets/HCSR04b.pdf)
    millimetres_s1 = 4000;
  } else {
    if (DEBUG>=2){
      Serial.print("s1 duration: ");
      Serial.print(duration);
      Serial.print(" us, distance: ");
      Serial.print(millimetres_s1);
      Serial.println(" mm");
    }
  }
}




comments