-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathBetaNear.java
276 lines (229 loc) · 10.3 KB
/
BetaNear.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
/*
* 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.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
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;
@Autonomous(name = "Near-1", group = "Beta")
public class BetaNear 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;
int goldMineralX = -1;
int silverMineral1X = -1;
int silverMineral2X = -1;
//set up encoders
static final double COUNTS_Per_REV = 1140 ;
static final double WHEEL_DIAMETER = 4 ; //in inches
static final double COUNTS_Per_INCH = COUNTS_Per_REV/(WHEEL_DIAMETER*Math.PI);
static final double COUNTS_Per_DEGREE = COUNTS_Per_REV/((130)/WHEEL_DIAMETER);
//configure motors
private DcMotor left = null;
private DcMotor right = null;
private DcMotor lift = null;
private Servo launch = null;
//st up time
ElapsedTime runTime = new ElapsedTime();
double checkpoint1 = 10;
//set speed
static final double speed = .3 ;
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());
telemetry.addData("goldlocation",goldLocation );
if (updatedRecognitions.size() == 2) {
for (Recognition recognition : updatedRecognitions) {
if (recognition.getLabel().equals(LABEL_GOLD_MINERAL)) {
goldMineralX = (int) recognition.getRight();
} else if (silverMineral1X == -1) {
silverMineral1X = (int) recognition.getTop();
} else {
silverMineral2X = (int) recognition.getTop();
}
}
if (silverMineral1X != -1 && silverMineral2X != -1) {
telemetry.addData("Gold Mineral Position", "Left");
goldLocation = "L";
break;
}
if (goldMineralX != -1) {
if (goldMineralX < silverMineral1X) {
telemetry.addData("Gold Mineral Position", "Left");
goldLocation = "C";
break;
}
}
if (goldMineralX != -1) {
if (goldMineralX > silverMineral1X) {
telemetry.addData("Gold Mineral Position", "Left");
goldLocation = "R";
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() {
left = hardwareMap.get(DcMotor.class, "mot0");
right = hardwareMap.get(DcMotor.class, "mot1");
lift = hardwareMap.get(DcMotor.class,"mot2");
launch = hardwareMap.get(Servo.class,"ser");
//set rotational direction
left.setDirection(DcMotor.Direction.REVERSE);
right.setDirection(DcMotor.Direction.FORWARD);
lift.setDirection(DcMotor.Direction.FORWARD);
launch.setDirection(Servo.Direction.REVERSE);
waitForStart();
}
public void moveForward(double dX){//dx means displacement in inches
runTime.reset();
left.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
right.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
left.setMode(DcMotor.RunMode.RUN_TO_POSITION);
right.setMode(DcMotor.RunMode.RUN_TO_POSITION);
left.setTargetPosition((int)(dX * COUNTS_Per_INCH));
right.setTargetPosition((int)(dX * COUNTS_Per_INCH));
left.setPower(speed);
right.setPower(speed);
while (left.isBusy()){
telemetry.addData("Left",left.getCurrentPosition());
telemetry.addData("Right",right.getCurrentPosition());
telemetry.addData("goldlocation",goldLocation );
telemetry.addData("gold value",goldMineralX );
telemetry.addData("silver value",silverMineral1X );
telemetry.update();
}
left.setPower(0);
right.setPower(0);
}
public void moveBackward(double dX){//dx means displacement in inches
runTime.reset();
left.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
right.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
left.setMode(DcMotor.RunMode.RUN_TO_POSITION);
right.setMode(DcMotor.RunMode.RUN_TO_POSITION);
left.setTargetPosition((int)(dX * COUNTS_Per_INCH));
right.setTargetPosition((int)(dX * COUNTS_Per_INCH));
left.setPower(-speed);
right.setPower(-speed);
while (left.isBusy()){
telemetry.addData("Left",left.getCurrentPosition());
telemetry.addData("Right",right.getCurrentPosition());
telemetry.update();
}
left.setPower(0);
right.setPower(0);
}
public void turnClockwise(double dA){//dx means displacement
runTime.reset();
left.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
right.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
left.setMode(DcMotor.RunMode.RUN_TO_POSITION);
right.setMode(DcMotor.RunMode.RUN_TO_POSITION);
left.setTargetPosition((int)(dA * COUNTS_Per_DEGREE));
right.setTargetPosition((int)(-dA * COUNTS_Per_DEGREE));
left.setPower(speed);//power depends on the the robot and case studies are needed
right.setPower(-speed);
while (left.isBusy()){
telemetry.addData("Left",left.getCurrentPosition());
telemetry.addData("Right",right.getCurrentPosition());
telemetry.update();
}
left.setPower(0);
right.setPower(0);
}
public void turnCounterClockwise(double dA){//dx means displacement
runTime.reset();
left.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
right.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
left.setMode(DcMotor.RunMode.RUN_TO_POSITION);
right.setMode(DcMotor.RunMode.RUN_TO_POSITION);
left.setTargetPosition((int)(-dA * COUNTS_Per_DEGREE));
right.setTargetPosition((int)(dA * COUNTS_Per_DEGREE));
left.setPower(-speed);//power depends on the the robot and case studies are needed
right.setPower(speed);
while (left.isBusy()){
telemetry.addData("Left",left.getCurrentPosition());
telemetry.addData("Right",right.getCurrentPosition());
telemetry.update();
}
left.setPower(0);
right.setPower(0);
}
private void pitch() {//pitch the ball means game starts. lower down, leave the latch, come up right in front of the mineral
}
private void bat(String location) {
if (location == "L") {
moveForward(13);
turnCounterClockwise(45);
moveForward(36);
turnClockwise(90);
moveForward(36);
}
if (location == "R") {
moveForward(13);
turnClockwise(45);
moveForward(36);
turnCounterClockwise(90);
moveForward(36);
}
if (location == "C" ||location == "N") {
moveForward(13);
moveForward(38);
}
}
private void homeRun() {
launch.setPosition(-.6);
}
@Override
public void runOpMode() {
configureMotors();
sample();
bat(goldLocation);
homeRun();
}
}