-
Notifications
You must be signed in to change notification settings - Fork 0
/
CraterCrossingCollecting.java
540 lines (469 loc) · 24.5 KB
/
CraterCrossingCollecting.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
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
/* Copyright (c) 2018 FIRST. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted (subject to the limitations in the disclaimer below) provided that
* the following conditions are met:
*
* Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
* promote products derived from this software without specific prior written permission.
*
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
package org.firstinspires.ftc.teamcode;
import android.app.Activity;
import android.view.View;
import com.qualcomm.hardware.bosch.BNO055IMU;
import com.qualcomm.hardware.bosch.JustLoggingAccelerationIntegrator;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.ColorSensor;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DistanceSensor;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.hardware.TouchSensor;
import com.qualcomm.robotcore.util.ElapsedTime;
import org.firstinspires.ftc.robotcore.external.ClassFactory;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
import org.firstinspires.ftc.robotcore.external.navigation.AxesOrder;
import org.firstinspires.ftc.robotcore.external.navigation.AxesReference;
import org.firstinspires.ftc.robotcore.external.navigation.Orientation;
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;
//import org.firstinspires.ftc.robotcore.external.tfod.TFObjectDetector;
/**
* This 2018-2019 OpMode illustrates the basics of using the TensorFlowFront Object Detection API to
* determine the position of the gold and silver minerals.
*
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
* Remove or comment out the @Disabled line to add this opmode to the Driver Station OpMode list.
*
* IMPORTANT: In order to use this OpMode, you need to obtain your own Vuforia license key as
* is explained below.
*/
@Autonomous(name = "Crater Crossing Collecting", group = "4924")
public class CraterCrossingCollecting extends LinearOpMode {
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 ElapsedTime runtime = new ElapsedTime();
DcMotor frontLeft;
DcMotor frontRight;
DcMotor backLeft;
DcMotor backRight;
DcMotor linearMotor;
TouchSensor limitSwitch;
TouchSensor rotationSwitch;
Servo linearServo;
// CRServo collectionServo;
Servo marker;
CRServo tape;
CRServo tapeM;
Servo led;
Servo mineralServo;
ColorSensor sensorColor;
DistanceSensor sensorDistance;
DcMotor extension;
DcMotor rotation;
DcMotor collectionServo;
Servo deliveryServo;
Servo armBump;
static final double COUNTS_PER_MOTOR_REV = 1425.2 ;
static final double DRIVE_GEAR_REDUCTION = 2.0 ; // This is < 1.0 if geared UP
static final double WHEEL_DIAMETER_INCHES = 4.0 ; // For figuring circumference
static final double COUNTS_PER_INCH = (COUNTS_PER_MOTOR_REV * DRIVE_GEAR_REDUCTION) /
(WHEEL_DIAMETER_INCHES * 3.1415);
static final double DRIVE_SPEED = 0.75;
static BNO055IMU imu;
static BNO055IMU.Parameters IMU_Parameters = new BNO055IMU.Parameters();
Orientation angles;
protected static DcMotor[] DRIVE_BASE_MOTORS = new DcMotor[4];
private static final double GYRO_TURN_TOLERANCE_DEGREES = 3;
boolean rotationOut = false;
boolean landed = false;
boolean latched = false;
boolean kicked = false;
int direction = 0;
boolean detected = false;
boolean markerDone = false;
boolean done1 = false;
int goldPosition;
/*
* IMPORTANT: You need to obtain your own license key to use Vuforia. The string below with which
* 'parameters.vuforiaLicenseKey' is initialized is for illustration only, and will not function.
* A Vuforia 'Development' license key, can be obtained free of charge from the Vuforia developer
* web site at https://developer.vuforia.com/license-manager.
*
* Vuforia license keys are always 380 characters long, and look as if they contain mostly
* random data. As an example, here is a example of a fragment of a valid key:
* ... yIgIzTqZ4mWjk9wd3cZO9T1axEqzuhxoGlfOOI2dRzKS4T0hQ8kT ...
* Once you've obtained a license key, copy the string from the Vuforia web site
* and paste it in to your code on the next line, between the double quotes.
*/
private static final String VUFORIA_KEY = "AaeF/Hb/////AAABmXyUA/dvl08Hn6O8IUco1axEjiRtYCVASeXGzCnFiMaizR1b3cvD+SXpU1UHHbSpnyem0dMfGb6wce32IWKttH90xMTnLjY4aXBEYscpQbX/FzUi6uf5M+sXDVNMtaVxLDGOb1phJ8tg9/Udb1cxIUCifI+AHmcwj3eknyY1ZapF81n/R0mVSmuyApS2oGQLnETWaWK+kxkx8cGnQ0Nj7a79gStXqm97obOdzptw7PdDNqOfSLVcyKCegEO0zbGoInhRMDm0MPPTxwnBihZsjDuz+I5kDEZJZfBWZ9O1PZMeFmhe6O8oFwE07nFVoclw7j2P6qHbsKTabg3w9w4ZdeTSZI4sV2t9OhbF13e0MWeV"; /**
* {@link #vuforia} is the variable we will use to store our instance of the Vuforia
* localization engine.
*/
private VuforiaLocalizer vuforia;
/**
* {@link #tfod} is the variable we will use to store our instance of the Tensor Flow Object
* Detection engine.
*/
private TFObjectDetector tfod;
@Override
public void runOpMode() {
// The TFObjectDetector uses the camera frames from the VuforiaLocalizer, so we create that
// first.
initVuforia();
limitSwitch = hardwareMap.get(TouchSensor.class, "limitSwitch");
rotationSwitch = hardwareMap.get(TouchSensor.class, "rotationSwitch");
linearServo = hardwareMap.get(Servo.class, "linearServo");
//collectionServo = hardwareMap.get(CRServo.class, "collectionServo");
marker = hardwareMap.get(Servo.class, "markerServo");
tape = hardwareMap.get(CRServo.class, "tapeMeasure");
tapeM = hardwareMap.get(CRServo.class, "tapeServo");
frontLeft = hardwareMap.get(DcMotor.class, "frontLeft");
frontRight = hardwareMap.get(DcMotor.class, "frontRight");
backLeft = hardwareMap.get(DcMotor.class, "backLeft");
backRight = hardwareMap.get(DcMotor.class, "backRight");
linearMotor = hardwareMap.get(DcMotor.class, "linearMotor");
led = hardwareMap.get(Servo.class, "led");
sensorColor = hardwareMap.get(ColorSensor.class, "color");
sensorDistance = hardwareMap.get(DistanceSensor.class, "color");
extension = hardwareMap.get(DcMotor.class, "extension");
rotation = hardwareMap.get(DcMotor.class, "rotation");
mineralServo = hardwareMap.get(Servo.class, "mineralServo");
collectionServo = hardwareMap.get(DcMotor.class, "collectionNew");
deliveryServo = hardwareMap.get(Servo.class, "deliveryServo");
armBump = hardwareMap.get(Servo.class, "armBump");
armBump.setPosition(.45);
led.setPosition(0.7745);
mineralServo.setPosition(0.45);
linearMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
linearMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rotation.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
frontLeft.setDirection(DcMotor.Direction.FORWARD);
frontRight.setDirection(DcMotor.Direction.REVERSE);
backRight.setDirection(DcMotor.Direction.REVERSE);
backLeft.setDirection(DcMotor.Direction.FORWARD);
BNO055IMU.Parameters parameters = new BNO055IMU.Parameters();
parameters.angleUnit = BNO055IMU.AngleUnit.DEGREES;
parameters.accelUnit = BNO055IMU.AccelUnit.METERS_PERSEC_PERSEC;
parameters.calibrationDataFile = "BNO055IMUCalibration.json"; // see the calibration sample opmode
parameters.loggingEnabled = true;
parameters.loggingTag = "IMU";
parameters.accelerationIntegrationAlgorithm = new JustLoggingAccelerationIntegrator();
// Retrieve and initialize the IMU. We expect the IMU to be attached to an I2C port
// on a Core Device Interface Module, configured to be a sensor of type "AdaFruit IMU",
// and named "imu".
imu = hardwareMap.get(BNO055IMU.class, "imu");
imu.initialize(parameters);
DRIVE_BASE_MOTORS[0] = frontLeft;
DRIVE_BASE_MOTORS[1] = frontRight;
DRIVE_BASE_MOTORS[2] = backLeft;
DRIVE_BASE_MOTORS[3] = backRight;
setMotorsModes(DcMotor.RunMode.STOP_AND_RESET_ENCODER, DRIVE_BASE_MOTORS);
setMotorsModes(DcMotor.RunMode.RUN_USING_ENCODER, DRIVE_BASE_MOTORS);
float hsvValues[] = {0F, 0F, 0F};
// values is a reference to the hsvValues array.
final float values[] = hsvValues;
// sometimes it helps to multiply the raw RGB values with a scale factor
// to amplify/attentuate the measured values.
final double SCALE_FACTOR = 255;
// get a reference to the RelativeLayout so we can change the background
// color of the Robot Controller app to match the hue detected by the RGB sensor.
int relativeLayoutId = hardwareMap.appContext.getResources().getIdentifier("RelativeLayout", "id", hardwareMap.appContext.getPackageName());
final View relativeLayout = ((Activity) hardwareMap.appContext).findViewById(relativeLayoutId);
/** Wait for the game to begin */
telemetry.addData(">", "Press Play to start tracking");
telemetry.update();
waitForStart();
telemetry.addData("Status:", "Starting");
telemetry.update();
while (opModeIsActive()) {
if (!landed && !latched) {
runtime.reset();
if (ClassFactory.getInstance().canCreateTFObjectDetector()) {
initTfod();
} else {
telemetry.addData("Sorry!", "This device is not compatible with TFOD");
}
/** Activate Tensor Flow Object Detection. */
/** Activate Tensor Flow Object Detection. */
if (tfod != null) {
tfod.activate();
}
while (opModeIsActive() && !detected) {
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 && !kicked) {
/*If gold is on the left then go forward 2 inches then turn left and go forward 14
inches then turn to face depot and drop marker then face crater on other color side
then drive forward and set power to tape.*/
if (goldMineralX < silverMineral1X && goldMineralX < silverMineral2X) {
direction = -1;
detected = true;
} else if (goldMineralX > silverMineral1X && goldMineralX > silverMineral2X) {
/*If gold is on the right then go forward 2 inches then turn right and go forward 12
inches then turn to face depot and go 12 inches and then drop marker then face crater on
other color side then drive forward and set power to tape.*/
direction = 1;
detected = true;
} else {
/*If gold is in the center then go forward 12 inches and drop marker then go backwards
and face crater on other color side then drive forward and set power to tape.*/
direction = 0;
detected = true;
}
}
} else if (runtime.seconds() >= 5 && !kicked) {
//It has been 20 seconds and we cannot identify the gold
//Assume middle
direction = 0;
detected = true;
}
telemetry.update();
}
}
}
if (tfod != null) {
tfod.shutdown();
}
linearServo.scaleRange(0.0, 1.0);
linearMotor.setTargetPosition(-7122);
linearMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
linearMotor.setPower(1);
if (linearMotor.getCurrentPosition() < -7100) {
landed = true;
telemetry.addData("Status:", "Landed");
telemetry.update();
}
}
if (landed && !latched) {
linearServo.setPosition(1);
// collectionServo.setPower(1);
sleep(2000);
//collectionServo.setPower(0);
latched = true;
telemetry.addData("Status:", "Latched");
telemetry.update();
}
if (landed && latched && !markerDone) {
if (direction==-1) {
kicked = true;
telemetry.addData("Gold Mineral Position", "Left");
encoderDrive(DRIVE_SPEED, 2, 2, 5);
turnToPosition(.5, 25);
encoderDrive(DRIVE_SPEED, 10, 10, 5);
encoderDrive(DRIVE_SPEED, -8, -8, 5);
markerDone=true;
} else if (direction==1) {
/*If gold is on the right then go forward 2 inches then turn right and go forward 12
inches then turn to face depot and go 12 inches and then drop marker then face crater on
other color side then drive forward and set power to tape.*/
kicked = true;
telemetry.addData("Gold Mineral Position", "Right");
encoderDrive(DRIVE_SPEED, 2, 2, 5);
turnToPosition(.5, -25);
encoderDrive(DRIVE_SPEED, 10, 10, 5);
encoderDrive(DRIVE_SPEED, -8, -8, 5);
markerDone=true;
} else {
/*If gold is in the center then go forward 12 inches and drop marker then go backwards
and face crater on other color side then drive forward and set power to tape.*/
kicked = true;
encoderDrive(DRIVE_SPEED, 2, 2, 5);
telemetry.addData("Gold Mineral Position", "Center");
encoderDrive(DRIVE_SPEED, 8, 8, 5);
encoderDrive(DRIVE_SPEED, -8, -8, 5);
markerDone=true;
}
}
if (markerDone && !done1){
armBump.setPosition(0);
rotation.setTargetPosition(1322);
rotation.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rotation.setPower(1);
if(!rotationOut) {
if (rotation.getCurrentPosition() > 300) {
rotation.setPower(0);
extension.setPower(-1);
sleep(1400);
extension.setPower(0);
rotationOut=true;
}
}
if (rotationOut){
rotation.setPower(1);
if (rotation.getCurrentPosition() > 1300) {
rotation.setPower(0);
extension.setPower(-1);
if (limitSwitch.isPressed()) {
extension.setPower(0);
done1 = true;
}
}
}
}
if(done1){
rotation.setTargetPosition(0);
rotation.setPower(-1);
if(rotation.getCurrentPosition() < 1050) {
rotation.setPower(0);
collectionServo.setPower(0);
deliveryServo.setPosition(0.3);
sleep(1000);
collectionServo.setPower(.3);
}
}
}
}
/**
* Initialize the Vuforia localization engine.
*/
private void initVuforia() {
/*
* Configure Vuforia by creating a Parameter object, and passing it to the Vuforia engine.
*/
VuforiaLocalizer.Parameters parameters = new VuforiaLocalizer.Parameters();
parameters.vuforiaLicenseKey = VUFORIA_KEY;
parameters.cameraDirection = CameraDirection.BACK;
// Instantiate the Vuforia engine
vuforia = ClassFactory.getInstance().createVuforia(parameters);
// Loading trackables is not necessary for the Tensor Flow Object Detection engine.
}
/**
* Initialize the Tensor Flow Object Detection engine.
*/
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);
}
public void encoderDrive(double speed,
double leftInches, double rightInches,
double timeoutS) {
int newLeftTarget;
int newRightTarget;
// Ensure that the opmode is still active
if (opModeIsActive()) {
// Determine new target position, and pass to motor controller
newLeftTarget = frontLeft.getCurrentPosition() + (int)(leftInches * COUNTS_PER_INCH);
newRightTarget = frontRight.getCurrentPosition() + (int)(rightInches * COUNTS_PER_INCH);
frontLeft.setTargetPosition(newLeftTarget);
backLeft.setTargetPosition(newLeftTarget);
frontRight.setTargetPosition(newRightTarget);
backRight.setTargetPosition(newRightTarget);
// Turn On RUN_TO_POSITION
frontRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
backRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
frontLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
backLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
// reset the timeout time and start motion.
runtime.reset();
frontRight.setPower(Math.abs(speed));
frontLeft.setPower(Math.abs(speed));
backRight.setPower(Math.abs(speed));
backLeft.setPower(Math.abs(speed));
while (opModeIsActive() &&
(runtime.seconds() < timeoutS) &&
(frontLeft.isBusy() && frontRight.isBusy())) {
// Display it for the driver.
telemetry.addData("Path1", "Running to " + newLeftTarget + newRightTarget);
telemetry.addData("Path2", "Running at " +
frontLeft.getCurrentPosition() +
frontRight.getCurrentPosition());
telemetry.addData("driving",leftInches);
telemetry.update();
}
// Stop all motion;
frontLeft.setPower(0);
frontRight.setPower(0);
backLeft.setPower(0);
backRight.setPower(0);
// Turn off RUN_TO_POSITION
frontLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
frontRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
backLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
backRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
}
public void turn(double power) {
frontLeft.setPower(power);
frontRight.setPower(-power);
backLeft.setPower(power);
backRight.setPower(-power);
}
public void turnToPosition(double turnPower, double desiredHeading) {
setMotorsModes(DcMotor.RunMode.RUN_WITHOUT_ENCODER, DRIVE_BASE_MOTORS);
while (getHeading() - desiredHeading > GYRO_TURN_TOLERANCE_DEGREES && opModeIsActive()) {
telemetry.addData("Heading", getHeading());
telemetry.update();
turn(turnPower);
}
while (getHeading() - desiredHeading < -GYRO_TURN_TOLERANCE_DEGREES && opModeIsActive()) {
telemetry.addData("Heading", getHeading());
telemetry.update();
turn(-turnPower);
}
setMotorsPowers(0, DRIVE_BASE_MOTORS);
//defaults to CW turning
}
public double getHeading() {
updateGyro();
telemetry.addData("getHeading",angles.firstAngle);
telemetry.update();
return angles.firstAngle;
}
void updateGyro() {
angles = imu.getAngularOrientation(AxesReference.INTRINSIC, AxesOrder.ZYX, AngleUnit.DEGREES);
}
public static void setMotorsModes(DcMotor.RunMode runMode, DcMotor[] motors) {
for (DcMotor d : motors)
d.setMode(runMode);
}
protected static void setMotorsPowers(double power, DcMotor[] motors) {
for (DcMotor d : motors)
d.setPower(power);
}
}