Skip to content

Commit

Permalink
working code from trinity league meet FIRST-Tech-Challenge#4
Browse files Browse the repository at this point in the history
-Will Cardo
  • Loading branch information
Will committed Dec 17, 2023
1 parent 260222e commit 2f6efb2
Show file tree
Hide file tree
Showing 5 changed files with 75 additions and 63 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -108,8 +108,8 @@ public class BlueNotBackStage50pt extends LinearOpMode {
private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera
private TfodProcessor tfod;
private static final String[] LABELS = {
"Blue_Bolt",
"Red_Bolt",
"Blue",
"Red",
};
/**
* The variable to store our instance of the AprilTag processor.
Expand Down Expand Up @@ -292,7 +292,7 @@ public void runOpMode() {
driveStraight(DRIVE_SPEED, -5.0, 0.0);

StrafeRight(DRIVE_SPEED, 20.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
holdHeading(TURN_SPEED, 0.0, 4.5);

driveStraight(DRIVE_SPEED, 31.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
Expand All @@ -319,7 +319,7 @@ else if (TeamElementPosition == 3) {
turnToHeading( TURN_SPEED, 0.0);
waittimer(.125);
StrafeRight(DRIVE_SPEED, 20.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
holdHeading(TURN_SPEED, 0.0, 4.5);

driveStraight(DRIVE_SPEED, 44.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
Expand All @@ -346,7 +346,7 @@ else if (TeamElementPosition == 3) {
waittimer(.125);

StrafeRight(DRIVE_SPEED, 20.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
holdHeading(TURN_SPEED, 0.0, 3.5);

driveStraight(DRIVE_SPEED, 40.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
Expand Down Expand Up @@ -572,6 +572,7 @@ public void StrafeRight(double maxDriveSpeed,
leftBackDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rightBackDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
}

}

public void StrafeLeft(double maxDriveSpeed,
Expand Down Expand Up @@ -629,6 +630,7 @@ public void StrafeLeft(double maxDriveSpeed,
rightBackDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);

}

}

public void moveRobot2AprilTag(double x, double y, double yaw) {
Expand Down Expand Up @@ -990,7 +992,7 @@ private void initDoubleVision() {
tfod = new TfodProcessor.Builder()
// Use setModelAssetName() if the TF Model is built in as an asset.
// Use setModelFileName() if you have downloaded a custom team model to the Robot Controller.
.setModelAssetName("Prop_Model.tflite")
.setModelAssetName("Correct_1.tflite")
//.setModelFileName("Prop_Model")

.setModelLabels(LABELS)
Expand Down Expand Up @@ -1138,9 +1140,9 @@ private void telemetryTfod() {
telemetry.addData("- Position", "%.0f / %.0f", x, y);
telemetry.addData("- Size", "%.0f x %.0f", recognition.getWidth(), recognition.getHeight());
telemetry.addData(">", "Robot Heading = %4.0f", getHeading());
if (recognition.getLabel().equals("Blue_Bolt")) {
if (recognition.getLabel().equals("Blue")) {
isPropDetected = true;
telemetry.addData("Object Detected", "Bolt Prop");
telemetry.addData("Object Detected", "Prop");
if (Double.parseDouble(JavaUtil.formatNumber(recognition.getLeft(), 0)) > 300) {
TeamElementPosition = 3;
DESIRED_TAG_ID = 3;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,8 +113,8 @@ public class LeftAutoBackstage extends LinearOpMode {
private TfodProcessor tfod;

private static final String[] LABELS = {
"Blue_Bolt",
"Red_Bolt",
"Blue",
"Red",
};

private boolean isPropDetected = false;
Expand Down Expand Up @@ -837,7 +837,7 @@ private void initDoubleVision() {
tfod = new TfodProcessor.Builder()
// Use setModelAssetName() if the TF Model is built in as an asset.
// Use setModelFileName() if you have downloaded a custom team model to the Robot Controller.
.setModelAssetName("Prop_Model.tflite")
.setModelAssetName("Correct_1.tflite")
//.setModelFileName("Prop_Model")

.setModelLabels(LABELS)
Expand Down Expand Up @@ -900,9 +900,9 @@ private void telemetryTfod() {
telemetry.addData("- Position", "%.0f / %.0f", x, y);
telemetry.addData("- Size", "%.0f x %.0f", recognition.getWidth(), recognition.getHeight());
telemetry.addData(">", "Robot Heading = %4.0f", getHeading());
if (recognition.getLabel().equals("Blue_Bolt")) {
if (recognition.getLabel().equals("Blue")) {
isPropDetected = true;
telemetry.addData("Object Detected", "Bolt Prop");
telemetry.addData("Object Detected", "Prop");
if (Double.parseDouble(JavaUtil.formatNumber(recognition.getLeft(), 0)) > 150) {
TeamElementPosition = 2;
telemetry.addData("Spike Position", "Spike 2");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -108,8 +108,8 @@ public class RedNotBackStage50pt extends LinearOpMode {
private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera
private TfodProcessor tfod;
private static final String[] LABELS = {
"Blue_Bolt",
"Red_Bolt",
"Blue",
"Red",
};
/**
* The variable to store our instance of the AprilTag processor.
Expand Down Expand Up @@ -263,7 +263,6 @@ public void runOpMode() {
telemetryTfod();
telemetry.update();
sleep(20);

}
ElapsedTime holdtimer = new ElapsedTime();
holdtimer.reset();
Expand All @@ -288,11 +287,13 @@ public void runOpMode() {
// if position == 2 pixel goes to center spike
IntakeLinkage.setPosition(0.2);
if (TeamElementPosition == 2) {

//MIDDLE
driveStraight(DRIVE_SPEED, 28.0, 0.0);
driveStraight(DRIVE_SPEED, -5.0, 0.0);

StrafeLeft(DRIVE_SPEED, 20.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
holdHeading(TURN_SPEED, 0.0, 4);

driveStraight(DRIVE_SPEED, 31.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
Expand All @@ -309,7 +310,10 @@ public void runOpMode() {
driveStraight(.15, 7.0, -90.0);
}
else if (TeamElementPosition == 3) {
driveStraight(DRIVE_SPEED, 33.0, -40.0);

//RIGHT
driveStraight(DRIVE_SPEED, 5.0, 0.0);
driveStraight(DRIVE_SPEED, 28.0, -40.0);
turnToHeading( TURN_SPEED, -40.0);
waittimer(.125);

Expand All @@ -319,14 +323,14 @@ else if (TeamElementPosition == 3) {
StrafeLeft(DRIVE_SPEED, 20.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);

driveStraight(DRIVE_SPEED, 44.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
driveStraight(DRIVE_SPEED, 40.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 3.5);

turnToHeading(TURN_SPEED, -90.0 );
driveStraight(DRIVE_SPEED, 109.0, -90.0);
driveStraight(DRIVE_SPEED, 100.0, -90.0);


StrafeRight(DRIVE_SPEED, 34.0, -90.0);
StrafeRight(DRIVE_SPEED, 38.0, -90.0);

leftFrontDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rightFrontDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
Expand All @@ -336,6 +340,7 @@ else if (TeamElementPosition == 3) {
}
else {

//LEFT
driveStraight(DRIVE_SPEED, 5.0,25.0);
driveStraight(DRIVE_SPEED, 20.0, 25.0);
turnToHeading( TURN_SPEED, 25.0);
Expand All @@ -345,17 +350,16 @@ else if (TeamElementPosition == 3) {
turnToHeading( TURN_SPEED, 0.0);
waittimer(.125);

StrafeLeft(DRIVE_SPEED, 15.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);
StrafeLeft(DRIVE_SPEED, 17.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 4.5);

driveStraight(DRIVE_SPEED, 43.0, 0.0);
driveStraight(DRIVE_SPEED, 46.0, 0.0);
holdHeading(TURN_SPEED, 0.0, 0.5);


turnToHeading(TURN_SPEED, -90.0 );
driveStraight(DRIVE_SPEED, 108.0, -90.0);

StrafeRight(DRIVE_SPEED, 20.0, -90.0);
StrafeRight(DRIVE_SPEED, 24.0, -90.0);

leftFrontDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rightFrontDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
Expand All @@ -365,7 +369,6 @@ else if (TeamElementPosition == 3) {
}



/*
while (holdtimer.time() < 25 && rangeError > 2.7) {
Expand Down Expand Up @@ -456,7 +459,8 @@ else if (TeamElementPosition == 3) {
Wrist.setPosition(0.1);


/* driveStraight(DRIVE_SPEED, 24.0, 0.0); // Drive Forward 24"
/*
driveStraight(DRIVE_SPEED, 24.0, 0.0); // Drive Forward 24"
turnToHeading( TURN_SPEED, -45.0); // Turn CW to -45 Degrees
holdHeading( TURN_SPEED, -45.0, 0.5); // Hold -45 Deg heading for a 1/2 second
Expand Down Expand Up @@ -989,7 +993,7 @@ private void initDoubleVision() {
tfod = new TfodProcessor.Builder()
// Use setModelAssetName() if the TF Model is built in as an asset.
// Use setModelFileName() if you have downloaded a custom team model to the Robot Controller.
.setModelAssetName("Prop_Model.tflite")
.setModelAssetName("Correct_1.tflite")
//.setModelFileName("Prop_Model")

.setModelLabels(LABELS)
Expand Down Expand Up @@ -1137,9 +1141,9 @@ private void telemetryTfod() {
telemetry.addData("- Position", "%.0f / %.0f", x, y);
telemetry.addData("- Size", "%.0f x %.0f", recognition.getWidth(), recognition.getHeight());
telemetry.addData(">", "Robot Heading = %4.0f", getHeading());
if (recognition.getLabel().equals("Red_Bolt")) {
if (recognition.getLabel().equals("Red")) {
isPropDetected = true;
telemetry.addData("Object Detected", "Bolt Prop");
telemetry.addData("Object Detected", "Prop");
if (Double.parseDouble(JavaUtil.formatNumber(recognition.getLeft(), 0)) > 200) {
TeamElementPosition = 2;
telemetry.addData("Spike Position", "Spike 2");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,8 +113,8 @@ public class RightAutoBackstage extends LinearOpMode {
private TfodProcessor tfod;

private static final String[] LABELS = {
"Blue_Bolt",
"Red_Bolt",
"Blue",
"Red",
};

private boolean isPropDetected = false;
Expand Down Expand Up @@ -839,7 +839,7 @@ private void initDoubleVision() {
tfod = new TfodProcessor.Builder()
// Use setModelAssetName() if the TF Model is built in as an asset.
// Use setModelFileName() if you have downloaded a custom team model to the Robot Controller.
.setModelAssetName("Prop_Model.tflite")
.setModelAssetName("Correct_1.tflite")
//.setModelFileName("Prop_Model")

.setModelLabels(LABELS)
Expand Down Expand Up @@ -902,9 +902,9 @@ private void telemetryTfod() {
telemetry.addData("- Position", "%.0f / %.0f", x, y);
telemetry.addData("- Size", "%.0f x %.0f", recognition.getWidth(), recognition.getHeight());
telemetry.addData(">", "Robot Heading = %4.0f", getHeading());
if (recognition.getLabel().equals("Red_Bolt")) {
if (recognition.getLabel().equals("Red")) {
isPropDetected = true;
telemetry.addData("Object Detected", "Bolt Prop");
telemetry.addData("Object Detected", "Prop");
if (Double.parseDouble(JavaUtil.formatNumber(recognition.getLeft(), 0)) > 200) {
TeamElementPosition = 3;
telemetry.addData("Spike Position", "Spike 3");
Expand Down
Loading

0 comments on commit 2f6efb2

Please sign in to comment.