added a break and implemented custom image model

This commit is contained in:
SpencerPiha
2022-12-17 11:26:33 -06:00
parent 87ca79e7b3
commit 11cf076fc1
6 changed files with 19 additions and 13 deletions

View File

@@ -7,6 +7,7 @@ import org.timecrafters.Autonomous.States.CollectorDistanceState;
import org.timecrafters.Autonomous.States.CollectorState;
import org.timecrafters.Autonomous.States.ConeIdentification;
import org.timecrafters.Autonomous.States.DriverState;
import org.timecrafters.Autonomous.States.DriverStateWithOdometer;
import org.timecrafters.Autonomous.States.ServoCameraRotate;
import org.timecrafters.TeleOp.states.PhoenixBot1;
@@ -26,7 +27,7 @@ public class RightFourConeAutonomousEngine extends CyberarmEngine {
// 3 Rotate Camera up, out of the way so it doesn't crash into stuff
addState(new ServoCameraRotate(robot, "RightFourCone", "03-0"));
// 4 Drive to the tall Pole (not all the way) while raising upper arm, this will be parallel
addState(new DriverState(robot, "RightFourCone", "04-0"));
addState(new DriverStateWithOdometer(robot, "RightFourCone", "04-0"));
// 5 Turn Towards and look for junction with sensor
// 6 Raise lower arm while slowly driving at the junction

View File

@@ -49,12 +49,12 @@ public class ConeIdentification extends CyberarmState {
engine.telemetry.addData("- Position (Row/Col)","%.0f / %.0f", row, col);
engine.telemetry.addData("- Size (Width/Height)","%.0f / %.0f", width, height);
if (recognition.getLabel().equals("2 Bulb")) {
engine.telemetry.addData("2 Bulb", engine.blackboard.put("parkPlace", "2"));
} else if (recognition.getLabel().equals("3 Panel")) {
engine.telemetry.addData("3 Panel",engine.blackboard.put("parkPlace", "3"));
if (recognition.getLabel().equals("#2")) {
engine.telemetry.addData("#2", engine.blackboard.put("parkPlace", "2"));
} else if (recognition.getLabel().equals("#3")) {
engine.telemetry.addData("#3",engine.blackboard.put("parkPlace", "3"));
} else {
engine.telemetry.addData("1 Bolt", engine.blackboard.put("parkPlace", "1"));
engine.telemetry.addData("#1", engine.blackboard.put("parkPlace", "1"));
}
}
}

View File

@@ -75,7 +75,7 @@ public class DriverState extends CyberarmState {
robot.backRightDrive.setPower(0);
robot.frontLeftDrive.setPower(0);
robot.frontRightDrive.setPower(0);
setHasFinished(true);
// setHasFinished(true);
}
@@ -87,6 +87,7 @@ public class DriverState extends CyberarmState {
engine.telemetry.addData("frontLeftDrive", robot.frontLeftDrive.getCurrentPosition());
engine.telemetry.addData("BackRightDrive", robot.backRightDrive.getCurrentPosition());
engine.telemetry.addData("BackLeftDrive", robot.backLeftDrive.getCurrentPosition());
engine.telemetry.addData("leftOdometerDrive", robot.OdometerEncoder.getCurrentPosition());
engine.telemetry.addData("drivePower", drivePower);
engine.telemetry.addData("targetDrivePower", targetDrivePower);

View File

@@ -76,7 +76,7 @@ public class DriverStateWithOdometer extends CyberarmState {
robot.backRightDrive.setPower(0);
robot.frontLeftDrive.setPower(0);
robot.frontRightDrive.setPower(0);
setHasFinished(true);
// setHasFinished(true);
}

View File

@@ -20,14 +20,14 @@ import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfig
public class PhoenixBot1 {
// private static final String TFOD_MODEL_ASSET = "22-23_PowerPlay_Colors.tflite";
private static final String TFOD_MODEL_ASSET = "PowerPlay.tflite";
private static final String TFOD_MODEL_ASSET = "AprilTagsV1.tflite";
private static final String[] LABELS = {
"1 Bolt",
"2 Bulb",
"3 Panel"
"#1",
"#2",
"#3"
};
private static final String VUFORIA_KEY =
@@ -112,24 +112,28 @@ public class PhoenixBot1 {
frontLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
frontLeftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
frontLeftDrive.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
frontLeftDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
frontRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
frontRightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
frontRightDrive.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
frontRightDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
backLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
backLeftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
backLeftDrive.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
backLeftDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
backRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
backRightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
backRightDrive.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
backRightDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
// Dead Wheel encoder for driving
OdometerEncoder = engine.hardwareMap.dcMotor.get("odometer encoder");
OdometerEncoder.setDirection(DcMotorSimple.Direction.FORWARD);
OdometerEncoder.setDirection(DcMotorSimple.Direction.REVERSE);
OdometerEncoder.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
OdometerEncoder.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);

Binary file not shown.