-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmotor.ino
272 lines (248 loc) · 12.3 KB
/
motor.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
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
#include <Servo.h>
// Define servo objects for the snake segments
Servo s1;
Servo s2;
Servo s3;
Servo s4;
Servo s5;
Servo s6;
Servo s7;
Servo s8;
Servo s9;
Servo s10;
Servo s11;
Servo s12;
Servo panServo;
// Define variables
int IRpin = 15;
int distanceReading;
int wallDistance;
int wallDistanceTolerance = 30;
int distanceReadingLeft;
int distanceReadingRight;
int wallDistanceLeft;
int wallDistanceRight;
int panDelay = 1000;
int forwardVal = 0; // Remote control variables
int reverseVal = 0;
int rightVal = 0;
int leftVal = 0;
int counter = 0; // Loop counter variable
float lag = .5712; // Phase lag between segments
int frequency = 1; // Oscillation frequency of segments.
int amplitude = 40; // Amplitude of the serpentine motion of the snake
int rightOffset = 5; // Right turn offset
int leftOffset = -5; // Left turn offset
int offset = 6; // Variable to correct servos that are not exactly centered
int delayTime = 3; // Delay between limb movements
int startPause = 5000; // Delay time to position robot
int test = -3; // Test varialble takes values from -6 to +5
void setup()
{
// Attach segments to pins
s1.attach(2);
s2.attach(3);
s3.attach(4);
s4.attach(5);
s5.attach(6);
s6.attach(7);
s7.attach(8);
s8.attach(9);
s9.attach(10);
s10.attach(11);
s11.attach(12);
s12.attach(13);
panServo.attach(14);
// Put snake in starting position
s1.write(90+offset+amplitude*cos(5*lag));
s2.write(90+offset+amplitude*cos(4*lag));
s3.write(90+offset+amplitude*cos(3*lag));
s4.write(90+amplitude*cos(2*lag));
s5.write(90+amplitude*cos(1*lag));
s6.write(90+amplitude*cos(0*lag));
s7.write(90+amplitude*cos(-1*lag));
s8.write(90+amplitude*cos(-2*lag));
s9.write(90+amplitude*cos(-3*lag));
s10.write(90+amplitude*cos(-4*lag));
s11.write(90+amplitude*cos(-5*lag));
s12.write(90+amplitude*cos(-6*lag));
delay(startPause); // Pause to position robot
}
void loop() {
// Point distance sensor straight ahead
panServo.write(90);
// Take reading from distance sensor
delay(1000);
distanceReading = analogRead(IRpin);
wallDistance = 40-distanceReading/10;
// If wallDistance > wallDistanceTolerance, move forward
if (wallDistance > wallDistanceTolerance) {
for(counter = 0; counter < 360; counter += 1) {
delay(delayTime);
s1.write(90+offset+amplitude*cos(frequency*counter*3.14159/180+5*lag));
s2.write(90+offset+amplitude*cos(frequency*counter*3.14159/180+4*lag));
s3.write(90+offset+amplitude*cos(frequency*counter*3.14159/180+3*lag));
s4.write(90+amplitude*cos(frequency*counter*3.14159/180+2*lag));
s5.write(90+amplitude*cos(frequency*counter*3.14159/180+1*lag));
s6.write(90+amplitude*cos(frequency*counter*3.14159/180+0*lag));
s7.write(90+amplitude*cos(frequency*counter*3.14159/180-1*lag));
s8.write(90+amplitude*cos(frequency*counter*3.14159/180-2*lag));
s9.write(90+amplitude*cos(frequency*counter*3.14159/180-3*lag));
s10.write(90+amplitude*cos(frequency*counter*3.14159/180-4*lag));
s11.write(90+amplitude*cos(frequency*counter*3.14159/180-5*lag));
s12.write(90+amplitude*cos(frequency*counter*3.14159/180-6*lag));
}
}
// If wallDistance , wallDistanceTolerance, stop and take
// distance measurements to the left and right
if (wallDistance < wallDistanceTolerance) {
panServo.write(170);
delay(panDelay);
distanceReadingLeft = analogRead(IRpin);
delay(panDelay);
wallDistanceLeft = 40-distanceReadingLeft/10;
panServo.write(20);
delay(panDelay);
distanceReadingRight = analogRead(IRpin);
delay(panDelay);
wallDistanceRight = 40-distanceReadingRight/10;
panServo.write(90);
delay(panDelay);
if (wallDistanceLeft > wallDistanceRight) {
// Reverse and then turn left
// Reverse
for(counter = 360; counter > 0; counter -= 1) {
delay(delayTime);
s1.write(90+offset+amplitude*cos(frequency*counter*3.14159/180+5*lag));
s2.write(90+offset+amplitude*cos(frequency*counter*3.14159/180+4*lag));
s3.write(90+offset+amplitude*cos(frequency*counter*3.14159/180+3*lag));
s4.write(90+amplitude*cos(frequency*counter*3.14159/180+2*lag));
s5.write(90+amplitude*cos(frequency*counter*3.14159/180+1*lag));
s6.write(90+amplitude*cos(frequency*counter*3.14159/180+0*lag));
s7.write(90+amplitude*cos(frequency*counter*3.14159/180-1*lag));
s8.write(90+amplitude*cos(frequency*counter*3.14159/180-2*lag));
s9.write(90+amplitude*cos(frequency*counter*3.14159/180-3*lag));
s10.write(90+amplitude*cos(frequency*counter*3.14159/180-4*lag));
s11.write(90+amplitude*cos(frequency*counter*3.14159/180-5*lag));
s12.write(90+amplitude*cos(frequency*counter*3.14159/180-6*lag));
}
// Left turn
// Ramp up turn offset
for(counter = 0; counter < 10; counter += 1) {
delay(delayTime);
s1.write(90+offset+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180+5*lag));
s2.write(90+offset+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180+4*lag));
s3.write(90+offset+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180+3*lag));
s4.write(90+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180+2*lag));
s5.write(90+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180+1*lag));
s6.write(90+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180+0*lag));
s7.write(90+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180-1*lag));
s8.write(90+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180-2*lag));
s9.write(90+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180-3*lag));
s10.write(90+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180-4*lag));
s11.write(90+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180-5*lag));
s12.write(90+.1*counter*leftOffset+amplitude*cos(frequency*counter*3.14159/180-6*lag));
}
// Continue left turn
for(counter = 11; counter < 350; counter += 1) {
delay(delayTime);
s1.write(90+offset+leftOffset+amplitude*cos(frequency*counter*3.14159/180+5*lag));
s2.write(90+offset+leftOffset+amplitude*cos(frequency*counter*3.14159/180+4*lag));
s3.write(90+offset+leftOffset+amplitude*cos(frequency*counter*3.14159/180+3*lag));
s4.write(90+leftOffset+amplitude*cos(frequency*counter*3.14159/180+2*lag));
s5.write(90+leftOffset+amplitude*cos(frequency*counter*3.14159/180+1*lag));
s6.write(90+leftOffset+amplitude*cos(frequency*counter*3.14159/180+0*lag));
s7.write(90+leftOffset+amplitude*cos(frequency*counter*3.14159/180-1*lag));
s8.write(90+leftOffset+amplitude*cos(frequency*counter*3.14159/180-2*lag));
s9.write(90+leftOffset+amplitude*cos(frequency*counter*3.14159/180-3*lag));
s10.write(90+leftOffset+amplitude*cos(frequency*counter*3.14159/180-4*lag));
s11.write(90+leftOffset+amplitude*cos(frequency*counter*3.14159/180-5*lag));
s12.write(90+leftOffset+amplitude*cos(frequency*counter*3.14159/180-6*lag));
}
// Ramp down turn offset
for(counter = 350; counter < 360; counter += 1) {
delay(delayTime);
s1.write(90+offset+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180+5*lag));
s2.write(90+offset+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180+4*lag));
s3.write(90+offset+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180+3*lag));
s4.write(90+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180+2*lag));
s5.write(90+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180+1*lag));
s6.write(90+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180+0*lag));
s7.write(90+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180-1*lag));
s8.write(90+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180-2*lag));
s9.write(90+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180-3*lag));
s10.write(90+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180-4*lag));
s11.write(90+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180-5*lag));
s12.write(90+.1*(360-counter)*leftOffset+amplitude*cos(frequency*counter*3.14159/180-6*lag));
}
}
if (wallDistanceLeft <= wallDistanceRight) {
// Reverse and turn right
// Reverse
for(counter = 360; counter > 0; counter -= 1) {
delay(delayTime);
s1.write(90+offset+amplitude*cos(frequency*counter*3.14159/180+5*lag));
s2.write(90+offset+amplitude*cos(frequency*counter*3.14159/180+4*lag));
s3.write(90+offset+amplitude*cos(frequency*counter*3.14159/180+3*lag));
s4.write(90+amplitude*cos(frequency*counter*3.14159/180+2*lag));
s5.write(90+amplitude*cos(frequency*counter*3.14159/180+1*lag));
s6.write(90+amplitude*cos(frequency*counter*3.14159/180+0*lag));
s7.write(90+amplitude*cos(frequency*counter*3.14159/180-1*lag));
s8.write(90+amplitude*cos(frequency*counter*3.14159/180-2*lag));
s9.write(90+amplitude*cos(frequency*counter*3.14159/180-3*lag));
s10.write(90+amplitude*cos(frequency*counter*3.14159/180-4*lag));
s11.write(90+amplitude*cos(frequency*counter*3.14159/180-5*lag));
s12.write(90+amplitude*cos(frequency*counter*3.14159/180-6*lag));
}
// Turn right
// Ramp up turn offset
for(counter = 0; counter < 10; counter += 1) {
delay(delayTime);
s1.write(90+offset+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180+5*lag));
s2.write(90+offset+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180+4*lag));
s3.write(90+offset+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180+3*lag));
s4.write(90+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180+2*lag));
s5.write(90+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180+1*lag));
s6.write(90+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180+0*lag));
s7.write(90+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180-1*lag));
s8.write(90+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180-2*lag));
s9.write(90+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180-3*lag));
s10.write(90+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180-4*lag));
s11.write(90+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180-5*lag));
s12.write(90+.1*counter*rightOffset+amplitude*cos(frequency*counter*3.14159/180-6*lag));
}
// Continue right turn
for(counter = 11; counter < 350; counter += 1) {
delay(delayTime);
s1.write(90+offset+rightOffset+amplitude*cos(frequency*counter*3.14159/180+5*lag));
s2.write(90+offset+rightOffset+amplitude*cos(frequency*counter*3.14159/180+4*lag));
s3.write(90+offset+rightOffset+amplitude*cos(frequency*counter*3.14159/180+3*lag));
s4.write(90+rightOffset+amplitude*cos(frequency*counter*3.14159/180+2*lag));
s5.write(90+rightOffset+amplitude*cos(frequency*counter*3.14159/180+1*lag));
s6.write(90+rightOffset+amplitude*cos(frequency*counter*3.14159/180+0*lag));
s7.write(90+rightOffset+amplitude*cos(frequency*counter*3.14159/180-1*lag));
s8.write(90+rightOffset+amplitude*cos(frequency*counter*3.14159/180-2*lag));
s9.write(90+rightOffset+amplitude*cos(frequency*counter*3.14159/180-3*lag));
s10.write(90+rightOffset+amplitude*cos(frequency*counter*3.14159/180-4*lag));
s11.write(90+rightOffset+amplitude*cos(frequency*counter*3.14159/180-5*lag));
s12.write(90+rightOffset+amplitude*cos(frequency*counter*3.14159/180-6*lag));
}
// Ramp down turn offset
for(counter = 350; counter < 360; counter += 1) {
delay(delayTime);
s1.write(90+offset+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180+5*lag));
s2.write(90+offset+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180+4*lag));
s3.write(90+offset+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180+3*lag));
s4.write(90+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180+2*lag));
s5.write(90+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180+1*lag));
s6.write(90+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180+0*lag));
s7.write(90+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180-1*lag));
s8.write(90+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180-2*lag));
s9.write(90+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180-3*lag));
s10.write(90+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180-4*lag));
s11.write(90+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180-5*lag));
s12.write(90+.1*(360-counter)*rightOffset+amplitude*cos(frequency*counter*3.14159/180-6*lag));
}
}
}
}