-
Notifications
You must be signed in to change notification settings - Fork 0
/
PZ_CentralisMediocrior.c
560 lines (495 loc) · 15 KB
/
PZ_CentralisMediocrior.c
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
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
#pragma config(Hubs, S1, HTMotor, HTMotor, HTServo, HTMotor)
#pragma config(Sensor, S1, , sensorI2CMuxController)
#pragma config(Sensor, S2, gyro, sensorI2CCustom)
#pragma config(Sensor, S3, USfront, sensorSONAR)
#pragma config(Sensor, S4, HTSMUX, sensorLowSpeed)
#pragma config(Motor, motorA, arm, tmotorNXT, openLoop, encoder)
#pragma config(Motor, motorB, , tmotorNXT, openLoop, encoder)
#pragma config(Motor, motorC, , tmotorNXT, openLoop, encoder)
#pragma config(Motor, mtr_S1_C1_1, FrontRight, tmotorTetrix, PIDControl, encoder)
#pragma config(Motor, mtr_S1_C1_2, BackRight, tmotorTetrix, PIDControl, reversed, encoder)
#pragma config(Motor, mtr_S1_C2_1, Flipper, tmotorTetrix, openLoop)
#pragma config(Motor, mtr_S1_C2_2, Lift, tmotorTetrix, openLoop, encoder)
#pragma config(Motor, mtr_S1_C4_1, BackLeft, tmotorTetrix, PIDControl, encoder)
#pragma config(Motor, mtr_S1_C4_2, FrontLeft, tmotorTetrix, PIDControl, reversed, encoder)
#pragma config(Servo, srvo_S1_C3_1, grabber, tServoStandard)
#pragma config(Servo, srvo_S1_C3_2, hood, tServoStandard)
#pragma config(Servo, srvo_S1_C3_3, USfrontservo, tServoStandard)
#pragma config(Servo, srvo_S1_C3_4, holder, tServoContinuousRotation)
#pragma config(Servo, srvo_S1_C3_5, trigger, tServoStandard)
#pragma config(Servo, srvo_S1_C3_6, servo6, tServoNone)
//*!!Code automatically generated by 'ROBOTC' configuration wizard !!*//
//!!!!!!!!!!!!!!!!!!!!!!!!ALWAYS CHANGE SENSOR S4 HTSMUX to sensorLowSpeed!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
/*version 2/10/15
*author: Eula, May, Kara
*status: post league championship fix-ups
*/
#include "JoystickDriver.c"
#include "include\hitechnic-irseeker-v2.h"
#include "include\hitechnic-sensormux.h"
#include "include\lego-touch.h"
#include "include\lego-ultrasound.h"
#include "include\hitechnic-gyro.h"
//const tMUXSensor USback = msensor_S4_1;
const tMUXSensor USback = msensor_S4_2;
const tMUXSensor TOUCHfront = msensor_S4_3;
const tMUXSensor TOUCHback = msensor_S4_4;
//everything is in centimeters
static float encoderScale=1120.0;
static float wheelRadius=((9.7)/2);
static float wheelCircumference=PI*2*wheelRadius;
static int counter = 0;
static bool isUp = false;
//------------------------------nonmotor related basic stuffs--------------------------------------------------------------------------------------------
void initUS() //Initializes ultrasonic sensors
{
servo[USfrontservo] = 120;
//servo[USbackservo] = 108;
}
void armOut(){
time1[T3]=0;
while((float)time1[T3]<2000){
motor[arm] = -50;
}
motor[arm] = 0;
}
void armIn(){
//time1[T3]=0;
ClearTimer(T3);
while((float)time1[T3] < 2000){
motor[arm] = 50;
}
motor[arm] = 0;
}
//----------------------------------plain movement stuffs---------------------------------------------------------------------------------
void resetEncoders(){
nMotorEncoder[FrontLeft] = 0;
nMotorEncoder[FrontRight] = 0;
nMotorEncoder[BackLeft] = 0;
nMotorEncoder[BackRight] = 0;
wait1Msec(50);
}
void Stop()
{
motor[BackLeft] = 0;
motor[BackRight] = 0;
motor[FrontLeft] = 0;
motor[FrontRight] = 0;
}
void mecJustMove(int speed, float degrees, float speedRotation)
{
motor[FrontLeft] = speed * sinDegrees(degrees + 45) + speedRotation;
motor[FrontRight] = speed * cosDegrees(degrees + 45) - speedRotation;
motor[BackLeft] = speed * cosDegrees(degrees + 45) + speedRotation;
motor[BackRight] = speed * sinDegrees(degrees + 45) - speedRotation;
}
//-------------Move Till stuffs-------------------------------------------------------------------------------------------------------------
void mecMove(float speed, float degrees, float speedRotation, float distance)
{ //speed [-100,100], degrees [0, 360] to the right, speedRotation [-100,100], distance cm
resetEncoders();
float min = 0.0;
if (cosDegrees(degrees) == 0.0 || sinDegrees(degrees) == 0.0)
{
min = 1.0;
}
else if (abs(1.0/cosDegrees(degrees))<= abs(1.0/sinDegrees(degrees)))
{
min = 1.0/cosDegrees(degrees);
}
else
{
min = 1.0/sinDegrees(degrees);
}
float scaled = abs(encoderScale* (distance * min / wheelCircumference));
writeDebugStreamLine("*************************");
//mecJustMove(speed, degrees, speedRotation);
motor[FrontLeft] = speed * sinDegrees(degrees + 45) + speedRotation;
motor[FrontRight] = speed * cosDegrees(degrees + 45) - speedRotation;
motor[BackLeft] = speed * cosDegrees(degrees + 45) + speedRotation;
motor[BackRight] = speed * sinDegrees(degrees + 45) - speedRotation;
while((abs(nMotorEncoder[FrontLeft])<scaled) && (abs(nMotorEncoder[FrontRight])<scaled) && (abs(nMotorEncoder[BackLeft])< scaled) && (abs(nMotorEncoder[BackRight])< scaled))
{
wait1Msec(5);
// writeDebugStreamLine("%d, %d, %d, %d ", (nMotorEncoder[FrontLeft]), (nMotorEncoder[FrontRight]), (nMotorEncoder[BackLeft]), (nMotorEncoder[BackRight]));
}
Stop();
resetEncoders();
wait1Msec(10);
}
void turnMecGyro(int speed, float degrees) {
float delTime = 0;
float curRate = 0;
float currHeading = 0;
Stop();
wait1Msec(500);
HTGYROstartCal(gyro);
wait1Msec(500);
//playSound(soundBeepBeep);
mecJustMove (0, 0, speed);//+ = right - = turn left
while (abs(currHeading) < abs(degrees)) {
time1[T1] = 0;
curRate = HTGYROreadRot(gyro);
if (abs(curRate) > 3) {
currHeading += curRate * delTime; //Approximates the next heading by adding the rate*time.
if (currHeading > 360) currHeading -= 360;
else if (currHeading < -360) currHeading += 360;
}
wait1Msec(5);
delTime = ((float)time1[T1]) / 1000; //set delta (zero first time around)
}
Stop();
}
void moveTillUS(float speed, float degrees, float speedRotation, float threshold, bool till)//if till = true, move until sees something; if till = false, move until not seeing something
{
mecJustMove(speed, degrees, speedRotation);
if (till){
while ((SensorValue(USfront) > threshold)){
nxtDisplayCenteredTextLine(2, "%d, %d", (SensorValue(USfront)), (USreadDist(USback)));
}}
else{
while ((SensorValue(USfront)) < threshold || (USreadDist(USback) < threshold)){}}//should be ||, so stop when none of them is in the threshold
Stop();
}
void parallel()
{
float difference=SensorValue(USfront) > USreadDist(USback)? 20:-20;//so that the sensors doesn't have to detect twice; to save batteries
mecJustMove(0, 0, difference);
while(abs(SensorValue(USfront)-USreadDist(USback))>5)
{}
Stop();
}
void moveTillTouch(float speed, float degrees, float speedRotation, bool till)
{
mecJustMove(speed, degrees, speedRotation);
if (till){
while ((!TSreadState(TOUCHFront)) && (!TSreadState(TOUCHBack))){
nxtDisplayCenteredTextLine(2, "%d, %d", TSreadState(TOUCHfront), TSreadState(TOUCHback));
//if(HTGYROreadRot(gyro)>5){break;}
if (counter>=10)
break;
}
}
else
{
while ((TSreadState(TOUCHFront)) || (TSreadState(TOUCHBack))){
//if(HTGYROreadRot(gyro)>5){break;}
if (counter>=10)
break;
}
}
Stop();
}
//--------------------Align stuffs-----------------------------------------------------------------------------------------------------------------------------------
void ballRelease()
{
servo[trigger] = 25;
playSound(soundLowBuzz);
}
bool alignRecursiveT()//true = we are all set, false = nope not even touching now and need to realign
//don't know if RobotC allows me to do recursive or would the robot crash...?
//**the function can stop and alarm when it is not aligning anymore, which is better than alignT()
{
nxtDisplayCenteredTextLine(2, "%d, %d", TSreadState(TOUCHfront), TSreadState(TOUCHback));
if (TSreadState(TOUCHfront) == 1 && TSreadState(TOUCHback) == 1)// if both of them are touching
{
nxtDisplayCenteredTextLine(2, "%d, %d", TSreadState(TOUCHfront), TSreadState(TOUCHback));
//mecMove(-20, 0, 0, 3);
playSound(soundUpwardTones);
wait1Msec(1000);
return true;
}
if (counter >= 10){
playSound(soundDownwardTones);
wait1Msec(1000);
return false;
}
counter++;
bool result;
if (TSreadState(TOUCHfront) == 1 || TSreadState(TOUCHback) == 1)//run if at least one of them is touching, else... it is just unfortunate
{
// nxtDisplayCenteredTextLine(2, "%d, %d", TSreadState(TOUCHfront), TSreadState(TOUCHback));
//mecMove(10, 90, 0, 2);
short reading1 = TSreadState(TOUCHfront), reading2 = TSreadState(TOUCHback);
short direction = TSreadState(TOUCHfront)? 1:-1;//if only the front sensor is active, move forward
int tempspeed = 10*direction;//positive speed = forward, negative = backward
mecJustMove(tempspeed, 0, 0);
while(TSreadState(TOUCHfront) == reading1 && TSreadState(TOUCHback) == reading2)//stop if at least one of them is different from the beginning
{
if (counter>=10)
break;
nxtDisplayCenteredTextLine(2, "%d, %d", TSreadState(TOUCHfront), TSreadState(TOUCHback));
}
Stop();
result = alignRecursiveT();
// result==true? playSound(soundUpwardTones): playSound(soundDownwardTones);
return result;
}
else{
moveTillTouch(10, 90, 0, true);
result = alignRecursiveT();
// result==true? playSound(soundUpwardTones): playSound(soundDownwardTones);
return result;
}
}
//----------------Sequential Stuffs--------------------------------------------------------------------------------------------------------------------------------
void kickstand1()
{
mecMove(70,180, 0, 40);
turnMecGyro(-60, 82.0);
mecMove(-78, 0, 0, 25);
armOut();
mecMove(-78, 0, 0, 80);
mecMove(78, 0, 0, 100);
armIn();
}
void kickstand2()
{
mecMove(70,180, 0, 40);
turnMecGyro(-60, 82.0);
mecMove(-78, 0, 0, 25);
armOut();
mecMove(-78, 0, 0, 80);
mecMove(78, 0, 0, 100);
armIn();
}
void kickstand3()
{
mecMove(70,180, 0, 43);
turnMecGyro(-60, 82.0);
mecMove(-78, 0, 0, 25);
armOut();
mecMove(-78, 0, 0, 80);
mecMove(78, 0, 0, 100);
armIn();
}
void liftUp()
{
/*nMotorEncoder[Lift]=0;
motor[Lift]=-100;
while(abs(nMotorEncoder[Lift])<encoderScale*13.5) //up ratio -38/(255-127) = -.297
{
}
motor[Lift]=0;*/
nMotorEncoder[Lift]=0;
motor[Lift]=-100;
while(abs(nMotorEncoder[Lift])<encoderScale*10.7) //up ratio -38/(255-127) = -.297
{
}
motor[Lift]=0;
time1[T4]=0;
motor[Lift]=-100;
while(time1[T4]<460){
}
motor[Lift]=0;
isUp = true;
}
void liftDown()
{
nMotorEncoder[Lift]=0;
motor[Lift]=50;
// while(abs(nMotorEncoder[Lift])<encoderScale*9.0) //!!REMBER TO CHANGE TO THIS!!!
while(abs(nMotorEncoder[Lift])<encoderScale*11.0)
{
}
motor[Lift]=0;
wait1Msec(5000);
}
void readUSavg(float &frontS, float &backS)
{
int f=0, b=0;
int tfront, tback;
float tcountF = 0.0, tcountB = 0.0;
for (int i=0; i<30; i++)
{
tfront = SensorValue(USfront);
tback = USreadDist(USback);
DisplayCenteredTextLine(2, "%d, %d", tfront, tback);
writeDebugStreamLine("%d, %d", tfront, tback);
if (tfront > 40)//95
{
tcountF++;
f+=tfront;
}
if (tback > 40)//95
{
tcountB++;
b+=tback;
}
wait1Msec(50);
}
frontS=f/tcountF;
backS=b/tcountB;
DisplayCenteredTextLine(2, "%d, %d", tcountF, tcountB);
wait1Msec(1000);
}
task kickStand1()
{
kickstand1();
}
task kickStand2()
{
kickstand2();
}
task kickStand3()
{
kickstand3();
}
void endSequence() //scores balls, lowers lift, and knocks kickstand
{
alignRecursiveT(); //aligns robot so both touch sensors hit
wait1Msec(500);
mecMove(-55, 0, 0, 10.8); //shift right to align lift/ramp with center goal
wait1Msec(500);
mecMove(60, 270, 0, 3); //shift back
wait1Msec(500);
ballRelease(); //release balls with servo
wait1Msec(2000);
mecMove(60, 270, 0, 15);//move backwards
}
//===================================================================================================================================
task simuLift()
{
liftUp();
}
task timePos1()
{
time1[T2]=0;
while(true)
{
if (T2> 20000){
counter = 10;
break;
}
}
}
task timePos2()
{
time1[T2]=0;
while(true)
{
if (T2> 20000){
counter = 10;
break;
}
}
}
task timePos3()
{
time1[T2]=0;
while(true)
{
if (T2> 20000){
counter = 10;
break;
}
}
}
task disice1()
{
mecMove(78, -90, 0, 140);
mecMove(78, 90, 0, 5);
mecMove(78, 0, 0, 50);
}
//============================================================================================
task main()
{
//*************Initialization******************************
servo[hood] = 60;//hood in place
initUS();
servo[grabber] = 255;
servo[trigger] = 182;
servo[holder] = 127; //still
int Cposition;
int delay=0;
while(nNxtButtonPressed!=3){
if(nNxtButtonPressed==1) delay++;
else if(nNxtButtonPressed==2 && delay>0) delay--;
nxtDisplayCenteredTextLine(2, "%d", delay);
wait1Msec(200);
}
waitForStart();
StartTask(simuLift);
nxtDisplayCenteredTextLine(2, "%d", delay);
wait1Msec(1000*delay);
eraseDisplay();
clearDebugStream();
//********Position detection*******************************************************************
/*DisplayCenteredTextLine(2, "%d, %d", USreadDist(USfront),SensorValue(USback));
wait1Msec(500);
eraseDisplay();
DisplayCenteredTextLine(2, "%d, %d", USreadDist(USfront),SensorValue(USback));
wait1Msec(500);
eraseDisplay();
DisplayCenteredTextLine(2, "%d, %d", USreadDist(USfront),SensorValue(USback));
wait1Msec(500);
eraseDisplay();*/
mecMove(70, 90, 0, 30);
float frontS=0, backS=0;
readUSavg(frontS, backS);
if (frontS > 240 && backS > 240) {
Cposition = 2;
DisplayCenteredTextLine(2, "%d", Cposition);
playSound(soundDownwardTones);
}
else if(frontS > 70 && frontS < 95 ){//was 95 125
Cposition = 3;
DisplayCenteredTextLine(2, "%d", Cposition);
playSound(soundUpwardTones);
}
else{ //values between 128-134, but don't really need it
Cposition = 1;
DisplayCenteredTextLine(2, "%d", Cposition);
playSound(soundBeepBeep);
}
/* while (true){
DisplayCenteredTextLine(2, "%d, %d", SensorValue(USfront), USreadDist(USback));
//DisplayCenteredTextLine(2, "%d, %d", frontS, backS);
}*/
DisplayCenteredTextLine(2, "%d, %d", frontS, backS);
// mecMove(10, 90, 0, 3);//move away from the wall
switch (Cposition)
{
case 1:{
mecMove(78, 90, 0, 90);// angle should be 105, 98cm
armOut();
mecMove(78, 0, 0, 80);
mecMove(-78, 0, 0, 80);
armIn();
//wait1Msec(300);
liftDown();
startTask(disice1);
};
break;
case 2:{
startTask(timePos2);
mecMove(78, 90, 0, 50);
turnMecGyro(60, 17);
mecMove(70, 0, 0, 60);//was speed 70
wait1Msec(500);
moveTillUS(70, 0, 0, 60, true);
//wait1Msec(400);
mecMove(70, 0, 0, 3);
//wait1Msec(400);
while(!isUp){};
moveTillTouch(70, 90, 0, true);
wait1Msec(200);
endSequence();
StartTask(kickStand2); //begins kickstand knocking function
liftDown(); //brings lift down simultaneously
};
break;
case 3:{
startTask(timePos3);
mecMove(70, 0, 0, 18);
mecMove(70, 90, 0, 60);
while(!isUp){};
moveTillTouch(70, 90, 0, true);
wait1Msec(500);
endSequence();
StartTask(kickStand3); //begins kickstand knocking function
liftDown(); //brings lift down simultaneously
}
break;
}
//---------------------------------------------------------------------------
}