-
Notifications
You must be signed in to change notification settings - Fork 0
/
RedAutonomous3.java
821 lines (615 loc) · 28.6 KB
/
RedAutonomous3.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
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
package org.firstinspires.ftc.teamcode;
import com.qualcomm.hardware.bosch.BNO055IMU;
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.Servo;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.util.Range;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
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.opencv.core.Scalar;
import org.openftc.easyopencv.OpenCvCamera;
import org.openftc.easyopencv.OpenCvCameraFactory;
import org.openftc.easyopencv.OpenCvCameraRotation;
/*
import org.opencv.core.Core;
import org.opencv.core.Mat;
import org.opencv.core.Point;
import org.opencv.core.Rect;
import org.opencv.core.Scalar;
import org.opencv.imgproc.Imgproc;
import org.openftc.easyopencv.OpenCvCamera;
import org.openftc.easyopencv.OpenCvCameraFactory;
import org.openftc.easyopencv.OpenCvCameraRotation;
import org.openftc.easyopencv.OpenCvPipeline;
import org.openftc.easyopencv.OpenCvWebcam;
*/
/**
* Created by maryjaneb on 11/13/2016.
*
* nerverest ticks
* 60 1680
* 40 1120
* 20 560
*
* monitor: 640 x 480
*YES
*/
@Autonomous(name= "Red Autonomous Left")
//@Disabled
public class RedAutonomous3<finalPosition> extends LinearOpMode {
private ElapsedTime runtime = new ElapsedTime();
//OpenCvWebcam robotWebcam;
//OpenCV.SkystoneDeterminationPipeline pipeline;
private OpenCvCamera robotWebcam;
private ContourPipeline pipeline;
private double crThreshHigh = 150;
private double crThreshLow = 120;
private double cbThreshHigh = 255;
private double cbThreshLow = 255;
private int minRectangleArea = 2000;
private double leftBarcodeRangeBoundary = 0.3; //i.e 30% of the way across the frame from the left
private double rightBarcodeRangeBoundary = 0.6; //i.e 60% of the way across the frame from the left
private double lowerRuntime = 0;
private double upperRuntime = 0;
// Pink Range Y Cr Cb
public static Scalar scalarLowerYCrCb = new Scalar( 0.0, 0.0, 0.0);
public static Scalar scalarUpperYCrCb = new Scalar(255.0, 120.0, 120.0);
//Motors
//Drivetrain
private DcMotor wheelFrontRight;
private DcMotor wheelFrontLeft;
private DcMotor wheelRearRight;
private DcMotor wheelRearLeft;
//Intake and Turntable
private DcMotor intake;
private DcMotor turntable;
//Servos
private Servo rightLinkage;
private Servo leftLinkage;
private Servo box;
private Servo catapult;
BNO055IMU imu; // Additional Gyro device
Orientation angles;
//Servo init values
private static final double RIGHT_LINKAGE_DOWN = -0.3;
private static final double RIGHT_LINKAGE_UP = 0.3;
private static final double LEFT_LINKAGE_DOWN = -0.3;
private static final double LEFT_LINKAGE_UP = 0.3;
private static final double BOX_OUT = 0.93;
private static final double BOX_IN = 0.52;
private static final double CATAPULT_IN = 0.79;
private static final double CATAPULT_OUT = 0.265;
static final double DRIVE_SPEED = 0.45; // Nominal speed for better accuracy.
static final double TURN_SPEED = 0.40; // Nominal half speed for better accuracy.
static final double HEADING_THRESHOLD = 1; // As tight as we can make it with an integer gyro
static final double P_TURN_COEFF = 0.025; // Larger is more responsive, but also less stable
static final double P_DRIVE_COEFF = 0.007; // Larger is more responsive, but also less stable
@Override
public void runOpMode() throws InterruptedException {
// OpenCV webcam
int cameraMonitorViewId = hardwareMap.appContext.getResources().getIdentifier("cameraMonitorViewId", "id", hardwareMap.appContext.getPackageName());
robotWebcam = OpenCvCameraFactory.getInstance().createWebcam(hardwareMap.get(WebcamName.class, "Webcam 1"), cameraMonitorViewId);
//OpenCV Pipeline
pipeline = new ContourPipeline(0.2, 0.2, 0.2, 0.2);
pipeline.configureScalarLower(scalarLowerYCrCb.val[0], scalarLowerYCrCb.val[1], scalarLowerYCrCb.val[2]);
pipeline.configureScalarUpper(scalarUpperYCrCb.val[0], scalarUpperYCrCb.val[1], scalarUpperYCrCb.val[2]);
robotWebcam.setPipeline(pipeline);
// Webcam Streaming
robotWebcam.openCameraDeviceAsync(new OpenCvCamera.AsyncCameraOpenListener() {
@Override
public void onOpened() {
robotWebcam.startStreaming(640, 480, OpenCvCameraRotation.UPRIGHT);
}
@Override
public void onError(int errorCode) {
}
});
//Drivetrain
wheelFrontRight = hardwareMap.get(DcMotor.class, "wheelFrontRight");
wheelFrontLeft = hardwareMap.get(DcMotor.class, "wheelFrontLeft");
wheelRearRight = hardwareMap.get(DcMotor.class, "wheelRearRight");
wheelRearLeft = hardwareMap.get(DcMotor.class, "wheelRearLeft");
intake = hardwareMap.get(DcMotor.class, "intake");
turntable = hardwareMap.get(DcMotor.class, "turntable");
//Servos
rightLinkage = hardwareMap.get(Servo.class, "rightLinkage");
leftLinkage = hardwareMap.get(Servo.class, "leftLinkage");
box = hardwareMap.get(Servo.class, "box");
catapult = hardwareMap.get(Servo.class, "catapult");
wheelFrontLeft.setDirection(DcMotor.Direction.FORWARD);
wheelRearLeft.setDirection(DcMotor.Direction.FORWARD);
wheelFrontRight.setDirection(DcMotor.Direction.REVERSE);
wheelRearRight.setDirection(DcMotor.Direction.REVERSE);
intake.setDirection(DcMotor.Direction.FORWARD);
turntable.setDirection(DcMotor.Direction.FORWARD);
//Set motor modes
wheelFrontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
wheelFrontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
wheelRearRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
wheelRearLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
intake.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
turntable.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
//Setting motor mode regarding encoders
wheelFrontRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelFrontLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelRearRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelRearLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
intake.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
turntable.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
BNO055IMU.Parameters parameters = new BNO055IMU.Parameters();
parameters.mode = BNO055IMU.SensorMode.IMU;
parameters.angleUnit = BNO055IMU.AngleUnit.DEGREES;
parameters.calibrationDataFile = "BNO055IMUCalibration.json";
imu = hardwareMap.get(BNO055IMU.class, "imu");
imu.initialize(parameters);
//Set servo positions
rightLinkage.setPosition(RIGHT_LINKAGE_DOWN);
leftLinkage.setPosition(LEFT_LINKAGE_DOWN);
box.setPosition(BOX_IN);
catapult.setPosition(CATAPULT_IN);
telemetry.addData("Mode", "working...");
telemetry.addData("imu calib status", imu.getCalibrationStatus().toString());
telemetry.update();
double rectangleArea = pipeline.getRectArea();
double position = pipeline.getRectMidpointX();
telemetry.addData("Mode", "ready");
telemetry.addData("imu calib status", imu.getCalibrationStatus().toString());
telemetry.update();
rectangleArea = pipeline.getRectArea();
position = pipeline.getRectMidpointX();
waitForStart();
runtime.reset();
if (isStopRequested()) return;
while (opModeIsActive()) {
//double rectangleArea = pipeline.getRectArea();
rectangleArea = pipeline.getRectArea();
position = pipeline.getRectMidpointX();
sleep(2000);
//BOTTOM
//LEFT
if (position < 150) {
telemetry.addData("Barcode Position", "left");
telemetry.update();
gyroDrive(0.45, 150, 0);
sleep(150);
gyroTurn(TURN_SPEED, 95);
gyroHold(TURN_SPEED, 95, 0.3);
gyroDrive(0.45, 230, 95);
sleep(150);
duck(-2500, 0.75);
gyroTurn(TURN_SPEED, 130);
gyroHold(TURN_SPEED, 130, 0.3);
gyroDrive(0.4, -770, 130);
sleep(200);
catapult.setPosition(0.21);
sleep(800);
gyroDrive(DRIVE_SPEED, -150, 130);
sleep(200);
box.setPosition(0.95);
sleep(500);
catapult.setPosition(CATAPULT_IN);
sleep(150);
gyroTurn(TURN_SPEED, 130);
gyroHold(TURN_SPEED, 130, 0.3);
gyroDrive(DRIVE_SPEED, 420, 130); //180
sleep(200);
gyroTurn(TURN_SPEED, 30);
gyroHold(TURN_SPEED, 30, 0.5);
gyroDrive(0.45, 680, 30);
sleep(200);
sleep(10000);
//MIDDLE
} else if (position > 150 && position < 400) {
telemetry.addData("Barcode Position", "Center");
telemetry.update();
gyroDrive(0.45, 150, 0);
sleep(150);
gyroTurn(TURN_SPEED, 95);
gyroHold(TURN_SPEED, 95, 0.3);
gyroDrive(DRIVE_SPEED, 230, 95);
sleep(200);
duck(-2500, 0.75);
gyroTurn(TURN_SPEED, 130);
gyroHold(TURN_SPEED, 130, 0.3);
gyroDrive(0.4, -800, 130);
sleep(200);
catapult.setPosition(0.3);
sleep(800);
gyroDrive(DRIVE_SPEED, -120, 130);
sleep(200);
box.setPosition(0.95);
sleep(500);
gyroTurn(TURN_SPEED, 90);
gyroHold(TURN_SPEED, 90, 0.3);
gyroDrive(0.45, 300, 90); //180
sleep(200);
catapult.setPosition(CATAPULT_IN);
sleep(300);
gyroDrive(DRIVE_SPEED, 500, 90); //180
sleep(200);
/*
gyroTurn(TURN_SPEED, 130);
gyroHold(TURN_SPEED, 130, 0.3);
gyroDrive(DRIVE_SPEED, 500, 130); //180
sleep(200);
gyroTurn(TURN_SPEED, 55);
gyroHold(TURN_SPEED, 55, 0.5);
gyroDrive(0.45, 600, 55);
sleep(200);
*/
sleep(10000);
//TOP
} else {
telemetry.addData("Barcode Position", "Right");
telemetry.update();
gyroDrive(0.45, 150, 0);
sleep(150);
gyroTurn(TURN_SPEED, 95);
gyroHold(TURN_SPEED, 95, 0.5);
gyroDrive(0.45, 230, 95);
sleep(200);
duck(-2500, 0.75);
gyroTurn(TURN_SPEED, 130); //152
gyroHold(TURN_SPEED, 130, 0.3);
gyroDrive(0.4, -1000, 130);
sleep(200);
leftLinkage.setPosition(LEFT_LINKAGE_UP);
rightLinkage.setPosition(RIGHT_LINKAGE_UP);
sleep(200);
catapult.setPosition(CATAPULT_OUT);
sleep(800);
box.setPosition(0.95);
sleep(500);
catapult.setPosition(CATAPULT_IN);
sleep(300);
leftLinkage.setPosition(LEFT_LINKAGE_DOWN);
rightLinkage.setPosition(RIGHT_LINKAGE_DOWN);
sleep(100);
gyroTurn(TURN_SPEED, 130);
gyroHold(TURN_SPEED, 130, 0.3);
gyroDrive(DRIVE_SPEED, 700, 130); //180
sleep(200);
gyroTurn(TURN_SPEED, 30);
gyroHold(TURN_SPEED, 30, 0.5);
gyroDrive(0.45, 520, 30);
sleep(200);
sleep(10000);
}
}
}
public void testing(ContourPipeline pipeline){
if(lowerRuntime + 0.05 < getRuntime()){
crThreshLow += -gamepad1.left_stick_y;
cbThreshLow += gamepad1.left_stick_x;
lowerRuntime = getRuntime();
}
if(upperRuntime + 0.05 < getRuntime()){
crThreshHigh += -gamepad1.right_stick_y;
cbThreshHigh += gamepad1.right_stick_x;
upperRuntime = getRuntime();
}
crThreshLow = inValues(crThreshLow, 0, 255);
crThreshHigh = inValues(crThreshHigh, 0, 255);
cbThreshLow = inValues(cbThreshLow, 0, 255);
cbThreshHigh = inValues(cbThreshHigh, 0, 255);
pipeline.configureScalarLower(0.0, crThreshLow, cbThreshLow);
pipeline.configureScalarUpper(255.0, crThreshHigh, cbThreshHigh);
telemetry.addData("lowerCr ", crThreshLow);
telemetry.addData("lowerCb ", cbThreshLow);
telemetry.addData("UpperCr ", crThreshHigh);
telemetry.addData("UpperCb ", cbThreshHigh);
}
public double inValues(double value, double min, double max){
if(value < min){ value = min; }
if(value > max){ value = max; }
return value;
}
public void duck (int distance, double speed){
turntable.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
turntable.setTargetPosition(distance);
turntable.setMode(DcMotor.RunMode.RUN_TO_POSITION);
turntable.setPower(speed);
while (turntable.isBusy() && opModeIsActive()) {
telemetry.addData("Horizontal Slide", turntable.getCurrentPosition());
telemetry.update();
}
turntable.setPower(0);
turntable.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
sleep(500);
}
public void intakeIntake (int distance, double speed){
intake.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
intake.setTargetPosition(distance);
intake.setMode(DcMotor.RunMode.RUN_TO_POSITION);
intake.setPower(speed);
while (intake.isBusy() && opModeIsActive()) {
telemetry.addData("Horizontal Slide", intake.getCurrentPosition());
telemetry.update();
}
intake.setPower(0);
intake.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
sleep(500);
}
public void gyroDrive(double speed,
int distance,
double angle) {
double max;
double error;
double steer;
double leftSpeed;
double rightSpeed;
// Ensure that the opmode is still active
if (opModeIsActive()) {
// Determine new target position, and pass to motor controller
wheelFrontRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelFrontLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelRearRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelRearLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelFrontRight.setTargetPosition(distance);
wheelFrontLeft.setTargetPosition(distance);
wheelRearRight.setTargetPosition(distance);
wheelRearLeft.setTargetPosition(distance);
wheelFrontRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelFrontLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelRearRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelRearLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelFrontRight.setPower(speed);
wheelFrontLeft.setPower(speed);
wheelRearRight.setPower(speed);
wheelRearLeft.setPower(speed);
// keep looping while we are still active, and BOTH motors are running.
while (opModeIsActive() &&
(wheelFrontRight.isBusy() && wheelFrontLeft.isBusy() && wheelRearRight.isBusy() && wheelRearLeft.isBusy())) {
// adjust relative speed based on heading error.
error = getError(angle);
steer = getSteer(error, P_DRIVE_COEFF);
// if driving in reverse, the motor correction also needs to be reversed
if (distance < 0)
steer *= -1.0;
leftSpeed = speed - steer;
rightSpeed = speed + steer;
// Normalize speeds if either one exceeds +/- 1.0;
max = Math.max(Math.abs(leftSpeed), Math.abs(rightSpeed));
if (max > 1.0) {
leftSpeed /= max;
rightSpeed /= max;
}
wheelFrontLeft.setPower(leftSpeed);
wheelRearLeft.setPower(leftSpeed);
wheelFrontRight.setPower(rightSpeed);
wheelRearRight.setPower(rightSpeed);
// Display drive status for the driver.
telemetry.addData("Err/St", "%5.1f/%5.1f", error, steer);
telemetry.addData("Speed", "%5.2f:%5.2f", leftSpeed, rightSpeed);
telemetry.update();
}
// Stop all motion;
wheelFrontRight.setPower(0);
wheelRearRight.setPower(0);
wheelFrontLeft.setPower(0);
wheelRearLeft.setPower(0);
// Turn off RUN_TO_POSITION
wheelFrontRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelRearRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelFrontLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelRearLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
}
public void gyroIntakeDrive(double speed,
int distance,
double angle, int intakeDistance, double intakeSpeed) {
double max;
double error;
double steer;
double leftSpeed;
double rightSpeed;
// Ensure that the opmode is still active
if (opModeIsActive()) {
// Determine new target position, and pass to motor controller
wheelFrontRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelFrontLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelRearRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelRearLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
intake.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelFrontRight.setTargetPosition(distance);
wheelFrontLeft.setTargetPosition(distance);
wheelRearRight.setTargetPosition(distance);
wheelRearLeft.setTargetPosition(distance);
intake.setTargetPosition(intakeDistance);
wheelFrontRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelFrontLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelRearRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelRearLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
intake.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelFrontRight.setPower(speed);
wheelFrontLeft.setPower(speed);
wheelRearRight.setPower(speed);
wheelRearLeft.setPower(speed);
intake.setPower(intakeSpeed);
// keep looping while we are still active, and BOTH motors are running.
while (opModeIsActive() &&
(wheelFrontRight.isBusy() && wheelFrontLeft.isBusy() && wheelRearRight.isBusy() && wheelRearLeft.isBusy())) {
// adjust relative speed based on heading error.
error = getError(angle);
steer = getSteer(error, P_DRIVE_COEFF);
// if driving in reverse, the motor correction also needs to be reversed
if (distance < 0)
steer *= -1.0;
leftSpeed = speed - steer;
rightSpeed = speed + steer;
// Normalize speeds if either one exceeds +/- 1.0;
max = Math.max(Math.abs(leftSpeed), Math.abs(rightSpeed));
if (max > 1.0) {
leftSpeed /= max;
rightSpeed /= max;
}
wheelFrontLeft.setPower(leftSpeed);
wheelRearLeft.setPower(leftSpeed);
wheelFrontRight.setPower(rightSpeed);
wheelRearRight.setPower(rightSpeed);
// Display drive status for the driver.
telemetry.addData("Err/St", "%5.1f/%5.1f", error, steer);
telemetry.addData("Speed", "%5.2f:%5.2f", leftSpeed, rightSpeed);
telemetry.update();
}
// Stop all motion;
wheelFrontRight.setPower(0);
wheelRearRight.setPower(0);
wheelFrontLeft.setPower(0);
wheelRearLeft.setPower(0);
intake.setPower(0);
// Turn off RUN_TO_POSITION
wheelFrontRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelRearRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelFrontLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelRearLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
intake.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
}
/**
* Method to spin on central axis to point in a new direction.
* Move will stop if either of these conditions occur:
* 1) Move gets to the heading (angle)
* 2) Driver stops the opmode running.
*
* @param speed Desired speed of turn.
* @param angle Absolute Angle (in Degrees) relative to last gyro reset.
* 0 = fwd. +ve is CCW from fwd. -ve is CW from forward.
* If a relative angle is required, add/subtract from current heading.
*/
public void gyroTurn(double speed, double angle) {
// keep looping while we are still active, and not on heading.
while (opModeIsActive() && !onHeading(speed, angle, P_TURN_COEFF)) {
// Update telemetry & Allow time for other processes to run.
telemetry.update();
}
}
public void Drive (int frontRightDistance, int frontLeftDistance, int rearRightDistance, int rearLeftDistance, double speed){
wheelFrontRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelFrontLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelRearRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelRearLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
wheelFrontRight.setTargetPosition(frontRightDistance);
wheelFrontLeft.setTargetPosition(frontLeftDistance);
wheelRearRight.setTargetPosition(rearRightDistance);
wheelRearLeft.setTargetPosition(rearLeftDistance);
wheelFrontRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelFrontLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelRearRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelRearLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
wheelFrontRight.setPower(speed);
wheelFrontLeft.setPower(speed);
wheelRearRight.setPower(speed);
wheelRearLeft.setPower(speed);
while (wheelFrontRight.isBusy() && wheelFrontLeft.isBusy() && wheelRearRight.isBusy() && wheelRearLeft.isBusy() && opModeIsActive()) {
telemetry.addData("FrontRightPosition", wheelFrontRight.getCurrentPosition());
telemetry.addData("FrontLeftPosition", wheelFrontLeft.getCurrentPosition());
telemetry.update();
}
wheelFrontRight.setPower(0);
wheelFrontLeft.setPower(0);
wheelRearRight.setPower(0);
wheelRearLeft.setPower(0);
wheelFrontRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelFrontLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelRearRight.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
wheelRearLeft.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
sleep(500);
}
/**
* Method to obtain & hold a heading for a finite amount of time
* Move will stop once the requested time has elapsed
*
* @param speed Desired speed of turn.
* @param angle Absolute Angle (in Degrees) relative to last gyro reset.
* 0 = fwd. +ve is CCW from fwd. -ve is CW from forward.
* If a relative angle is required, add/subtract from current heading.
* @param holdTime Length of time (in seconds) to hold the specified heading.
*/
public void gyroHold(double speed, double angle, double holdTime) {
ElapsedTime holdTimer = new ElapsedTime();
// keep looping while we have time remaining.
holdTimer.reset();
while (opModeIsActive() && (holdTimer.time() < holdTime)) {
// Update telemetry & Allow time for other processes to run.
onHeading(speed, angle, P_TURN_COEFF);
telemetry.update();
}
// Stop all motion;
wheelFrontRight.setPower(0);
wheelRearRight.setPower(0);
wheelFrontLeft.setPower(0);
wheelRearLeft.setPower(0);
}
/**
* Perform one cycle of closed loop heading control.
*
* @param speed Desired speed of turn.
* @param angle Absolute Angle (in Degrees) relative to last gyro reset.
* 0 = fwd. +ve is CCW from fwd. -ve is CW from forward.
* If a relative angle is required, add/subtract from current heading.
* @param PCoeff Proportional Gain coefficient
* @return
*/
boolean onHeading(double speed, double angle, double PCoeff) {
double error;
double steer;
boolean onTarget = false;
double leftSpeed;
double rightSpeed;
// determine turn power based on +/- error
error = getError(angle);
if (Math.abs(error) <= HEADING_THRESHOLD) {
steer = 0.0;
leftSpeed = 0.0;
rightSpeed = 0.0;
onTarget = true;
} else {
steer = getSteer(error, PCoeff);
rightSpeed = speed * steer;
leftSpeed = -rightSpeed;
}
// Send desired speeds to motors.
wheelFrontLeft.setPower(leftSpeed);
wheelRearLeft.setPower(leftSpeed);
wheelFrontRight.setPower(rightSpeed);
wheelRearRight.setPower(rightSpeed);
// Display it for the driver.
telemetry.addData("Target", "%5.2f", angle);
telemetry.addData("Error", error);
telemetry.addData("Speed.", "%5.2f:%5.2f", leftSpeed, rightSpeed);
return onTarget;
}
/**
* getError determines the error between the target angle and the robot's current heading
*
* @param targetAngle Desired angle (relative to global reference established at last Gyro Reset).
* @return error angle: Degrees in the range +/- 180. Centered on the robot's frame of reference
* +ve error means the robot should turn LEFT (CCW) to reduce error.
*/
public double getError(double targetAngle) {
double robotError;
angles = imu.getAngularOrientation(AxesReference.INTRINSIC, AxesOrder.ZYX, AngleUnit.DEGREES);
this.imu.getPosition();
// calculate error in -179 to +180 range (
robotError = angles.firstAngle - targetAngle;
while (robotError > 180) robotError -= 360;
while (robotError <= -180) robotError += 360;
return robotError;
}
/**
* returns desired steering force. +/- 1 range. +ve = steer left
*
* @param error Error angle in robot relative degrees
* @param PCoeff Proportional Gain Coefficient
* @return
*/
public double getSteer(double error, double PCoeff) {
return Range.clip(error * PCoeff, -1, 1);
}
}