Newer
Older
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
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
#include "Move.h"
Move* Move::_singleton = 0;
Move* Move::singleton()
{
if (_singleton==0)
_singleton = new Move();
return _singleton;
}
Move::Move()
{
Serial.println("Move manager created !");
inversedSense = false;
sensorEnabled = true;
performKind = MOVE_NONE;
performStartTimer = 0;
performTimeLeft = 0;
performRunning = false;
// Create the Servos
wheelLeft = new Servo();
wheelRight = new Servo();
// Init the servos
wheelLeft->attach(PIN_WL,210,2400); //100,1500 || 200,2400
wheelRight->attach(PIN_WR,230,2400); //80,1500 || 220,2400
// Init the sharp sensors
initSharp();
actionList = (MoveAction**) malloc(sizeof(MoveAction*) * ACTION_NUMBERS);
actionNumber = 0;
actionCurrent = 0;
performSpeed = 0;
performIsAccelerating = false;
// Location
x = 4.;
y = 20.;
angle = 0.;
previousTime = micros();
stop();
}
Move::~Move()
{
//dtor
}
void Move::initSharp()
{
sharpList = (Sharp**) malloc(sizeof(Sharp*) * SHARP_NUMBERS);
sharpList[SHARP_FRONT_L] = new Sharp(A1);
sharpList[SHARP_FRONT_R] = new Sharp(A3);
sharpList[SHARP_FRONT_C] = new Sharp(A4);
sharpList[SHARP_BEHIND] = new Sharp(A0);
}
void Move::updateSharp()
{
for(int i(0); i<SHARP_NUMBERS; i++)
sharpList[i]->update();
}
void Move::update(int timeSinceLastFrame)
{
updateSharp();
/*Serial.print(" Sharps (FL, FC, FL, B) : ");
Serial.print(sharpList[SHARP_FRONT_L]->getValue());
Serial.print(" ");
Serial.print(sharpList[SHARP_FRONT_C]->getValue());
Serial.print(" ");
Serial.print(sharpList[SHARP_FRONT_R]->getValue());
Serial.print(" ");
Serial.print(analogRead(A1));
Serial.print(" ");
Serial.print(sharpList[SHARP_BEHIND]->getValue());
Serial.print("\n");*/
if (performKind!=MOVE_NONE)
{
if (placeFree(performKind) || performKind==DELAY || performKind==ENABLE_SHARPS || performKind==DISABLE_SHARPS)
{
if (!performRunning)
{
Serial.println("Robot no longer Detected, resume action");
DiodeMgr::singleton()->getLed(2)->off();
startAction(performKind);
}
doAction(performKind);
// Timer update
if (performIsAccelerating)
{
if (performSpeed<1.)
performSpeed += W_ACC;
//if (performTimeLeft < WF_SPEED*performSpeed*W_INVACC)
else
performIsAccelerating = false;
//Serial.println(performSpeed);
}
else
{
/*if (performSpeed>0.4)
performSpeed -= W_ACC;
else */if (performSpeed<0.3)
performSpeed = 0.3;
}
int factor = (micros() - previousTime)*performSpeed;
previousTime = micros();
//Serial.println(factor);
performTimeLeft -= factor;
switch(performKind)
{
case MOVE_45ANTICLOCK:
angle += factor/8334.;
break;
case MOVE_45CLOCK:
angle -= factor/8334.;
break;
default:
x += cos(angle) * factor / MOVE_TIME_DISTANCE_RATIO;
y += sin(angle) * factor / MOVE_TIME_DISTANCE_RATIO;
break;
}
if (performTimeLeft <= 0)
{
performIsAccelerating = false;
Serial.print(" Finished ! position (x,y,angle) : (");
Serial.print(x);
Serial.print(" ");
Serial.print(y);
Serial.print(" ");
Serial.print(angle);
Serial.print(")\n");
Serial.print(" Time spent over the limit : ");
Serial.print(-performTimeLeft);
Serial.print(" microseconds\n");
stop();
delay(150);
}
}
else if (performRunning)
{
Serial.println(" Robot Detected, pause...");
Serial.print(" Sharps (FL, FC, FL, B) : ");
Serial.print(sharpList[SHARP_FRONT_L]->getValue());
Serial.print(" ");
Serial.print(sharpList[SHARP_FRONT_C]->getValue());
Serial.print(" ");
Serial.print(sharpList[SHARP_FRONT_R]->getValue());
Serial.print(" ");
Serial.print(sharpList[SHARP_BEHIND]->getValue());
Serial.print("\n");
DiodeMgr::singleton()->getLed(2)->on();
pause();
previousTime = micros();
}
else
previousTime = micros();
}
else
{
// Treat the list
if (actionNumber>actionCurrent)
{
DiodeMgr::singleton()->getLed(1)->on();
perform(actionList[actionCurrent]->getKind(), actionList[actionCurrent]->getDistance());
actionCurrent += 1;
}
else
DiodeMgr::singleton()->getLed(1)->off();
previousTime = micros();
}
}
bool Move::perform(MOVE_KIND kind, float distance, bool overwrite)
{
if (kind==MOVE_NONE)
{
stop();
return true;
}
if (overwrite || isReady())
{
Serial.print("Starting action... ");
performStartTimer = micros();
switch(kind)
{
case DELAY:
Serial.print("Delaying Skarabi");
performTimeLeft = distance * 1000;
break;
case MOVE_45ANTICLOCK:
Serial.print(45*distance);
Serial.print(" degrees anti-clockwise");
performTimeLeft = W_45ANTITIME * distance;
break;
case MOVE_45CLOCK:
Serial.print(45*distance);
Serial.print(" degrees clockwise");
performTimeLeft = W_45CLOCKTIME * distance;
break;
case DISABLE_SHARPS:
setSensor(false);
Serial.print(" DISABLING SHARPS");
performTimeLeft = 0;
break;
case ENABLE_SHARPS:
setSensor(true);
Serial.print(" ENABLING SHARPS");
performTimeLeft = 0;
break;
default:
performTimeLeft = distance * MOVE_TIME_DISTANCE_RATIO;
break;
}
if (distance>0)
{
Serial.print(", duration : ");
Serial.print(performTimeLeft/1000);
Serial.print(" ms");
}
Serial.print("\n");
startAction(kind);
return true;
}
else
{
Serial.println("Can't start an action : the previous one wasn't finished !");
return false;
}
}
void Move::startAction(MOVE_KIND kind)
{
performKind = kind;
performRunning = true;
performIsAccelerating = true;
performSpeed = 1.;
doAction(kind);
}
void Move::doAction(MOVE_KIND kind)
{
switch(kind)
{
case MOVE_FORWARD:
wheelLeft->write(WL_STOP + WL_FORWARD*WF_SPEED*performSpeed);
wheelRight->write(WR_STOP + WR_FORWARD*WF_SPEED*performSpeed);
break;
case MOVE_BACKWARD:
wheelLeft->write(WL_STOP + WL_BACKWARD*WF_SPEED*performSpeed);
wheelRight->write(WR_STOP + WR_BACKWARD*WF_SPEED*performSpeed);
break;
case MOVE_45ANTICLOCK:
wheelLeft->write(WL_STOP + WL_45ANTI*WF_SPEED*performSpeed);
wheelRight->write(WR_STOP + WR_45ANTI*WF_SPEED*performSpeed);
break;
case MOVE_45CLOCK:
wheelLeft->write(WL_STOP + WL_45CLOCK*WF_SPEED*performSpeed);
wheelRight->write(WR_STOP + WR_45CLOCK*WF_SPEED*performSpeed);
break;
}
}
void Move::pause()
{
performSpeed = 0;
wheelLeft->write(WL_STOP);
wheelRight->write(WR_STOP);
performRunning = false;
}
void Move::stop()
{
performSpeed = 0;
Serial.println("Robot halted !");
Serial.println("");
wheelLeft->write(WL_STOP);
wheelRight->write(WR_STOP);
performKind = MOVE_NONE;
performRunning = false;
}
bool Move::isReady()
{
return (performKind == MOVE_NONE);
}
void Move::setSensor(bool enable)
{
sensorEnabled = enable;
}
void Move::setInversedSense(bool inversed)
{
inversedSense = inversed;
Serial.println("Sense of rotation changed !");
}
bool Move::placeFree(MOVE_KIND kind)
{
if (!sensorEnabled)
return true;
switch(kind)
{
case MOVE_FORWARD:
return (!(sharpList[SHARP_FRONT_L]->getValue()||sharpList[SHARP_FRONT_R]->getValue()||sharpList[SHARP_FRONT_C]->getValue()));
break;
case MOVE_BACKWARD:
return (!(sharpList[SHARP_BEHIND]->getValue()));
break;
case MOVE_45ANTICLOCK:
return (!sharpList[SHARP_FRONT_L]->getValue());
break;
case MOVE_45CLOCK:
return (!sharpList[SHARP_FRONT_R]->getValue());
break;
default:
return false;
break;
}
}
void Move::addAction(MOVE_KIND kind, float distance)
{
if (actionNumber < ACTION_NUMBERS-1)
{
Serial.println("Action added to the queue !");
// Inverse if needed
if (inversedSense)
{
if (kind==MOVE_45ANTICLOCK)
kind = MOVE_45CLOCK;
else if (kind==MOVE_45CLOCK)
kind = MOVE_45ANTICLOCK;
}
actionList[actionNumber] = new MoveAction(kind,distance);
actionNumber+=1;
}
else
Serial.println("Can't queue action : too many actions !");
}