Compare commits

...

2 commits

Author SHA1 Message Date
Yash Karandikar 7bb091571c o, ante e tenpo pi tawa 2022-11-16 17:55:18 -06:00
Yash Karandikar 88138e43ff tawa wawa ilo li pali ala tan seme? 2022-11-16 16:50:43 -06:00
2 changed files with 12 additions and 7 deletions

View file

@ -56,7 +56,7 @@ public class AutoCameraRight extends LinearOpMode {
ArrayList<AprilTagDetection> currentDetections = aprilTagDetectionPipeline.getLatestDetections();
if (currentDetections.size() != 0) {
detected_id = currentDetections.get(currentDetections.size() - 1).id;
detected_id = currentDetections.get(0).id;
telemetry.addData("Tag found", String.valueOf(detected_id));
telemetry.update();
}
@ -64,23 +64,23 @@ public class AutoCameraRight extends LinearOpMode {
switch (detected_id) {
case 1:
movementAPI.move(90, 0.7);
api.pause(1);
api.pause(0.85);
movementAPI.move(0, 0.5);
api.pause(0.7);
api.pause(1.4);
break;
case 2:
movementAPI.move(0, 0.5);
api.pause(0.7);
api.pause(1.4);
break;
case 3:
movementAPI.move(-90, 0.7);
api.pause(1);
api.pause(1.5);
movementAPI.move(0, 0.5);
api.pause(0.7);
api.pause(1.4);
break;
default:
movementAPI.move(90, 0.5);
api.pause(0.75);
api.pause(1.5);
break;
}

View file

@ -30,6 +30,11 @@ public class MovementAPI {
bl = api.opMode.hardwareMap.get(DcMotor.class, "rearLeft");
br = api.opMode.hardwareMap.get(DcMotor.class, "rearRight");
fl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
fr.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
bl.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
br.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
fl.setDirection(DcMotor.Direction.REVERSE);
bl.setDirection(DcMotor.Direction.REVERSE);
fr.setDirection(DcMotor.Direction.FORWARD);