-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathSigmaFar.java
363 lines (322 loc) · 12.6 KB
/
SigmaFar.java
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
/*
* Author: Benton Li '19
* Version: 1.0
*
* */
package org.firstinspires.ftc.teamcode;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.util.ElapsedTime;
import org.firstinspires.ftc.robotcore.external.ClassFactory;
import org.firstinspires.ftc.robotcore.external.navigation.VuforiaLocalizer;
import org.firstinspires.ftc.robotcore.external.navigation.VuforiaLocalizer.CameraDirection;
import org.firstinspires.ftc.robotcore.external.tfod.Recognition;
import org.firstinspires.ftc.robotcore.external.tfod.TFObjectDetector;
import java.util.List;
@Disabled
@Autonomous(name = "Far-2")
public class SigmaFar extends LinearOpMode {
//preparation for these cool vuforia stuffs
private static final String TFOD_MODEL_ASSET = "RoverRuckus.tflite";
private static final String LABEL_GOLD_MINERAL = "Gold Mineral";
private static final String LABEL_SILVER_MINERAL = "Silver Mineral";
private VuforiaLocalizer vuforia;
private TFObjectDetector tfod;
private static final String VUFORIA_KEY = "AUrb6t//////AAABmZ7sUnVME0wvu2pmOKRP5ilgE5gzg4vWVqHNhc0ef2FEwf9NlosWkTS81UmRvZ0UTHFjPeQYLKL6iY60ZJQcJFcMftURUv/1nA/9YELScRwzltxrUAFpfMA/VE9VTaNPTQQYUfm1Z1wUwY6fAJBwDvZJP+UBqPD0AJxz0Gf8jgcdCVgu4A7VtVdk1PRMTSUkHdOEm+VmXzpjxL9X4d/v81mx3aqJbVc6+qhUD53umiep/wCgl9WxHYY6ZEM2tuS7Eih3TexL24HLFvdEu79t24yTzCFz6du/hB12nfyySO78UWbdlusHuHIv0ZI5/IWh4RigF057FaLWc4F+EluGBkO0c6ygIaciN5fHPS9l7dtj";
String goldLocation;
//configure motors
private DcMotor leftFront = null;
private DcMotor rightFront = null;
private DcMotor leftBack = null;
private DcMotor rightBack = null;
private DcMotor lift = null;
private Servo ser = null;
int p = 1; //default power
float x = 0;//default x-coord
float y = 0;//default y-coord
String direction = "static";//default direction
ElapsedTime runTime = new ElapsedTime();
double checkpoint1 = 10;
double checkpoint2 = 20;
public void sample() {
runTime.reset();
initVuforia();
initTfod();
tfod.activate();
goldLocation = "N";
while (goldLocation == "N" && runTime.time() < checkpoint1) {
if (tfod != null) {
// getUpdatedRecognitions() will return null if no new information is available since
// the last time that call was made.
List<Recognition> updatedRecognitions = tfod.getUpdatedRecognitions();
if (updatedRecognitions != null) {
telemetry.addData("# Object Detected", updatedRecognitions.size());
if (updatedRecognitions.size() == 3) {
int goldMineralX = -1;
int silverMineral1X = -1;
int silverMineral2X = -1;
for (Recognition recognition : updatedRecognitions) {
if (recognition.getLabel().equals(LABEL_GOLD_MINERAL)) {
goldMineralX = (int) recognition.getLeft();
} else if (silverMineral1X == -1) {
silverMineral1X = (int) recognition.getLeft();
} else {
silverMineral2X = (int) recognition.getLeft();
}
}
if (goldMineralX != -1 && silverMineral1X != -1 && silverMineral2X != -1) {
if (goldMineralX < silverMineral1X && goldMineralX < silverMineral2X) {
telemetry.addData("Gold Mineral Position", "Left");
goldLocation = "L";
break;
} else if (goldMineralX > silverMineral1X && goldMineralX > silverMineral2X) {
telemetry.addData("Gold Mineral Position", "Right");
goldLocation = "R";
break;
} else {
telemetry.addData("Gold Mineral Position", "Center");
goldLocation = "C";
break;
}
}
}
telemetry.update();
}
}
}
//Four endings for this story: left, right, center, nothing
}
private void initVuforia() {
VuforiaLocalizer.Parameters parameters = new VuforiaLocalizer.Parameters();
parameters.vuforiaLicenseKey = VUFORIA_KEY;
parameters.cameraDirection = CameraDirection.BACK;
vuforia = ClassFactory.getInstance().createVuforia(parameters);
}
private void initTfod() {
int tfodMonitorViewId = hardwareMap.appContext.getResources().getIdentifier(
"tfodMonitorViewId", "id", hardwareMap.appContext.getPackageName());
TFObjectDetector.Parameters tfodParameters = new TFObjectDetector.Parameters(tfodMonitorViewId);
tfod = ClassFactory.getInstance().createTFObjectDetector(tfodParameters, vuforia);
tfod.loadModelFromAsset(TFOD_MODEL_ASSET, LABEL_GOLD_MINERAL, LABEL_SILVER_MINERAL);
}
private void configureMotors(){
leftFront = hardwareMap.get(DcMotor.class, "mot0");
leftBack = hardwareMap.get(DcMotor.class, "mot2");
rightFront = hardwareMap.get(DcMotor.class, "mot1");
rightBack = hardwareMap.get(DcMotor.class, "mot3");
//ser = hardwareMap.get(Servo.class,"ser");
// lift = hardwareMap.get(DcMotor.class,"lift");
//set rotational direction
leftFront.setDirection(DcMotor.Direction.REVERSE);
rightFront.setDirection(DcMotor.Direction.FORWARD);
leftBack.setDirection(DcMotor.Direction.REVERSE);
rightBack.setDirection(DcMotor.Direction.FORWARD);
}
public void dump(){
}
public void move(String dir, double magnitude){
direction = dir;
if (direction == "static"){
runTime.reset();
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "LF"){
runTime.reset();
leftFront.setPower(0);
leftBack.setPower(p);
rightFront.setPower(0);
rightBack.setPower(p);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "RF"){
runTime.reset();
leftFront.setPower(p);
leftBack.setPower(0);
rightFront.setPower(p);
rightBack.setPower(0);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "LB"){
runTime.reset();
leftFront.setPower(-p);
leftBack.setPower(0);
rightFront.setPower(-p);
rightBack.setPower(0);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "RB"){
runTime.reset();
leftFront.setPower(0);
leftBack.setPower(-p);
rightFront.setPower(0);
rightBack.setPower(-p);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "RR"){
runTime.reset();
leftFront.setPower(p);
leftBack.setPower(-p);
rightFront.setPower(p);
rightBack.setPower(-p);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "LL"){
runTime.reset();
leftFront.setPower(-p);
leftBack.setPower(p);
rightFront.setPower(-p);
rightBack.setPower(p);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "FF"){
runTime.reset();
leftFront.setPower(.7*p);
leftBack.setPower(.7*p);
rightFront.setPower(.7*p);
rightBack.setPower(.7*p);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "BB"){
runTime.reset();
leftFront.setPower(-.7*p);
leftBack.setPower(-.7*p);
rightFront.setPower(-.7*p);
rightBack.setPower(-.7*p);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "CO"){
runTime.reset();
leftFront.setPower(-.7*p);
leftBack.setPower(-.7*p);
rightFront.setPower(+.7*p);
rightBack.setPower(+.7*p);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
if (direction == "CC"){
runTime.reset();
leftFront.setPower(+.7*p);
leftBack.setPower(+.7*p);
rightFront.setPower(-.7*p);
rightBack.setPower(-.7*p);
while (runTime.seconds()<magnitude){
telemetry.addData("time",runTime.seconds());
telemetry.update();
}
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
}
}
private void pitch(){//pitch the ball means game starts. lower down, leave the latch, come up right in front of the mineral
move("FF",10);
}
private void bat(String location) {
if (location == "L") {
move("LL",3);
move("FF",3);
move("BB",3);
move("LL",6);
}
if (location == "R") {
move("RR",9);
move("FF",3);
move("BB",3);
move("LL",18);
}
if (location == "C" ||location == "N") {
move("RR",3);
move("FF",3);
move("BB",3);
move("LL",12);
}
}
private void homeRun(){
move("RF",30);
//dump();
}
@Override
public void runOpMode() {
configureMotors();
pitch();
bat(goldLocation);
homeRun();
}
}