app
is
- * passed, post two intermediate states of the image from during processing
- * to the gui
- *
- * @param frame
- * The image to process
- *
- * @param app
- * (Optional: pass null
to ignore) The Main
to
- * post intermediate states of the processed image to.
- *
- * @return Three doubles, in a double[3]
, ordered as such:
- * index 0
: The x-offset, in pixels, of the center of the
- * bounding rectangle of the found goal from the center of the image
index 1
: The y-offset, in pixels, of the center of the
- * bounding rectangle of the found goal form the center of the image
index 2
: The angle at which the bounding rectangle is
- * tilted
iters
frames read from
- * cs
- *
- * @param cs
- * The CaptureSource from which to read frames
- * @param iters
- * The number of frames to read from cs
and to process and time
- * @return The average time taken by hsvThresholding
to process
- * one of the frames
- */
- public double testProcessingTime(CaptureSource cs, int iters) {
- int total = 0;
- double[] vec;
- for (int i = 0; i < iters; i++) {
- long start = System.currentTimeMillis();
- vec = processImage();
- total += (int) (System.currentTimeMillis() - start);
- }
- return total / (double) iters;
- }
-
- // Calculation methods:
- public static double frameXPxToDegrees(double px) {
- return CAMERA_VIEWING_ANGLE_X * px / CAMERA_FRAME_PX_WIDTH;
- }
-
- public static double frameYPxToDegrees(double dy) {
- return dy / CAMERA_FRAME_PX_HEIGHT * CAMERA_VIEWING_ANGLE_Y;
- }
-
- public static double yInFrameToDegreesFromHorizon(double height) {
- return CAMERA_TILT_ANGLE - frameYPxToDegrees(height);
- }
-
- public static double findCameraDistanceToGoal(double frameY) {
- double angle = yInFrameToDegreesFromHorizon(frameY);
- return (HIGH_GOAL_HEIGHT - CAMERA_HEIGHT_FROM_GROUND) / Math.tan(Math.toRadians(angle));
- }
-
- public static double findBotDistanceToGoal(double frameY) {
- return findCameraDistanceToGoal(frameY) - CAMERA_DIST_TO_BOT_FRONT;
- }
-
- public static double findDistanceToGoal(double[] vec) {
- if (vec == null) {
- return -1;
- }
- return findCameraDistanceToGoal(vec[1]);
- }
-
- public static class Report {
- double[] reading;
- double goalDegsY;
- double goalDegsX;
- double inchesAway;
- double degsUp;
-
- public Report(double[] visionReading) {
- if (visionReading == null) {
- return;
- }
- reading = visionReading;
- goalDegsX = frameXPxToDegrees(reading[0]);
- goalDegsY = frameXPxToDegrees(reading[1]);
- degsUp = yInFrameToDegreesFromHorizon(reading[1]);
- inchesAway = findCameraDistanceToGoal(reading[1]);
- // let null pointer exception occur if data is null
- }
-
- public String formattedReading() {
- if (reading == null) {
- return "null";
- }
- return "[" + fmt(reading[0]) + ", " + fmt(reading[1]) + ", " + fmt(reading[2]) + "]";
- }
-
- private static final String blank = "------------------------------------";
-
- public String toString() {
- boolean none = false;
- if (reading == null) {
- // return "| CV read no goals in frame\n" + blank + blank +
- // blank + blank + blank;
- none = true;
- }
- return "| CV Read: " + Arrays.toString(reading) + "\n" + "| Data: "
- + (none ? blank : formattedReading()) + "\n" + "| Angle X: "
- + (none ? blank : (fmt(goalDegsX) + "\u00B0 right from center")) + "\n" + "| Angle Y: "
- + (none ? blank : (fmt(goalDegsY) + "\u00B0 down from center")) + "\n" + "| Elevation: "
- + (none ? blank : (fmt(degsUp) + "\u00B0 up from horizon")) + "\n" + "| Cam Dist: "
- + (none ? blank : fmtDist(inchesAway)) + "\n" + "| (Time: " + System.currentTimeMillis() + ")\n";
- }
-
- private static String fmtDist(double d) {
- int inches = (int) d;
- return (inches / 12) + " ft, " + (inches % 12) + " in";
- }
-
- private static String fmt(double d) {
- return String.format("%.0f", d);
- }
- }
-
- public static void main(String[] args) {
- System.out.println("Running test: read from frame and determine angle to rotate");
- StuyVision sv = new StuyVision();
- double[] reading = sv.processImage();
- System.out.println(new Report(reading));
- }
-
- public void run(Main app, Mat frame) {
- app.postImage(frame, "Video", this);
- double[] reading = hsvThresholding(frame, app);
- System.out.println("\n\n" + new Report(reading));
- }
-}
diff --git a/src/edu/stuy/robot/cv/gui/ControlsController.java b/src/edu/stuy/robot/cv/gui/ControlsController.java
deleted file mode 100644
index d699a26..0000000
--- a/src/edu/stuy/robot/cv/gui/ControlsController.java
+++ /dev/null
@@ -1,170 +0,0 @@
-package edu.stuy.robot.cv.gui;
-
-import java.lang.reflect.Field;
-import java.text.DecimalFormat;
-import java.util.ArrayList;
-
-import edu.stuy.robot.cv.util.DebugPrinter;
-import javafx.application.Platform;
-import javafx.beans.value.ChangeListener;
-import javafx.beans.value.ObservableValue;
-import javafx.fxml.FXML;
-import javafx.geometry.Pos;
-import javafx.scene.Node;
-import javafx.scene.control.Button;
-import javafx.scene.control.CheckBox;
-import javafx.scene.control.Slider;
-import javafx.scene.layout.FlowPane;
-import javafx.scene.layout.VBox;
-import javafx.scene.text.Text;
-
-public class ControlsController {
-
- @FXML
- FlowPane flowPane;
- @FXML
- VBox controlsContainer;
- @FXML
- Button restoreDefaults;
-
- final DecimalFormat formatter = new DecimalFormat("#.###");
-
- public void setup(VisionModule module) {
- ArrayListIf you change your main robot class, change the parameter type.
+ */
+ public static void main(String... args) {
+ RobotBase.startRobot(Robot::new);
+ }
+}
diff --git a/src/edu/stuy/robot/OI.java b/src/main/java/edu/stuy/robot/OI.java
similarity index 82%
rename from src/edu/stuy/robot/OI.java
rename to src/main/java/edu/stuy/robot/OI.java
index b571536..4559b18 100644
--- a/src/edu/stuy/robot/OI.java
+++ b/src/main/java/edu/stuy/robot/OI.java
@@ -15,10 +15,10 @@
import edu.stuy.robot.commands.HoodUpCommand;
import edu.stuy.robot.commands.HopperRunCommand;
import edu.stuy.robot.commands.JionDriveCommand;
-import edu.stuy.robot.commands.RotateToAimCommand;
-import edu.stuy.robot.commands.RotateToAimMultiCommand;
+//import edu.stuy.robot.commands.RotateToAimCommand;
+//import edu.stuy.robot.commands.RotateToAimMultiCommand;
import edu.stuy.robot.commands.RunInLowGearCommand;
-import edu.stuy.robot.commands.SetupForShotCommand;
+//import edu.stuy.robot.commands.SetupForShotCommand;
import edu.stuy.robot.commands.ShooterHopperBackwardsCommand;
import edu.stuy.robot.commands.ShooterHopperStopCommand;
import edu.stuy.robot.commands.ShooterSetLayupCommand;
@@ -77,20 +77,20 @@ public OI() {
driverGamepad.getLeftBumper().whenPressed(new FlashlightOnCommand());
driverGamepad.getLeftBumper().whenReleased(new FlashlightOffCommand());
- // CV controls
- GyroRotationalCommand singleRotationTrigger = new RotateToAimCommand(false, 1.7);
- singleRotationTrigger.setUseSignalLights(true);
- driverGamepad.getRightTrigger().whenPressed(new RunInLowGearCommand(singleRotationTrigger));
-
- driverGamepad.getBottomButton().whenPressed(new RunInLowGearCommand(new RotateToAimMultiCommand()));
- driverGamepad.getTopButton().whenPressed(new RunInLowGearCommand(new SetupForShotCommand()));
- GyroRotationalCommand singleRotationLeft = new RotateToAimCommand(false, 1.7);
- singleRotationLeft.setUseSignalLights(true);
- GyroRotationalCommand singleRotationRight = new RotateToAimCommand(false, 1.7);
- singleRotationRight.setUseSignalLights(true);
- driverGamepad.getRightButton().whenPressed(new RunInLowGearCommand(singleRotationLeft));
- driverGamepad.getLeftButton().whenPressed(new RunInLowGearCommand(singleRotationRight));
-
+// // CV controls
+// GyroRotationalCommand singleRotationTrigger = new RotateToAimCommand(false, 1.7);
+// singleRotationTrigger.setUseSignalLights(true);
+// driverGamepad.getRightTrigger().whenPressed(new RunInLowGearCommand(singleRotationTrigger));
+//
+// driverGamepad.getBottomButton().whenPressed(new RunInLowGearCommand(new RotateToAimMultiCommand()));
+// driverGamepad.getTopButton().whenPressed(new RunInLowGearCommand(new SetupForShotCommand()));
+// GyroRotationalCommand singleRotationLeft = new RotateToAimCommand(false, 1.7);
+// singleRotationLeft.setUseSignalLights(true);
+// GyroRotationalCommand singleRotationRight = new RotateToAimCommand(false, 1.7);
+// singleRotationRight.setUseSignalLights(true);
+// driverGamepad.getRightButton().whenPressed(new RunInLowGearCommand(singleRotationLeft));
+// driverGamepad.getLeftButton().whenPressed(new RunInLowGearCommand(singleRotationRight));
+//
// OPERATOR BINDINGS
operatorGamepad.getLeftTrigger().whileHeld(new HopperRunCommand(true));
operatorGamepad.getLeftBumper().whileHeld(new HopperRunCommand(false));
diff --git a/src/edu/stuy/robot/Robot.java b/src/main/java/edu/stuy/robot/Robot.java
similarity index 95%
rename from src/edu/stuy/robot/Robot.java
rename to src/main/java/edu/stuy/robot/Robot.java
index 73c05b4..335d065 100644
--- a/src/edu/stuy/robot/Robot.java
+++ b/src/main/java/edu/stuy/robot/Robot.java
@@ -7,7 +7,7 @@
import static edu.stuy.robot.RobotMap.SIGNAL_LIGHT_YELLOW_PORT;
import static edu.stuy.robot.RobotMap.YUBIN_ID;
-import edu.stuy.robot.commands.auton.CrossObstacleThenShootCommand;
+//import edu.stuy.robot.commands.auton.CrossObstacleThenShootCommand;
import edu.stuy.robot.commands.auton.GoOverMoatCommand;
import edu.stuy.robot.commands.auton.GoOverRampartsCommand;
import edu.stuy.robot.commands.auton.GoOverRockWallBackwardsCommand;
@@ -16,7 +16,7 @@
import edu.stuy.robot.commands.auton.PassChevalCommand;
import edu.stuy.robot.commands.auton.PassPortcullisCommand;
import edu.stuy.robot.commands.auton.ReachObstacleCommand;
-import edu.stuy.robot.cv.StuyVision;
+//import edu.stuy.robot.cv.StuyVision;
import edu.stuy.robot.subsystems.Acquirer;
import edu.stuy.robot.subsystems.Drivetrain;
import edu.stuy.robot.subsystems.DropDown;
@@ -69,7 +69,7 @@ public class Robot extends IterativeRobot {
private double autonStartTime;
private static boolean debugMode;
- public static StuyVision vision;
+// public static StuyVision vision;
public static BoolBox stopAutoMovement = new BoolBox(false);
// Used to not waste a ball in a shooting auton if CV doesn't
@@ -120,7 +120,7 @@ public void robotInit() {
flashlight = new Flashlight();
oi = new OI();
- vision = new StuyVision();
+// vision = new StuyVision();
drivetrain.setDrivetrainBrakeMode(true);
shooter.setShooterBrakeMode(false);
@@ -199,9 +199,13 @@ private void setupShootChooser() {
public void disabledPeriodic() {
Scheduler.getInstance().run();
+ oi.driverGamepad.resetGamepadType();
+ oi.operatorGamepad.resetGamepadType();
}
public void autonomousInit() {
+ oi.driverGamepad.resetGamepadType();
+ oi.operatorGamepad.resetGamepadType();
try {
Robot.cvSignalLight.stayOff();
debugMode = (Boolean) debugChooser.getSelected();
@@ -211,7 +215,7 @@ public void autonomousInit() {
boolean shoot = (Boolean) autonShootChooser.getSelected();
selectedAutonomousCommand = selected;
if (shoot) {
- autonomousCommand = new CrossObstacleThenShootCommand(selectedAutonomousCommand, autonPosition);
+// autonomousCommand = new CrossObstacleThenShootCommand(selectedAutonomousCommand, autonPosition);
} else {
autonomousCommand = selectedAutonomousCommand;
}
@@ -252,6 +256,8 @@ public void autonomousPeriodic() {
}
public void teleopInit() {
+ oi.operatorGamepad.resetGamepadType();
+ oi.driverGamepad.resetGamepadType();
try {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
diff --git a/src/edu/stuy/robot/RobotMap.java b/src/main/java/edu/stuy/robot/RobotMap.java
similarity index 93%
rename from src/edu/stuy/robot/RobotMap.java
rename to src/main/java/edu/stuy/robot/RobotMap.java
index 1297159..f822652 100644
--- a/src/edu/stuy/robot/RobotMap.java
+++ b/src/main/java/edu/stuy/robot/RobotMap.java
@@ -12,16 +12,16 @@ public interface RobotMap {
int DRIVER_GAMEPAD = 0;
int OPERATOR_GAMEPAD = 1;
- // Drivetrain CANTalon channels
- int FRONT_RIGHT_MOTOR_CHANNEL = 1;
+ // Drivetrain TalonSRX channels
+ int FRONT_RIGHT_MOTOR_CHANNEL = 3;
int REAR_RIGHT_MOTOR_CHANNEL = 2;
- int REAR_LEFT_MOTOR_CHANNEL = 3;
- int FRONT_LEFT_MOTOR_CHANNEL = 4;
+ int REAR_LEFT_MOTOR_CHANNEL = 4;
+ int FRONT_LEFT_MOTOR_CHANNEL = 1;
- // CANTalon channels for other subsystems
+ // TalonSRX channels for other subsystems
int HOPPER_MOTOR_CHANNEL = 5;
int ACQUIRER_MOTOR_CHANNEL = 6;
- int SHOOTER_MOTOR_CHANNEL = 7;
+ int SHOOTER_MOTOR_CHANNEL = 13;
int DROPDOWN_MOTOR_CHANNEL = 8;
// Solenoid ports
diff --git a/src/edu/stuy/robot/commands/AcquirerAcquireCommand.java b/src/main/java/edu/stuy/robot/commands/AcquirerAcquireCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/AcquirerAcquireCommand.java
rename to src/main/java/edu/stuy/robot/commands/AcquirerAcquireCommand.java
diff --git a/src/edu/stuy/robot/commands/AcquirerDeacquireCommand.java b/src/main/java/edu/stuy/robot/commands/AcquirerDeacquireCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/AcquirerDeacquireCommand.java
rename to src/main/java/edu/stuy/robot/commands/AcquirerDeacquireCommand.java
diff --git a/src/edu/stuy/robot/commands/AcquirerStopCommand.java b/src/main/java/edu/stuy/robot/commands/AcquirerStopCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/AcquirerStopCommand.java
rename to src/main/java/edu/stuy/robot/commands/AcquirerStopCommand.java
diff --git a/src/edu/stuy/robot/commands/AutoMovementCommand.java b/src/main/java/edu/stuy/robot/commands/AutoMovementCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/AutoMovementCommand.java
rename to src/main/java/edu/stuy/robot/commands/AutoMovementCommand.java
diff --git a/src/main/java/edu/stuy/robot/commands/CVReadAndPrintCommand.java b/src/main/java/edu/stuy/robot/commands/CVReadAndPrintCommand.java
new file mode 100644
index 0000000..098fba3
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/commands/CVReadAndPrintCommand.java
@@ -0,0 +1,65 @@
+//package edu.stuy.robot.commands;
+//
+//import java.util.Arrays;
+//
+//import edu.stuy.robot.Robot;
+//import edu.stuy.robot.cv.StuyVision;
+//import edu.wpi.first.wpilibj.command.Command;
+//import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+//
+///**
+// *
+// */
+//public class CVReadAndPrintCommand extends Command {
+// boolean tryToSaveFile;
+// public CVReadAndPrintCommand() {
+// // Use requires() here to declare subsystem dependencies
+// // eg. requires(chassis);
+// }
+// public CVReadAndPrintCommand(boolean save) {
+// // Use requires() here to declare subsystem dependencies
+// // eg. requires(chassis);
+// tryToSaveFile = save;
+// }
+//
+// // Called just before this Command runs the first time
+// protected void initialize() {
+// try {
+// long start = System.currentTimeMillis();
+// double[] cvReading = null;
+// cvReading = Robot.vision.processImage(Robot.isDebugModeOn() && tryToSaveFile);
+// System.out.println("\n\n\n\n\n\n\n\n\n\nprocessImage took " + (System.currentTimeMillis() - start) + "ms");
+// System.out.println(new StuyVision.Report(cvReading));
+// boolean canProceed = cvReading != null;
+// SmartDashboard.putString("cv-reading", Arrays.toString(cvReading));
+// if (canProceed) {
+// double desiredAngle = StuyVision.frameXPxToDegrees(cvReading[0]);
+// SmartDashboard.putNumber("cv-angle", desiredAngle);
+// System.out.println("Desired Angle Delta: " + desiredAngle);
+// }
+// SmartDashboard.putBoolean("cv-visible", canProceed);
+// } catch (Exception e) {
+// System.err.println("\n\n\n\nGeneric exception caught in CVReadAndPrintCommand:");
+// e.printStackTrace();
+// System.err.println("^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^");
+// }
+// }
+//
+// // Called repeatedly when this Command is scheduled to run
+// protected void execute() {
+// }
+//
+// // Make this return true when this Command no longer needs to run execute()
+// protected boolean isFinished() {
+// return true;
+// }
+//
+// // Called once after isFinished returns true
+// protected void end() {
+// }
+//
+// // Called when another command which requires one or more of the same
+// // subsystems is scheduled to run
+// protected void interrupted() {
+// }
+//}
diff --git a/src/edu/stuy/robot/commands/ChangeGearCommand.java b/src/main/java/edu/stuy/robot/commands/ChangeGearCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ChangeGearCommand.java
rename to src/main/java/edu/stuy/robot/commands/ChangeGearCommand.java
diff --git a/src/edu/stuy/robot/commands/DisableAutoGearShiftCommand.java b/src/main/java/edu/stuy/robot/commands/DisableAutoGearShiftCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/DisableAutoGearShiftCommand.java
rename to src/main/java/edu/stuy/robot/commands/DisableAutoGearShiftCommand.java
diff --git a/src/main/java/edu/stuy/robot/commands/DriveToCourtyardRangeCommand.java b/src/main/java/edu/stuy/robot/commands/DriveToCourtyardRangeCommand.java
new file mode 100644
index 0000000..b3fbc31
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/commands/DriveToCourtyardRangeCommand.java
@@ -0,0 +1,34 @@
+//package edu.stuy.robot.commands;
+//
+//import static edu.stuy.robot.RobotMap.COURTYARD_SHOOTING_DISTANCE;
+//
+//import edu.stuy.robot.Robot;
+//import edu.stuy.robot.cv.StuyVision;
+//
+///**
+// *
+// */
+//public class DriveToCourtyardRangeCommand extends EncoderDrivingCommand {
+//
+// public DriveToCourtyardRangeCommand() {
+// super(Robot.stopAutoMovement);
+// // Use requires() here to declare subsystem dependencies
+// // eg. requires(chassis);
+// requires(Robot.drivetrain);
+// }
+//
+// protected void setInchesToMove() {
+// double[] cvReading = Robot.vision.processImage();
+// if (cvReading != null) {
+// double curDistance = StuyVision.findBotDistanceToGoal(cvReading[1]);
+// initialInchesToMove = curDistance - COURTYARD_SHOOTING_DISTANCE;
+// } else {
+// // CV failed!
+// cancelCommand = true;
+// }
+// System.out.println(new StuyVision.Report(cvReading));
+// if (cvReading != null) {
+// System.out.println(StuyVision.findBotDistanceToGoal(cvReading[1]));
+// }
+// }
+//}
diff --git a/src/main/java/edu/stuy/robot/commands/DriveToLayupRangeCommand.java b/src/main/java/edu/stuy/robot/commands/DriveToLayupRangeCommand.java
new file mode 100644
index 0000000..49e914e
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/commands/DriveToLayupRangeCommand.java
@@ -0,0 +1,35 @@
+//package edu.stuy.robot.commands;
+//
+//import static edu.stuy.robot.RobotMap.LAYUP_SHOOTING_DISTANCE;
+//
+//import edu.stuy.robot.Robot;
+//import edu.stuy.robot.cv.StuyVision;
+//import edu.stuy.util.BoolBox;
+//
+///**
+// *
+// */
+//public class DriveToLayupRangeCommand extends EncoderDrivingCommand {
+//
+// public DriveToLayupRangeCommand() {
+// super(Robot.stopAutoMovement);
+// // Use requires() here to declare subsystem dependencies
+// // eg. requires(chassis);
+// requires(Robot.drivetrain);
+// }
+//
+// protected void setInchesToMove() {
+// double[] cvReading = Robot.vision.processImage();
+// if (cvReading != null) {
+// double curDistance = StuyVision.findBotDistanceToGoal(cvReading[1]);
+// initialInchesToMove = curDistance - LAYUP_SHOOTING_DISTANCE;
+// } else {
+// // CV failed!
+// cancelCommand = true;
+// }
+// System.out.println(new StuyVision.Report(cvReading));
+// if (cvReading != null) {
+// System.out.println(StuyVision.findBotDistanceToGoal(cvReading[1]));
+// }
+// }
+//}
diff --git a/src/main/java/edu/stuy/robot/commands/DriveToLayupRangeMultiCommand.java b/src/main/java/edu/stuy/robot/commands/DriveToLayupRangeMultiCommand.java
new file mode 100644
index 0000000..fad94a2
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/commands/DriveToLayupRangeMultiCommand.java
@@ -0,0 +1,35 @@
+//package edu.stuy.robot.commands;
+//
+//import edu.wpi.first.wpilibj.command.CommandGroup;
+//
+///**
+// *
+// */
+//public class DriveToLayupRangeMultiCommand extends CommandGroup {
+//
+// public DriveToLayupRangeMultiCommand() {
+// // Add Commands here:
+// // e.g. addSequential(new Command1());
+// // addSequential(new Command2());
+// // these will run in order.
+//
+// // To run multiple commands at the same time,
+// // use addParallel()
+// // e.g. addParallel(new Command1());
+// // addSequential(new Command2());
+// // Command1 and Command2 will run in parallel.
+//
+// // A command group will require all of the subsystems that each member
+// // would require.
+// // e.g. if Command1 requires chassis, and Command2 requires arm,
+// // a CommandGroup containing them would require both the chassis and the
+// // arm.
+//
+// // This is a janky way of doing this. Urgency calls.
+//
+// // First movement:
+// addSequential(new DriveToLayupRangeCommand());
+// // Refine to account for mistakes:
+// addSequential(new DriveToLayupRangeCommand());
+// }
+//}
diff --git a/src/edu/stuy/robot/commands/DrivetrainDriveStraightCommand.java b/src/main/java/edu/stuy/robot/commands/DrivetrainDriveStraightCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/DrivetrainDriveStraightCommand.java
rename to src/main/java/edu/stuy/robot/commands/DrivetrainDriveStraightCommand.java
diff --git a/src/edu/stuy/robot/commands/DrivetrainStopCommand.java b/src/main/java/edu/stuy/robot/commands/DrivetrainStopCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/DrivetrainStopCommand.java
rename to src/main/java/edu/stuy/robot/commands/DrivetrainStopCommand.java
diff --git a/src/edu/stuy/robot/commands/DrivetrainTankDriveCommand.java b/src/main/java/edu/stuy/robot/commands/DrivetrainTankDriveCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/DrivetrainTankDriveCommand.java
rename to src/main/java/edu/stuy/robot/commands/DrivetrainTankDriveCommand.java
diff --git a/src/edu/stuy/robot/commands/DropDownDefaultCommand.java b/src/main/java/edu/stuy/robot/commands/DropDownDefaultCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/DropDownDefaultCommand.java
rename to src/main/java/edu/stuy/robot/commands/DropDownDefaultCommand.java
diff --git a/src/edu/stuy/robot/commands/DropDownMoveCommand.java b/src/main/java/edu/stuy/robot/commands/DropDownMoveCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/DropDownMoveCommand.java
rename to src/main/java/edu/stuy/robot/commands/DropDownMoveCommand.java
diff --git a/src/edu/stuy/robot/commands/EnableAutoGearShiftCommand.java b/src/main/java/edu/stuy/robot/commands/EnableAutoGearShiftCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/EnableAutoGearShiftCommand.java
rename to src/main/java/edu/stuy/robot/commands/EnableAutoGearShiftCommand.java
diff --git a/src/edu/stuy/robot/commands/EncoderDrivingCommand.java b/src/main/java/edu/stuy/robot/commands/EncoderDrivingCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/EncoderDrivingCommand.java
rename to src/main/java/edu/stuy/robot/commands/EncoderDrivingCommand.java
diff --git a/src/edu/stuy/robot/commands/FlashlightOffCommand.java b/src/main/java/edu/stuy/robot/commands/FlashlightOffCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/FlashlightOffCommand.java
rename to src/main/java/edu/stuy/robot/commands/FlashlightOffCommand.java
diff --git a/src/edu/stuy/robot/commands/FlashlightOnCommand.java b/src/main/java/edu/stuy/robot/commands/FlashlightOnCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/FlashlightOnCommand.java
rename to src/main/java/edu/stuy/robot/commands/FlashlightOnCommand.java
diff --git a/src/edu/stuy/robot/commands/FlashlightToggleCommand.java b/src/main/java/edu/stuy/robot/commands/FlashlightToggleCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/FlashlightToggleCommand.java
rename to src/main/java/edu/stuy/robot/commands/FlashlightToggleCommand.java
diff --git a/src/edu/stuy/robot/commands/GyroRotationalCommand.java b/src/main/java/edu/stuy/robot/commands/GyroRotationalCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/GyroRotationalCommand.java
rename to src/main/java/edu/stuy/robot/commands/GyroRotationalCommand.java
diff --git a/src/edu/stuy/robot/commands/HighGearCommand.java b/src/main/java/edu/stuy/robot/commands/HighGearCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/HighGearCommand.java
rename to src/main/java/edu/stuy/robot/commands/HighGearCommand.java
diff --git a/src/edu/stuy/robot/commands/HoodDownCommand.java b/src/main/java/edu/stuy/robot/commands/HoodDownCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/HoodDownCommand.java
rename to src/main/java/edu/stuy/robot/commands/HoodDownCommand.java
diff --git a/src/edu/stuy/robot/commands/HoodUpCommand.java b/src/main/java/edu/stuy/robot/commands/HoodUpCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/HoodUpCommand.java
rename to src/main/java/edu/stuy/robot/commands/HoodUpCommand.java
diff --git a/src/edu/stuy/robot/commands/HopperRunCommand.java b/src/main/java/edu/stuy/robot/commands/HopperRunCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/HopperRunCommand.java
rename to src/main/java/edu/stuy/robot/commands/HopperRunCommand.java
diff --git a/src/edu/stuy/robot/commands/HopperStopCommand.java b/src/main/java/edu/stuy/robot/commands/HopperStopCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/HopperStopCommand.java
rename to src/main/java/edu/stuy/robot/commands/HopperStopCommand.java
diff --git a/src/edu/stuy/robot/commands/JionDriveCommand.java b/src/main/java/edu/stuy/robot/commands/JionDriveCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/JionDriveCommand.java
rename to src/main/java/edu/stuy/robot/commands/JionDriveCommand.java
diff --git a/src/edu/stuy/robot/commands/LowGearCommand.java b/src/main/java/edu/stuy/robot/commands/LowGearCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/LowGearCommand.java
rename to src/main/java/edu/stuy/robot/commands/LowGearCommand.java
diff --git a/src/edu/stuy/robot/commands/ResetForceStopCommand.java b/src/main/java/edu/stuy/robot/commands/ResetForceStopCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ResetForceStopCommand.java
rename to src/main/java/edu/stuy/robot/commands/ResetForceStopCommand.java
diff --git a/src/edu/stuy/robot/commands/RotateDegreesGyroCommand.java b/src/main/java/edu/stuy/robot/commands/RotateDegreesGyroCommand.java
similarity index 95%
rename from src/edu/stuy/robot/commands/RotateDegreesGyroCommand.java
rename to src/main/java/edu/stuy/robot/commands/RotateDegreesGyroCommand.java
index c3f3c39..2395246 100644
--- a/src/edu/stuy/robot/commands/RotateDegreesGyroCommand.java
+++ b/src/main/java/edu/stuy/robot/commands/RotateDegreesGyroCommand.java
@@ -22,7 +22,7 @@ public RotateDegreesGyroCommand(double angle) {
}
protected void setDesiredAngle() {
- desiredAngle = notSet ? SmartDashboard.getNumber("gyro-rotate-degs") : _angle;
+ desiredAngle = notSet ? SmartDashboard.getNumber("gyro-rotate-degs", 0) : _angle;
}
protected void onEnd() {}
diff --git a/src/main/java/edu/stuy/robot/commands/RotateToAimCommand.java b/src/main/java/edu/stuy/robot/commands/RotateToAimCommand.java
new file mode 100644
index 0000000..54b5309
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/commands/RotateToAimCommand.java
@@ -0,0 +1,50 @@
+//package edu.stuy.robot.commands;
+//
+//import java.util.Arrays;
+//
+//import edu.stuy.robot.Robot;
+//import edu.stuy.robot.cv.StuyVision;
+//import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+//
+///**
+// *
+// */
+//public class RotateToAimCommand extends GyroRotationalCommand {
+//
+// public RotateToAimCommand() {
+// // Use requires() here to declare subsystem dependencies
+// // eg. requires(chassis);
+// super(Robot.stopAutoMovement, false);
+// }
+//
+// public RotateToAimCommand(boolean gentle) {
+// // Use requires() here to declare subsystem dependencies
+// // eg. requires(chassis);
+// super(Robot.stopAutoMovement, gentle);
+// }
+//
+// public RotateToAimCommand(boolean gentle, double tolerance) {
+// // Use requires() here to declare subsystem dependencies
+// // eg. requires(chassis);
+// super(Robot.stopAutoMovement, gentle, tolerance);
+// }
+//
+// private double[] cvReading;
+//
+// protected void setDesiredAngle() {
+// cvReading = Robot.vision.processImage();
+// canProceed = cvReading != null;
+// SmartDashboard.putString("cv-reading", Arrays.toString(cvReading));
+// if (canProceed) {
+// desiredAngle = StuyVision.frameXPxToDegrees(cvReading[0]);
+// SmartDashboard.putNumber("cv-angle", desiredAngle);
+// }
+// SmartDashboard.putBoolean("cv-visible", canProceed);
+// // For auton:
+// Robot.cvFoundGoal = canProceed;
+// }
+//
+// protected void onEnd() {
+// System.out.println(new StuyVision.Report(cvReading));
+// }
+//}
diff --git a/src/main/java/edu/stuy/robot/commands/RotateToAimMultiCommand.java b/src/main/java/edu/stuy/robot/commands/RotateToAimMultiCommand.java
new file mode 100644
index 0000000..b03927b
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/commands/RotateToAimMultiCommand.java
@@ -0,0 +1,27 @@
+//package edu.stuy.robot.commands;
+//
+//import edu.wpi.first.wpilibj.command.CommandGroup;
+//
+///**
+// *
+// */
+//public class RotateToAimMultiCommand extends CommandGroup {
+//
+// public RotateToAimMultiCommand() {
+// // First rotation:
+// addSequential(new RotateToAimCommand());
+// // Refine:
+// GyroRotationalCommand finalRot = new RotateToAimCommand(true);
+// finalRot.setUseSignalLights(true);
+// addSequential(finalRot);
+// }
+//
+// public RotateToAimMultiCommand(double tolerance) {
+// // First rotation:
+// addSequential(new RotateToAimCommand(false, tolerance));
+// // Refine:
+// GyroRotationalCommand finalRot = new RotateToAimCommand(true);
+// finalRot.setUseSignalLights(true);
+// addSequential(finalRot);
+// }
+//}
diff --git a/src/edu/stuy/robot/commands/RunInLowGearCommand.java b/src/main/java/edu/stuy/robot/commands/RunInLowGearCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/RunInLowGearCommand.java
rename to src/main/java/edu/stuy/robot/commands/RunInLowGearCommand.java
diff --git a/src/main/java/edu/stuy/robot/commands/SetupForShotCommand.java b/src/main/java/edu/stuy/robot/commands/SetupForShotCommand.java
new file mode 100644
index 0000000..3d3ade5
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/commands/SetupForShotCommand.java
@@ -0,0 +1,41 @@
+//package edu.stuy.robot.commands;
+//
+//import edu.wpi.first.wpilibj.command.CommandGroup;
+//
+///**
+// *
+// */
+//public class SetupForShotCommand extends CommandGroup {
+//
+// public SetupForShotCommand() {
+// // Add Commands here:
+// // e.g. addSequential(new Command1());
+// // addSequential(new Command2());
+// // these will run in order.
+//
+// // To run multiple commands at the same time,
+// // use addParallel()
+// // e.g. addParallel(new Command1());
+// // addSequential(new Command2());
+// // Command1 and Command2 will run in parallel.
+//
+// // A command group will require all of the subsystems that each member
+// // would require.
+// // e.g. if Command1 requires chassis, and Command2 requires arm,
+// // a CommandGroup containing them would require both the chassis and the
+// // arm.
+//
+// addSequential(new ResetForceStopCommand());
+//
+// addSequential(new RotateToAimCommand(false, 1.5)); // Coarse rotation
+// addSequential(new RotateToAimCommand(true)); // Refining rotation
+//
+// addSequential(new DriveToLayupRangeCommand());
+//
+// GyroRotationalCommand finalRotation = new RotateToAimCommand(false, 1.7);
+// finalRotation.setUseSignalLights(true);
+// addSequential(finalRotation);
+//
+// addSequential(new ResetForceStopCommand());
+// }
+//}
diff --git a/src/edu/stuy/robot/commands/ShooterBackwardsCommand.java b/src/main/java/edu/stuy/robot/commands/ShooterBackwardsCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ShooterBackwardsCommand.java
rename to src/main/java/edu/stuy/robot/commands/ShooterBackwardsCommand.java
diff --git a/src/edu/stuy/robot/commands/ShooterHopperBackwardsCommand.java b/src/main/java/edu/stuy/robot/commands/ShooterHopperBackwardsCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ShooterHopperBackwardsCommand.java
rename to src/main/java/edu/stuy/robot/commands/ShooterHopperBackwardsCommand.java
diff --git a/src/edu/stuy/robot/commands/ShooterHopperStopCommand.java b/src/main/java/edu/stuy/robot/commands/ShooterHopperStopCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ShooterHopperStopCommand.java
rename to src/main/java/edu/stuy/robot/commands/ShooterHopperStopCommand.java
diff --git a/src/edu/stuy/robot/commands/ShooterLowerSpeed.java b/src/main/java/edu/stuy/robot/commands/ShooterLowerSpeed.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ShooterLowerSpeed.java
rename to src/main/java/edu/stuy/robot/commands/ShooterLowerSpeed.java
diff --git a/src/edu/stuy/robot/commands/ShooterRaiseSpeed.java b/src/main/java/edu/stuy/robot/commands/ShooterRaiseSpeed.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ShooterRaiseSpeed.java
rename to src/main/java/edu/stuy/robot/commands/ShooterRaiseSpeed.java
diff --git a/src/edu/stuy/robot/commands/ShooterSetLayupCommand.java b/src/main/java/edu/stuy/robot/commands/ShooterSetLayupCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ShooterSetLayupCommand.java
rename to src/main/java/edu/stuy/robot/commands/ShooterSetLayupCommand.java
diff --git a/src/edu/stuy/robot/commands/ShooterSetMaxSpeed.java b/src/main/java/edu/stuy/robot/commands/ShooterSetMaxSpeed.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ShooterSetMaxSpeed.java
rename to src/main/java/edu/stuy/robot/commands/ShooterSetMaxSpeed.java
diff --git a/src/edu/stuy/robot/commands/ShooterSetOutWorksSpeed.java b/src/main/java/edu/stuy/robot/commands/ShooterSetOutWorksSpeed.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ShooterSetOutWorksSpeed.java
rename to src/main/java/edu/stuy/robot/commands/ShooterSetOutWorksSpeed.java
diff --git a/src/edu/stuy/robot/commands/ShooterStopCommand.java b/src/main/java/edu/stuy/robot/commands/ShooterStopCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/ShooterStopCommand.java
rename to src/main/java/edu/stuy/robot/commands/ShooterStopCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/AlignWithWallCommand.java b/src/main/java/edu/stuy/robot/commands/auton/AlignWithWallCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/AlignWithWallCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/AlignWithWallCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/AutonHopperCommand.java b/src/main/java/edu/stuy/robot/commands/auton/AutonHopperCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/AutonHopperCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/AutonHopperCommand.java
diff --git a/src/main/java/edu/stuy/robot/commands/auton/CrossObstacleThenShootCommand.java b/src/main/java/edu/stuy/robot/commands/auton/CrossObstacleThenShootCommand.java
new file mode 100644
index 0000000..20f8054
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/commands/auton/CrossObstacleThenShootCommand.java
@@ -0,0 +1,53 @@
+//package edu.stuy.robot.commands.auton;
+//
+//import edu.stuy.robot.commands.DrivetrainStopCommand;
+//import edu.stuy.robot.commands.FlashlightOnCommand;
+//import edu.stuy.robot.commands.LowGearCommand;
+//import edu.stuy.robot.commands.SetupForShotCommand;
+//import edu.stuy.robot.commands.ShooterSetLayupCommand;
+//import edu.wpi.first.wpilibj.command.Command;
+//import edu.wpi.first.wpilibj.command.CommandGroup;
+//
+///**
+// *
+// */
+//public class CrossObstacleThenShootCommand extends CommandGroup {
+//
+// public CrossObstacleThenShootCommand(Command obstacle, int position) {
+// // Add Commands here:
+// // e.g. addSequential(new Command1());
+// // addSequential(new Command2());
+// // these will run in order.
+//
+// // To run multiple commands at the same time,
+// // use addParallel()
+// // e.g. addParallel(new Command1());
+// // addSequential(new Command2());
+// // Command1 and Command2 will run in parallel.
+//
+// // A command group will require all of the subsystems that each member
+// // would require.
+// // e.g. if Command1 requires chassis, and Command2 requires arm,
+// // a CommandGroup containing them would require both the chassis and the
+// // arm.
+//
+// addSequential(obstacle);
+// addSequential(new LowGearCommand());
+// addSequential(new DrivetrainStopCommand());
+// addParallel(new ShooterSetLayupCommand());
+// addSequential(new DropDownMoveToAngleCommand(0), 2.0);
+// if (position != 3 && position != 4) {
+// // RotateDrivetrainCommand will, at runtime, decide angle
+// // based on Robot.autonPositionChooser.getSelected()
+// addSequential(new RotateDrivetrainCommand());
+// }
+// addParallel(new FlashlightOnCommand()); // So we can see where it is aiming
+// addSequential(new SetupForShotCommand());
+//
+// // The following only runs the hopper if goal was in frame for CV
+// addSequential(new HandleAutonShotCommand(), 3.0);
+//
+// // Drivetrain returns to high gear in teleopInit, where
+// // also shooter, hopper and flashlight are turned off.
+// }
+//}
diff --git a/src/edu/stuy/robot/commands/auton/DriveBackwardCommand.java b/src/main/java/edu/stuy/robot/commands/auton/DriveBackwardCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/DriveBackwardCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/DriveBackwardCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/DriveForwardCommand.java b/src/main/java/edu/stuy/robot/commands/auton/DriveForwardCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/DriveForwardCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/DriveForwardCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/DriveOverMoatCommand.java b/src/main/java/edu/stuy/robot/commands/auton/DriveOverMoatCommand.java
similarity index 91%
rename from src/edu/stuy/robot/commands/auton/DriveOverMoatCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/DriveOverMoatCommand.java
index a5adc77..b06df29 100644
--- a/src/edu/stuy/robot/commands/auton/DriveOverMoatCommand.java
+++ b/src/main/java/edu/stuy/robot/commands/auton/DriveOverMoatCommand.java
@@ -9,7 +9,7 @@ public class DriveOverMoatCommand extends DriveForwardCommand {
private static final double SPEED = 0.9;
public DriveOverMoatCommand() {
- super(SmartDashboard.getNumber("Moat"), MAX_TIME_IN_SECONDS, SPEED);
+ super(SmartDashboard.getNumber("Moat", 0), MAX_TIME_IN_SECONDS, SPEED);
}
@Override
diff --git a/src/edu/stuy/robot/commands/auton/DriveOverRampartsCommand.java b/src/main/java/edu/stuy/robot/commands/auton/DriveOverRampartsCommand.java
similarity index 90%
rename from src/edu/stuy/robot/commands/auton/DriveOverRampartsCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/DriveOverRampartsCommand.java
index d30602f..d0ca283 100644
--- a/src/edu/stuy/robot/commands/auton/DriveOverRampartsCommand.java
+++ b/src/main/java/edu/stuy/robot/commands/auton/DriveOverRampartsCommand.java
@@ -9,7 +9,7 @@ public class DriveOverRampartsCommand extends DriveForwardCommand {
private static final double SPEED = 1.0;
public DriveOverRampartsCommand() {
- super(SmartDashboard.getNumber("Ramparts"), MAX_TIME_IN_SECONDS, SPEED);
+ super(SmartDashboard.getNumber("Ramparts", 0), MAX_TIME_IN_SECONDS, SPEED);
}
@Override
diff --git a/src/edu/stuy/robot/commands/auton/DriveOverRockWallCommand.java b/src/main/java/edu/stuy/robot/commands/auton/DriveOverRockWallCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/DriveOverRockWallCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/DriveOverRockWallCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/DriveOverRoughTerrainCommand.java b/src/main/java/edu/stuy/robot/commands/auton/DriveOverRoughTerrainCommand.java
similarity index 91%
rename from src/edu/stuy/robot/commands/auton/DriveOverRoughTerrainCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/DriveOverRoughTerrainCommand.java
index b674cd1..b18acb5 100644
--- a/src/edu/stuy/robot/commands/auton/DriveOverRoughTerrainCommand.java
+++ b/src/main/java/edu/stuy/robot/commands/auton/DriveOverRoughTerrainCommand.java
@@ -9,7 +9,7 @@ public class DriveOverRoughTerrainCommand extends DriveForwardCommand {
private static final double SPEED = 1.0;
public DriveOverRoughTerrainCommand() {
- super(SmartDashboard.getNumber("Rough"), MAX_TIME_IN_SECONDS, SPEED);
+ super(SmartDashboard.getNumber("Rough", 0), MAX_TIME_IN_SECONDS, SPEED);
}
@Override
diff --git a/src/edu/stuy/robot/commands/auton/DropDownMoveToAngleCommand.java b/src/main/java/edu/stuy/robot/commands/auton/DropDownMoveToAngleCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/DropDownMoveToAngleCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/DropDownMoveToAngleCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/GoOverMoatCommand.java b/src/main/java/edu/stuy/robot/commands/auton/GoOverMoatCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/GoOverMoatCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/GoOverMoatCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/GoOverRampartsCommand.java b/src/main/java/edu/stuy/robot/commands/auton/GoOverRampartsCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/GoOverRampartsCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/GoOverRampartsCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/GoOverRockWallBackwardsCommand.java b/src/main/java/edu/stuy/robot/commands/auton/GoOverRockWallBackwardsCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/GoOverRockWallBackwardsCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/GoOverRockWallBackwardsCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/GoOverRockWallCommand.java b/src/main/java/edu/stuy/robot/commands/auton/GoOverRockWallCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/GoOverRockWallCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/GoOverRockWallCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/GoOverRoughTerrainCommand.java b/src/main/java/edu/stuy/robot/commands/auton/GoOverRoughTerrainCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/GoOverRoughTerrainCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/GoOverRoughTerrainCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/HandleAutonShotCommand.java b/src/main/java/edu/stuy/robot/commands/auton/HandleAutonShotCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/HandleAutonShotCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/HandleAutonShotCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/PassChevalCommand.java b/src/main/java/edu/stuy/robot/commands/auton/PassChevalCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/PassChevalCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/PassChevalCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/PassPortcullisCommand.java b/src/main/java/edu/stuy/robot/commands/auton/PassPortcullisCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/PassPortcullisCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/PassPortcullisCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/ReachObstacleCommand.java b/src/main/java/edu/stuy/robot/commands/auton/ReachObstacleCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/ReachObstacleCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/ReachObstacleCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/RotateDrivetrainCommand.java b/src/main/java/edu/stuy/robot/commands/auton/RotateDrivetrainCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/RotateDrivetrainCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/RotateDrivetrainCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/SetDistanceFromWallCommand.java b/src/main/java/edu/stuy/robot/commands/auton/SetDistanceFromWallCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/SetDistanceFromWallCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/SetDistanceFromWallCommand.java
diff --git a/src/edu/stuy/robot/commands/auton/ShootOuterworkCommand.java b/src/main/java/edu/stuy/robot/commands/auton/ShootOuterworkCommand.java
similarity index 100%
rename from src/edu/stuy/robot/commands/auton/ShootOuterworkCommand.java
rename to src/main/java/edu/stuy/robot/commands/auton/ShootOuterworkCommand.java
diff --git a/src/main/java/edu/stuy/robot/cv/StuyVision.java b/src/main/java/edu/stuy/robot/cv/StuyVision.java
new file mode 100644
index 0000000..a5ab54c
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/cv/StuyVision.java
@@ -0,0 +1,411 @@
+//package edu.stuy.robot.cv;
+//
+//import static edu.stuy.robot.RobotMap.CAMERA_DIST_TO_BOT_FRONT;
+//import static edu.stuy.robot.RobotMap.CAMERA_FRAME_PX_HEIGHT;
+//import static edu.stuy.robot.RobotMap.CAMERA_FRAME_PX_WIDTH;
+//import static edu.stuy.robot.RobotMap.CAMERA_HEIGHT_FROM_GROUND;
+//import static edu.stuy.robot.RobotMap.CAMERA_TILT_ANGLE;
+//import static edu.stuy.robot.RobotMap.CAMERA_VIEWING_ANGLE_X;
+//import static edu.stuy.robot.RobotMap.CAMERA_VIEWING_ANGLE_Y;
+//import static edu.stuy.robot.RobotMap.HIGH_GOAL_HEIGHT;
+//
+//import java.io.IOException;
+//import java.io.PrintWriter;
+//import java.util.ArrayList;
+//import java.util.Arrays;
+//
+//import org.opencv.core.Core;
+//import org.opencv.core.CvType;
+//import org.opencv.core.Mat;
+//import org.opencv.core.MatOfPoint;
+//import org.opencv.core.MatOfPoint2f;
+//import org.opencv.core.Point;
+//import org.opencv.core.RotatedRect;
+//import org.opencv.core.Scalar;
+//import org.opencv.core.Size;
+//import org.opencv.imgcodecs.Imgcodecs;
+//import org.opencv.imgproc.Imgproc;
+//import org.opencv.videoio.Videoio;
+//
+//import edu.stuy.robot.cv.capture.CaptureSource;
+//import edu.stuy.robot.cv.capture.DeviceCaptureSource;
+//import edu.stuy.robot.cv.gui.DoubleSV;
+//import edu.stuy.robot.cv.gui.IntegerSV;
+//import edu.stuy.robot.cv.gui.Main;
+//import edu.stuy.robot.cv.gui.VisionModule;
+//
+//public class StuyVision extends VisionModule {
+//
+// // The following can be left in even in production, as the overhead
+// // of using .value() is negligible
+// public IntegerSV minH_GREEN = IntegerSV.mkColor(36, "Min Hue");
+// public IntegerSV maxH_GREEN = IntegerSV.mkColor(94, "Max Hue");
+//
+// public IntegerSV minS_GREEN = IntegerSV.mkColor(225, "Min Saturation");
+// public IntegerSV maxS_GREEN = IntegerSV.mkColor(255, "Max Saturation");
+//
+// public IntegerSV minV_GREEN = IntegerSV.mkColor(30, "Min Value");
+// public IntegerSV maxV_GREEN = IntegerSV.mkColor(255, "Max Value");
+//
+// // Thresholds regarding the geometry of the bounding box of the region found
+// // by the HSV filtering
+// public DoubleSV minGoalArea = new DoubleSV(200.0, 0.0, 10000.0, "Min Goal Area");
+// public DoubleSV maxGoalArea = new DoubleSV(30720.0, 0.0, 10000.0, "Max Goal Area");
+// public DoubleSV minGoalRatio = new DoubleSV(1.1, 1.0, 10.0, "Min Goal Ratio");
+// public DoubleSV maxGoalRatio = new DoubleSV(3.0, 1.0, 10.0, "Max Goal Ratio");
+//
+// private static final int outerUSBPort = 0;
+// private int cameraPort;
+// private DeviceCaptureSource camera;
+//
+// private static PrintWriter logWriter;
+//
+// // Reused across processImage() calls
+// private Mat rawFrame;
+// private Mat resizedFrame;
+//
+// public StuyVision() {
+// try {
+// // Ensure native libraries are loaded
+// loadOpenCV();
+// // Assume the camera is plugged into port `outerUSBPort`
+// cameraPort = outerUSBPort;
+// initializeCamera();
+// rawFrame = new Mat();
+// resizedFrame = new Mat();
+// } catch (Exception e) {
+// System.out.println("Failed to create camera at " + cameraPort + ". Error was: " + e);
+// }
+// try {
+// logWriter = new PrintWriter("logs.txt");
+// } catch (Exception e) {
+// }
+// }
+//
+// public static void loadOpenCV() {
+// // Load opencv native library
+// String dir = StuyVision.class.getClassLoader().getResource("").getPath();
+// if (System.getProperty("os.name").toLowerCase().contains("windows")) {
+// System.load(dir.substring(1).replaceAll("\\%20", " ")
+// + "..\\lib\\opencv-3.1.0\\build\\java\\x64\\opencv_java310.dll");
+// } else {
+// // This is the .so's location on the roboRio
+// System.load("/usr/local/frc/lib/libopencv_java320.so");
+// }
+// }
+//
+// private void initializeCamera() {
+// Runtime rt = Runtime.getRuntime();
+// try {
+// rt.exec("/usr/bin/v4l2-ctl -c exposure_auto=1,exposure_absolute=5,brightness=30,contrast=10,saturation=200,white_balance_temperature_auto=0,sharpness=50").waitFor();
+// rt.exec("/usr/bin/v4l2-ctl -c white_balance_temperature=4624").waitFor();
+// } catch (Exception e) {
+// System.err.println("Setting v4l settings crashed!");
+// }
+// camera = new DeviceCaptureSource(cameraPort);
+// System.out.println("Made camera");
+// camera.capture.set(Videoio.CV_CAP_PROP_BUFFERSIZE, 2);
+// }
+//
+// /**
+// * Given the dimensions of a rectangle, return whether the ratio of these
+// * rectangle's dimensions suggests it may be a valid goal.
+// *
+// * @param height
+// * @param width
+// * @return
+// */
+// private boolean aspectRatioThreshold(double height, double width) {
+// double ratio = width / height;
+// return (minGoalRatio.value() < ratio && ratio < maxGoalRatio.value())
+// || (1 / maxGoalRatio.value() < ratio && ratio < 1 / minGoalRatio.value());
+// }
+//
+// private double[] getLargestGoal(Mat originalFrame, Mat filteredImage, Main app) {
+// boolean withGui = app != null;
+// Mat drawn = null;
+// if (withGui) {
+// drawn = originalFrame.clone();
+// }
+//
+// ArrayList
+// * app
is
+// * passed, post two intermediate states of the image from during processing
+// * to the gui
+// *
+// * @param frame
+// * The image to process
+// *
+// * @param app
+// * (Optional: pass null
to ignore) The Main
to
+// * post intermediate states of the processed image to.
+// *
+// * @return Three doubles, in a double[3]
, ordered as such: index 0
: The x-offset, in pixels, of the center of the
+// * bounding rectangle of the found goal from the center of the image index 1
: The y-offset, in pixels, of the center of the
+// * bounding rectangle of the found goal form the center of the image index 2
: The angle at which the bounding rectangle is
+// * tilted iters
frames read from
+// * cs
+// *
+// * @param cs
+// * The CaptureSource from which to read frames
+// * @param iters
+// * The number of frames to read from cs
and to process and time
+// * @return The average time taken by hsvThresholding
to process
+// * one of the frames
+// */
+// public double testProcessingTime(CaptureSource cs, int iters) {
+// int total = 0;
+// double[] vec;
+// for (int i = 0; i < iters; i++) {
+// long start = System.currentTimeMillis();
+// vec = processImage();
+// total += (int) (System.currentTimeMillis() - start);
+// }
+// return total / (double) iters;
+// }
+//
+// // Calculation methods:
+// public static double frameXPxToDegrees(double px) {
+// return CAMERA_VIEWING_ANGLE_X * px / CAMERA_FRAME_PX_WIDTH;
+// }
+//
+// public static double frameYPxToDegrees(double dy) {
+// return dy / CAMERA_FRAME_PX_HEIGHT * CAMERA_VIEWING_ANGLE_Y;
+// }
+//
+// public static double yInFrameToDegreesFromHorizon(double height) {
+// return CAMERA_TILT_ANGLE - frameYPxToDegrees(height);
+// }
+//
+// public static double findCameraDistanceToGoal(double frameY) {
+// double angle = yInFrameToDegreesFromHorizon(frameY);
+// return (HIGH_GOAL_HEIGHT - CAMERA_HEIGHT_FROM_GROUND) / Math.tan(Math.toRadians(angle));
+// }
+//
+// public static double findBotDistanceToGoal(double frameY) {
+// return findCameraDistanceToGoal(frameY) - CAMERA_DIST_TO_BOT_FRONT;
+// }
+//
+// public static double findDistanceToGoal(double[] vec) {
+// if (vec == null) {
+// return -1;
+// }
+// return findCameraDistanceToGoal(vec[1]);
+// }
+//
+// public static class Report {
+// double[] reading;
+// double goalDegsY;
+// double goalDegsX;
+// double inchesAway;
+// double degsUp;
+//
+// public Report(double[] visionReading) {
+// if (visionReading == null) {
+// return;
+// }
+// reading = visionReading;
+// goalDegsX = frameXPxToDegrees(reading[0]);
+// goalDegsY = frameXPxToDegrees(reading[1]);
+// degsUp = yInFrameToDegreesFromHorizon(reading[1]);
+// inchesAway = findCameraDistanceToGoal(reading[1]);
+// // let null pointer exception occur if data is null
+// }
+//
+// public String formattedReading() {
+// if (reading == null) {
+// return "null";
+// }
+// return "[" + fmt(reading[0]) + ", " + fmt(reading[1]) + ", " + fmt(reading[2]) + "]";
+// }
+//
+// private static final String blank = "------------------------------------";
+//
+// public String toString() {
+// boolean none = false;
+// if (reading == null) {
+// // return "| CV read no goals in frame\n" + blank + blank +
+// // blank + blank + blank;
+// none = true;
+// }
+// return "| CV Read: " + Arrays.toString(reading) + "\n" + "| Data: "
+// + (none ? blank : formattedReading()) + "\n" + "| Angle X: "
+// + (none ? blank : (fmt(goalDegsX) + "\u00B0 right from center")) + "\n" + "| Angle Y: "
+// + (none ? blank : (fmt(goalDegsY) + "\u00B0 down from center")) + "\n" + "| Elevation: "
+// + (none ? blank : (fmt(degsUp) + "\u00B0 up from horizon")) + "\n" + "| Cam Dist: "
+// + (none ? blank : fmtDist(inchesAway)) + "\n" + "| (Time: " + System.currentTimeMillis() + ")\n";
+// }
+//
+// private static String fmtDist(double d) {
+// int inches = (int) d;
+// return (inches / 12) + " ft, " + (inches % 12) + " in";
+// }
+//
+// private static String fmt(double d) {
+// return String.format("%.0f", d);
+// }
+// }
+//
+// public static void main(String[] args) {
+// System.out.println("Running test: read from frame and determine angle to rotate");
+// StuyVision sv = new StuyVision();
+// double[] reading = sv.processImage();
+// System.out.println(new Report(reading));
+// }
+//
+// public void run(Main app, Mat frame) {
+// app.postImage(frame, "Video", this);
+// double[] reading = hsvThresholding(frame, app);
+// System.out.println("\n\n" + new Report(reading));
+// }
+//}
diff --git a/src/edu/stuy/robot/cv/capture/CaptureSource.java b/src/main/java/edu/stuy/robot/cv/capture/CaptureSource.java
similarity index 100%
rename from src/edu/stuy/robot/cv/capture/CaptureSource.java
rename to src/main/java/edu/stuy/robot/cv/capture/CaptureSource.java
diff --git a/src/edu/stuy/robot/cv/capture/DeviceCaptureSource.java b/src/main/java/edu/stuy/robot/cv/capture/DeviceCaptureSource.java
similarity index 100%
rename from src/edu/stuy/robot/cv/capture/DeviceCaptureSource.java
rename to src/main/java/edu/stuy/robot/cv/capture/DeviceCaptureSource.java
diff --git a/src/edu/stuy/robot/cv/capture/ImageCaptureSource.java b/src/main/java/edu/stuy/robot/cv/capture/ImageCaptureSource.java
similarity index 100%
rename from src/edu/stuy/robot/cv/capture/ImageCaptureSource.java
rename to src/main/java/edu/stuy/robot/cv/capture/ImageCaptureSource.java
diff --git a/src/edu/stuy/robot/cv/capture/VideoCaptureSource.java b/src/main/java/edu/stuy/robot/cv/capture/VideoCaptureSource.java
similarity index 100%
rename from src/edu/stuy/robot/cv/capture/VideoCaptureSource.java
rename to src/main/java/edu/stuy/robot/cv/capture/VideoCaptureSource.java
diff --git a/src/edu/stuy/robot/cv/gui/BooleanVariable.java b/src/main/java/edu/stuy/robot/cv/gui/BooleanVariable.java
similarity index 100%
rename from src/edu/stuy/robot/cv/gui/BooleanVariable.java
rename to src/main/java/edu/stuy/robot/cv/gui/BooleanVariable.java
diff --git a/src/main/java/edu/stuy/robot/cv/gui/ControlsController.java b/src/main/java/edu/stuy/robot/cv/gui/ControlsController.java
new file mode 100644
index 0000000..8f7df08
--- /dev/null
+++ b/src/main/java/edu/stuy/robot/cv/gui/ControlsController.java
@@ -0,0 +1,170 @@
+//package edu.stuy.robot.cv.gui;
+//
+//import java.lang.reflect.Field;
+//import java.text.DecimalFormat;
+//import java.util.ArrayList;
+//
+//import edu.stuy.robot.cv.util.DebugPrinter;
+//import javafx.application.Platform;
+//import javafx.beans.value.ChangeListener;
+//import javafx.beans.value.ObservableValue;
+//import javafx.fxml.FXML;
+//import javafx.geometry.Pos;
+//import javafx.scene.Node;
+//import javafx.scene.control.Button;
+//import javafx.scene.control.CheckBox;
+//import javafx.scene.control.Slider;
+//import javafx.scene.layout.FlowPane;
+//import javafx.scene.layout.VBox;
+//import javafx.scene.text.Text;
+//
+//public class ControlsController {
+//
+// @FXML
+// FlowPane flowPane;
+// @FXML
+// VBox controlsContainer;
+// @FXML
+// Button restoreDefaults;
+//
+// final DecimalFormat formatter = new DecimalFormat("#.###");
+//
+// public void setup(VisionModule module) {
+// ArrayList