m_blocks = new ArrayList<>();
+ private static boolean m_hasRun = false;
+
+ public DeferredBlock(Runnable block) {
+ m_blocks.add(block);
+ }
+
+ public static void execute() {
+ if (m_hasRun) return;
+
+ for (Runnable block : m_blocks) {
+ block.run();
+ }
+
+ m_blocks.clear(); // for garbage collection
+ m_hasRun = true;
+ }
+}
diff --git a/src/main/java/frc4388/utility/Gains.java b/src/main/java/frc4388/utility/Gains.java
new file mode 100644
index 0000000..7a3a026
--- /dev/null
+++ b/src/main/java/frc4388/utility/Gains.java
@@ -0,0 +1,83 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package frc4388.utility;
+
+/** Add your docs here. */
+public class Gains {
+ public double kP;
+ public double kI;
+ public double kD;
+ public double kF;
+ public int kIZone;
+ public double kPeakOutput;
+ public double kMaxOutput;
+ public double kMinOutput;
+
+ /**
+ * Creates Gains object for PIDs
+ * @param kP The P value.
+ * @param kI The I value.
+ * @param kD The D value.
+ * @param kF The F value.
+ * @param kIZone The zone of the I value.
+ * @param kPeakOutput The peak output setting the motors to run the gains at, in both forward and reverse directions. By default 1.0.
+ */
+ public Gains(double kP, double kI, double kD, double kF, int kIZone, double kPeakOutput) {
+ this.kP = kP;
+ this.kI = kI;
+ this.kD = kD;
+ this.kF = kF;
+ this.kIZone = kIZone;
+ this.kPeakOutput = kPeakOutput;
+ this.kMaxOutput = kPeakOutput;
+ this.kMinOutput = -kPeakOutput;
+ }
+
+ /**
+ * Creates Gains object for PIDs
+ * @param kP The P value.
+ * @param kI The I value.
+ * @param kD The D value.
+ * @param kF The F value.
+ * @param kIZone The zone of the I value.
+ */
+ public Gains(double kP, double kI, double kD, double kF, int kIZone) {
+ this.kP = kP;
+ this.kI = kI;
+ this.kD = kD;
+ this.kF = kF;
+ this.kIZone = kIZone;
+ this.kPeakOutput = 1.0;
+ this.kMaxOutput = 1.0;
+ this.kMinOutput = -1.0;
+ }
+
+ public Gains(double kP, double kI, double kD) {
+ this.kP = kP;
+ this.kI = kI;
+ this.kD = kD;
+ }
+
+ /**
+ * Creates Gains object for PIDs
+ * @param kP The P value.
+ * @param kI The I value.
+ * @param kD The D value.
+ * @param kF The F value.
+ * @param kIZone The zone of the I value.
+ * @param kMinOutput The lowest output setting to run the gains at, usually in the reverse direction. By default -1.0.
+ * @param kMaxOutput The highest output setting to run the gains at, usually in the forward direction. By default 1.0.
+ */
+ public Gains(double kP, double kI, double kD, double kF, int kIZone, double kMaxOutput, double kMinOutput) {
+ this.kP = kP;
+ this.kI = kI;
+ this.kD = kD;
+ this.kF = kF;
+ this.kIZone = kIZone;
+ this.kMaxOutput = kMaxOutput;
+ this.kMinOutput = kMinOutput;
+ this.kPeakOutput = (Math.abs(kMinOutput) > Math.abs(kMaxOutput)) ? Math.abs(kMinOutput) : Math.abs(kMaxOutput);
+ }
+}
\ No newline at end of file
diff --git a/src/main/java/frc4388/utility/LEDPatterns.java b/src/main/java/frc4388/utility/LEDPatterns.java
new file mode 100644
index 0000000..6df032c
--- /dev/null
+++ b/src/main/java/frc4388/utility/LEDPatterns.java
@@ -0,0 +1,45 @@
+package frc4388.utility;
+
+/**
+ * Add your docs here.
+ */
+public enum LEDPatterns {
+ /* PALLETTE PATTERNS */
+ RAINBOW_RAINBOW(-0.99f), PARTY_RAINBOW(-0.97f), OCEAN_RAINBOW(-0.95f), LAVA_RAINBOW(-0.93f), FOREST_RAINBOW(-0.91f),
+ RAINBOW_GLITTER(-0.89f), CONFETTI(-0.87f), RED_SHOT(-0.85f), BLUE_SHOT(-0.83f), WHITE_SHOT(-0.81f), RAINBOW_SINELON(-0.79f),
+ PARTY_SINELON(-0.77f), OCEAN_SINELON(-0.75f), LAVA_SINELON(-0.73f), FOREST_SINELON(-0.71f), RAINBOW_BPM(-0.69f),
+ PARTY_BPM(-0.67f), OCEAN_BPM(-0.65f), LAVA_BPM(-0.63f), FOREST_BPM(-0.61f), FIRE_MEDIUM(-0.59f), FIRE_LARGE(-0.57f),
+ RAINBOW_TWINKLES(-0.55f), PARTY_TWINKLES(-0.53f), OCEAN_TWINKLES(-0.51f), LAVA_TWINKLES(-0.49f), FOREST_TWINKLES(-0.47f),
+ RAINBOW_WAVES(-0.45f), PARTY_WAVES(-0.43f), OCEAN_WAVES(-0.41f), LAVA_WAVES(-0.39f), FOREST_WAVES(-0.37f),
+ RED_SCANNER(-0.35f), GRAY_SCANNER(-0.33f), RED_CHASE(-0.31f), BLUE_CHASE(-0.29f), GRAY_CHASE(-0.27f), RED_HEARTBEAT(-0.25f),
+ BLUE_HEARTBEAT(-0.23f), WHITE_HEARTBEAT(-0.21f), GRAY_HEARBEAT(-0.19f), RED_BREATH(-0.17f), BLUE_BREATH(-0.15f),
+ GRAY_BREATH(-0.13f), RED_STROBE(-0.11f), BLUE_STROBE(-0.09f), GOLD_STROBE(-0.07f), WHITE_STROBE(-0.05f),
+
+ /* COLOR 1 PATTERNS */
+ C1_END_TO_END(-0.03f), C1_SCANNER(-0.01f), C1_CHASE(0.01f), C1_HEARTBEAT_SLOW(0.03f), C1_HEARTBEAT_MEDIUM(0.05f),
+ C1_HEARTBEAT_FAST(0.07f), C1_BREATH_SLOW(0.09f), C1_BREATH_FAST(0.11f), C1_SHOT(0.13f), C1_STROBE(0.15f),
+
+ /* COLOR 2 PATTERNS */
+ C2_END_TO_END(0.17f), C2_SCANNER(0.19f), C2_CHASE(0.21f), C2_HEARTBEAT_SLOW(0.23f), C2_HEARTBEAT_MEDIUM(0.25f),
+ C2_HEARTBEAT_FAST(0.27f), C2_BREATH_SLOW(0.29f), C2_BREATH_FAST(0.31f), C2_SHOT(0.33f), C2_STROBE(0.35f),
+
+ /* COLOR 1 AND 2 PATTERNS */
+ C1C2_SPARKLE(0.37f), C2C1_SPARKLE(0.39f), C1C2_GRADIENT(0.41f), C1C2_BPM(0.43f), C1C2_BLEND(0.45f), C1C2_TWINKLES(0.51f),
+ C1C2_WAVES(0.53f), C1C2_SINELON(0.55f),
+
+ /* SOLID COLORS */
+ SOLID_PINK_HOT(0.57f), SOLID_RED_DARK(0.59f), SOLID_RED(0.61f), SOLID_RED_ORANGE(0.63f), SOLID_ORANGE(0.65f),
+ SOLID_GOLD(0.67f), SOLID_YELLOW(0.69f), SOLID_GREEN_LAWN(0.71f), SOLID_GREEN_LIME(0.73f), SOLID_GREEN_DARK(0.75f),
+ SOLID_GREEN(0.77f), SOLID_BLUE_GREEN(0.79f), SOLID_BLUE_AQUA(0.81f), SOLID_BLUE_SKY(0.83f), SOLID_BLUE_DARK(0.85f),
+ SOLID_BLUE(0.87f), SOLID_BLUE_VIOLET(0.89f), SOLID_VIOLET(0.91f), SOLID_WHITE(0.93f), SOLID_GRAY(0.95f),
+ SOLID_GRAY_DARK(0.97f), SOLID_BLACK(0.99f);
+
+ /* GETTERS/SETTERS */
+ private final float id;
+ LEDPatterns(float id) {
+ this.id = id;
+ }
+ public float getValue() {
+ return id;
+ }
+}
\ No newline at end of file
diff --git a/src/main/java/frc4388/utility/RobotGyro.java b/src/main/java/frc4388/utility/RobotGyro.java
new file mode 100644
index 0000000..966d2e0
--- /dev/null
+++ b/src/main/java/frc4388/utility/RobotGyro.java
@@ -0,0 +1,269 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package frc4388.utility;
+
+// import com.ctre.phoenix.sensors.WPI_Pigeon2;
+import com.ctre.phoenix6.hardware.Pigeon2;
+import com.kauailabs.navx.frc.AHRS;
+
+// import edu.wpi.first.wpilibj.GyroBase;
+// import edu.wpi.first.wpilibj.interfaces.Gyro;
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.geometry.Rotation2d;
+
+/**
+ * Gyro class that allows for interchangeable use between a pigeon and a navX
+ */
+public class RobotGyro {
+ private RobotTime m_robotTime = RobotTime.getInstance();
+
+ private Pigeon2 m_pigeon = null;
+ private AHRS m_navX = null;
+ public boolean m_isGyroAPigeon; //true if pigeon, false if navX
+
+ private double m_lastPigeonAngle;
+ private double m_deltaPigeonAngle;
+
+ private double pitchZero = 0;
+ private double rollZero = 0;
+
+ /**
+ * Creates a Gyro based on a pigeon
+ * @param gyro the gyroscope to use for Gyro
+ */
+ public RobotGyro(Pigeon2 gyro) {
+ m_pigeon = gyro;
+ m_isGyroAPigeon = true;
+ }
+
+ /**
+ * Creates a Gyro based on a navX
+ * @param gyro the gyroscope to use for Gyro
+ */
+ public RobotGyro(AHRS gyro){
+ m_navX = gyro;
+ m_isGyroAPigeon = false;
+ }
+
+ /**
+ * Resets yaw, pitch, and roll.
+ */
+ public void resetZeroValues() {
+ if (!m_isGyroAPigeon) return;
+
+ // pitchZero = m_pigeon.getPitch();
+ // rollZero = m_pigeon.getRoll();
+ }
+
+ /**
+ * Run in periodic if you are using a pigeon. Updates a delta angle so that it can calculate getRate(). Note
+ * that the getRate() method for a navX will likely be much more accurate than for a pigeon.
+ */
+ public void updatePigeonDeltas() {
+ double currentPigeonAngle = getAngle();
+ m_deltaPigeonAngle = currentPigeonAngle - m_lastPigeonAngle;
+ m_lastPigeonAngle = currentPigeonAngle;
+ }
+
+ /**
+ * NavX:
+ *
Calibrate the gyro by running for a number of samples and computing the center value. Then use
+ * the center value as the Accumulator center value for subsequent measurements. It's important to
+ * make sure that the robot is not moving while the centering calculations are in progress, this
+ * is typically done when the robot is first turned on while it's sitting at rest before the
+ * competition starts.
+ *
+ *
Pigeon:
+ *
Calibrate the gyro by collecting data at a range of tempuratures. Allow pigeon to cool, then boot
+ * into calibration mode. For faster calibration, use a heat lamp to heat up the pigeon. Once the pigeon
+ * has seen a reasonable range of tempuratures, it will exit calibration mode. It's important to
+ * make sure that the robot is not moving while the tempurature calculations are in progress, this
+ * is typically done when the robot is first turned on while it's sitting at rest before the
+ * competition starts.
+ */
+ public void calibrate() {
+ return;
+ // if (m_isGyroAPigeon) {
+ // m_pigeon.calibrate();
+ // } else {
+ // m_navX.calibrate();
+ // }
+ }
+
+ public void reset() {
+ resetZeroValues();
+
+ if (m_isGyroAPigeon) {
+ m_pigeon.setYaw(0);
+ } else {
+ m_navX.reset();
+ }
+
+ }
+
+ public void reset(double val) {
+ resetZeroValues();
+
+ if (m_isGyroAPigeon) {
+ m_pigeon.setYaw(val);
+ } else {
+ m_navX.reset();
+ }
+
+ }
+
+ public void resetFlip() {
+ resetZeroValues();
+
+ if (m_isGyroAPigeon) {
+ m_pigeon.setYaw(180);
+ } else {
+ m_navX.reset();
+ }
+
+ }
+
+ public void resetNinety() {
+ resetZeroValues();
+
+ if (m_isGyroAPigeon) {
+ m_pigeon.setYaw(90);
+ } else {
+ m_navX.reset();
+ }
+
+ }
+
+ public void resetTwoSeventy() {
+ resetZeroValues();
+
+ if (m_isGyroAPigeon) {
+ m_pigeon.setYaw(270);
+ } else {
+ m_navX.reset();
+ }
+
+ }
+
+ public void resetRightSideBlue() {
+ resetZeroValues();
+
+ if (m_isGyroAPigeon) {
+ m_pigeon.setYaw(60);
+ } else {
+ m_navX.reset();
+ }
+
+ }
+
+ public void resetAmpSide() {
+ resetZeroValues();
+
+ if (m_isGyroAPigeon) {
+ m_pigeon.setYaw(-60);
+ } else {
+ m_navX.reset();
+ }
+
+ }
+
+ /**
+ * Get Yaw, Pitch, and Roll data.
+ *
+ * @return ypr_deg Array with yaw[0], pitch[1], and roll[2] data.
+ * Yaw is within [-368,640, +368,640] degrees.
+ * Pitch is within [-90,+90] degrees.
+ * Roll is within [-90,+90] degrees.
+ */
+ private double[] getPigeonAngles() {
+ m_pigeon.getAngle();
+ var rotation = m_pigeon.getRotation3d();
+
+ return new double[] {RobotUnits.radiansToDegrees(rotation.getX() - rollZero), RobotUnits.radiansToDegrees(rotation.getY() - pitchZero), RobotUnits.radiansToDegrees(rotation.getZ())};
+ }
+
+ public Rotation2d getRotation2d() {
+ return m_pigeon.getRotation2d();
+ }
+
+ public double getAngle() {
+ if (m_isGyroAPigeon) {
+ return getPigeonAngles()[2];
+ } else {
+ return m_navX.getAngle();
+ }
+ }
+
+ public double getYaw() {
+ return this.getAngle();
+ }
+
+ /**
+ * Gets an absolute heading of the robot
+ * @return heading from -180 to 180 degrees
+ */
+ public double getHeading() {
+ return getHeading(getAngle());
+ }
+
+ /**
+ * Gets an absolute heading of the robot
+ * @return heading from -180 to 180 degrees
+ */
+ public double getHeading(double angle) {
+ return Math.IEEEremainder(angle, 360);
+ }
+
+ /**
+ * Returns the current pitch value (in degrees, from -90 to 90)
+ * reported by the sensor. Pitch is a measure of rotation around
+ * the Y Axis.
+ * @return The current pitch value in degrees (-90 to 90).
+ */
+ public double getPitch() {
+ if (m_isGyroAPigeon) {
+ return MathUtil.clamp(getPigeonAngles()[1], -90, 90);
+ } else {
+ return MathUtil.clamp(m_navX.getPitch(), -90, 90);
+ }
+ }
+
+ /**
+ * Returns the current roll value (in degrees, from -90 to 90)
+ * reported by the sensor. Roll is a measure of rotation around
+ * the X Axis.
+ * @return The current roll value in degrees (-90 to 90).
+ */
+ public double getRoll() {
+ if (m_isGyroAPigeon) {
+ return MathUtil.clamp(getPigeonAngles()[2], -90, 90);
+ } else {
+ return MathUtil.clamp(m_navX.getRoll(), -90, 90);
+ }
+ }
+
+ public double getRate() {
+ if (m_isGyroAPigeon) {
+ return m_deltaPigeonAngle / m_robotTime.m_deltaTime * 1000;
+ } else {
+ return m_navX.getRate();
+ }
+ }
+
+ public Pigeon2 getPigeon(){
+ return m_pigeon;
+ }
+
+ public AHRS getNavX(){
+ return m_navX;
+ }
+
+ public void close() throws Exception {
+
+ }
+}
diff --git a/src/main/java/frc4388/utility/RobotTime.java b/src/main/java/frc4388/utility/RobotTime.java
new file mode 100644
index 0000000..694f850
--- /dev/null
+++ b/src/main/java/frc4388/utility/RobotTime.java
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package frc4388.utility;
+
+/**
+ *
Keeps track of Robot times like time passed, delta time, etc
+ *
All times are in milliseconds
+ */
+public class RobotTime {
+ private long m_currTime = System.currentTimeMillis();
+ public long m_deltaTime = 0;
+
+ private long m_startRobotTime = m_currTime;
+ public long m_robotTime = 0;
+ public long m_lastRobotTime = 0;
+
+ private long m_startMatchTime = 0;
+ public long m_matchTime = 0;
+ public long m_lastMatchTime = 0;
+
+ public long m_frameNumber = 0;
+
+ /**
+ * Private constructor prevents other classes from instantiating
+ */
+ private RobotTime(){}
+
+ private static RobotTime instance = null;
+
+ /**
+ * Gets the instance of Robot Time. If there is no instance running one will be created.
+ * @return instance of Robot Time
+ */
+ public static RobotTime getInstance() {
+ if (instance == null) {
+ instance = new RobotTime();
+ }
+ return instance;
+ }
+
+ /**
+ * Call this once per periodic loop.
+ */
+ public void updateTimes() {
+ m_lastRobotTime = m_robotTime;
+ m_lastMatchTime = m_matchTime;
+
+ m_currTime = System.currentTimeMillis();
+ m_robotTime = m_currTime - m_startRobotTime;
+ m_deltaTime = m_robotTime - m_lastRobotTime;
+ m_frameNumber++;
+
+ if (m_startMatchTime != 0) {
+ m_matchTime = m_currTime - m_startMatchTime;
+ }
+ }
+
+ /**
+ * Call this in both the auto and periodic inits
+ */
+ public void startMatchTime() {
+ if (m_startMatchTime == 0) {
+ m_startMatchTime = m_currTime;
+ }
+ }
+
+ /**
+ * Call this in disabled init
+ */
+ public void endMatchTime() {
+ m_startMatchTime = 0;
+ m_matchTime = 0;
+ }
+}
diff --git a/src/main/java/frc4388/utility/RobotUnits.java b/src/main/java/frc4388/utility/RobotUnits.java
new file mode 100644
index 0000000..9e07312
--- /dev/null
+++ b/src/main/java/frc4388/utility/RobotUnits.java
@@ -0,0 +1,27 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+package frc4388.utility;
+
+/** Aarav's good units class (better than WPILib)
+ * @author Aarav Shah */
+
+public class RobotUnits {
+ // constants
+
+ // angle conversions
+ public static double degreesToRadians(final double degrees) {return degrees * Math.PI / 180;}
+
+ public static double radiansToDegrees(final double radians) {return radians / Math.PI * 180;}
+
+ // falcon conversions
+ public static double falconTicksToRotations(final double ticks) {return ticks / 2048;}
+
+ public static double falconRotationsToTicks(final double rotations) {return rotations * 2048;}
+
+ // distance conversions
+ public static double metersToFeet(final double meters) {return meters * 3.28084;}
+
+ public static double feetToMeters(final double feet) {return feet / 3.28084;}
+}
\ No newline at end of file
diff --git a/src/main/java/frc4388/utility/UtilityStructs.java b/src/main/java/frc4388/utility/UtilityStructs.java
new file mode 100644
index 0000000..935dbbe
--- /dev/null
+++ b/src/main/java/frc4388/utility/UtilityStructs.java
@@ -0,0 +1,26 @@
+package frc4388.utility;
+
+public class UtilityStructs {
+ public static class TimedOutput {
+ public double leftX = 0.0;
+ public double leftY = 0.0;
+ public double rightX = 0.0;
+ public double rightY = 0.0;
+
+ public boolean OPLB;
+ public boolean OPRB;
+
+
+ public long timedOffset = 0;
+ }
+ public static class AutoRecordingControllerFrame {
+ public double[] axes = new double[6];
+ public short button = 0;
+ public short[] POV = new short[1];
+
+ }
+ public static class AutoRecordingFrame {
+ public AutoRecordingControllerFrame[] controllerFrames = new AutoRecordingControllerFrame[2];
+ public int timeStamp;
+ }
+}
diff --git a/src/main/java/frc4388/utility/configurable/ConfigurableDouble.java b/src/main/java/frc4388/utility/configurable/ConfigurableDouble.java
new file mode 100644
index 0000000..c0384db
--- /dev/null
+++ b/src/main/java/frc4388/utility/configurable/ConfigurableDouble.java
@@ -0,0 +1,23 @@
+package frc4388.utility.configurable;
+
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+public class ConfigurableDouble {
+ private double defualtValue;
+ private String name;
+
+ /**
+ * Creates an new ConfigurableDouble through Smart Dashboard.
+ * @param name the name of the Smart Dashboard key.
+ * @param defualtValue the initilization value
+ */
+ public ConfigurableDouble(String name, double defualtValue) {
+ this.name = name;
+ this.defualtValue = defualtValue;
+ SmartDashboard.putNumber(name, defualtValue);
+ }
+
+ public double get() {
+ return SmartDashboard.getNumber(name, defualtValue);
+ }
+}
diff --git a/src/main/java/frc4388/utility/configurable/ConfigurableString.java b/src/main/java/frc4388/utility/configurable/ConfigurableString.java
new file mode 100644
index 0000000..34c0290
--- /dev/null
+++ b/src/main/java/frc4388/utility/configurable/ConfigurableString.java
@@ -0,0 +1,23 @@
+package frc4388.utility.configurable;
+
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+public class ConfigurableString {
+ private String defualtValue;
+ private String name;
+
+ /**
+ * Creates an new ConfigurableString through Smart Dashboard.
+ * @param name the name of the Smart Dashboard key.
+ * @param defualtValue the initilization value
+ */
+ public ConfigurableString(String name, String defualtValue) {
+ this.name = name;
+ this.defualtValue = defualtValue;
+ SmartDashboard.putString(name, defualtValue);
+ }
+
+ public String get() {
+ return SmartDashboard.getString(name, defualtValue);
+ }
+}
diff --git a/src/main/java/frc4388/utility/controller/DeadbandedXboxController.java b/src/main/java/frc4388/utility/controller/DeadbandedXboxController.java
new file mode 100644
index 0000000..4577a2e
--- /dev/null
+++ b/src/main/java/frc4388/utility/controller/DeadbandedXboxController.java
@@ -0,0 +1,27 @@
+package frc4388.utility.controller;
+
+import static frc4388.robot.Constants.OIConstants.LEFT_AXIS_DEADBAND;
+
+import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.wpilibj.XboxController;
+
+public class DeadbandedXboxController extends XboxController {
+ public DeadbandedXboxController(int port) { super(port); }
+
+ @Override public double getLeftX() { return getLeft().getX(); }
+ @Override public double getLeftY() { return getLeft().getY(); }
+ @Override public double getRightX() { return getRight().getX(); }
+ @Override public double getRightY() { return getRight().getY(); }
+
+ public Translation2d getLeft() { return skewToDeadzonedCircle(super.getLeftX(), super.getLeftY()); }
+ public Translation2d getRight() { return skewToDeadzonedCircle(-super.getRightX(), super.getRightY()); }
+
+ public static Translation2d skewToDeadzonedCircle(double x, double y) {
+ Translation2d translation2d = new Translation2d(x, y);
+ double magnitude = translation2d.getNorm();
+
+ if (magnitude < LEFT_AXIS_DEADBAND) return new Translation2d(0,0);
+
+ return translation2d;
+ }
+}
\ No newline at end of file
diff --git a/src/main/java/frc4388/utility/controller/IHandController.java b/src/main/java/frc4388/utility/controller/IHandController.java
new file mode 100644
index 0000000..13aa763
--- /dev/null
+++ b/src/main/java/frc4388/utility/controller/IHandController.java
@@ -0,0 +1,21 @@
+package frc4388.utility.controller;
+
+/**
+ * Add your docs here.
+ */
+public interface IHandController {
+
+ public double getLeftXAxis();
+
+ public double getLeftYAxis();
+
+ public double getRightXAxis();
+
+ public double getRightYAxis();
+
+ public double getLeftTriggerAxis();
+
+ public double getRightTriggerAxis();
+
+ public int getDpadAngle();
+}
diff --git a/src/main/java/frc4388/utility/controller/VirtualController.java b/src/main/java/frc4388/utility/controller/VirtualController.java
new file mode 100644
index 0000000..85adb64
--- /dev/null
+++ b/src/main/java/frc4388/utility/controller/VirtualController.java
@@ -0,0 +1,145 @@
+package frc4388.utility.controller;
+
+import edu.wpi.first.wpilibj.GenericHID;
+
+/**
+ * A virtual controller that can be bound like an standard controller.
+ * @author Zachary Wilke
+ */
+public class VirtualController extends GenericHID {
+ private short m_buttonStates = 0;
+ private short m_buttonStatesLastFrame = 0;
+ private double[] m_axes = new double[6];
+ private short[] m_pov = new short[1];
+
+ /**
+ * Create an virtual controller
+ * @param port virtual port (merely a formality).
+ */
+ public VirtualController(int port) {
+ super(port);
+ }
+
+ /**
+ * Set the curent inputs to the new frames.
+ * @param axes joystick axes, (i.e. joysticks and triggers).
+ * @param buttonFlags the bit packed button states.
+ * @param pov the array of dpads.
+ */
+ public void setFrame(double[] axes, short buttonFlags, short[] pov) {
+ m_axes = axes;
+ setOutputs(buttonFlags);
+ m_pov = pov;
+ }
+
+ /**
+ * Zero outs the controls.
+ */
+ public void zeroControls() {
+ m_axes = new double[6];
+ m_buttonStates = 0;
+ m_buttonStatesLastFrame = 0;
+ m_pov = new short[] {-1};
+ }
+
+ /**
+ * Gets the value of a bitflag from an int
+ * @param value int to search
+ * @param index index of bit
+ * @return if the bit is set
+ */
+ public static boolean getFlag(int value, int index) {
+ return ((value & 1 << index) != 0);
+ }
+
+ @Override
+ public boolean getRawButton(int button) { // man why are buttons indexed at 1.
+ return getFlag(m_buttonStates, button - 1);
+ }
+
+ @Override
+ public boolean getRawButtonPressed(int button) {
+ return (!getFlag(m_buttonStatesLastFrame, button - 1) && getRawButton(button));
+ }
+
+ @Override
+ public boolean getRawButtonReleased(int button) {
+ return (getFlag(m_buttonStatesLastFrame, button - 1) && !getRawButton(button));
+ }
+
+ @Override
+ public double getRawAxis(int axis) {
+ return m_axes[axis];
+ }
+
+ @Override
+ public int getPOV(int pov) {
+ return m_pov[pov];
+ }
+
+ @Override
+ public int getAxisCount() {
+ return m_axes.length;
+ }
+
+ @Override
+ public int getPOVCount() {
+ return m_pov.length;
+ }
+
+ @Override
+ public int getButtonCount() {
+ return 10;
+ }
+
+ @Override
+ public boolean isConnected() {
+ return true;
+ }
+
+ @Override
+ public HIDType getType() {
+ return HIDType.kXInputGamepad;
+ }
+
+ @Override
+ public String getName() {
+ return "Virtual Controller";
+ }
+
+ @Override
+ public int getAxisType(int axis) {
+ return 1; /* ! Warning, does not return accurate data.
+ Hopefully this isn't a problem */
+ }
+
+ /**
+ * Use {@link VirtualController#setFrame} or {@link VirtualController#setOutputs}.
+ * this is an no-op overide.
+ */
+ @Override
+ public void setOutput(int outputNumber, boolean value) {
+ // do not use
+ //m_buttonStatesLastFrame[outputNumber - 1] = m_buttonStates[outputNumber - 1];
+ //m_buttonStates[outputNumber - 1] = value;
+ }
+
+ /**
+ * Set buttons from a packed int, if you want to set joysticks and dpad use {@link VirtualController#SetFrame}
+ */
+ @Override
+ public void setOutputs(int value) {
+ m_buttonStatesLastFrame = m_buttonStates;
+ m_buttonStates = (short) value;
+ }
+
+ /**
+ * Why are you Setting rumble on an virtual controller?
+ * @param type the rumble type (even though it won't do anything)
+ * @param value the rumble strength (always multiplyed by 0.0)
+ */
+ @Override
+ public void setRumble(RumbleType type, double value) {
+ System.out.println("Why are you Setting rumble on an virtual controller?");
+ }
+}
\ No newline at end of file
diff --git a/src/main/java/frc4388/utility/controller/XboxController.java b/src/main/java/frc4388/utility/controller/XboxController.java
new file mode 100644
index 0000000..8b8f0f8
--- /dev/null
+++ b/src/main/java/frc4388/utility/controller/XboxController.java
@@ -0,0 +1,218 @@
+package frc4388.utility.controller;
+
+import edu.wpi.first.wpilibj.Joystick;
+
+/**
+ * This is a wrapper for the WPILib Joystick class that represents an XBox
+ * controller.
+ * @author frc1675
+ */
+public class XboxController implements IHandController
+{
+ public static final int LEFT_X_AXIS = 0;
+ public static final int LEFT_Y_AXIS = 1;
+ public static final int LEFT_TRIGGER_AXIS = 2;
+ public static final int RIGHT_TRIGGER_AXIS = 3;
+ public static final int RIGHT_X_AXIS = 4;
+ public static final int RIGHT_Y_AXIS = 5;
+ public static final int LEFT_RIGHT_DPAD_AXIS = 6;
+ public static final int TOP_BOTTOM_DPAD_AXIS = 6;
+
+ public static final int A_BUTTON = 1;
+ public static final int B_BUTTON = 2;
+ public static final int X_BUTTON = 3;
+ public static final int Y_BUTTON = 4;
+ public static final int LEFT_BUMPER_BUTTON = 5;
+ public static final int RIGHT_BUMPER_BUTTON = 6;
+ public static final int BACK_BUTTON = 7;
+ public static final int START_BUTTON = 8;
+
+ public static final int LEFT_JOYSTICK_BUTTON = 9;
+ public static final int RIGHT_JOYSTICK_BUTTON = 10;
+
+ private static final double LEFT_DPAD_TOLERANCE = -0.9;
+ private static final double RIGHT_DPAD_TOLERANCE = 0.9;
+ private static final double BOTTOM_DPAD_TOLERANCE = -0.9;
+ private static final double TOP_DPAD_TOLERANCE = 0.9;
+
+ private static final double LEFT_TRIGGER_TOLERANCE = 0.5;
+ private static final double RIGHT_TRIGGER_TOLERANCE = 0.5;
+
+ private static final double RIGHT_AXIS_UP_TOLERANCE = -0.9;
+ private static final double RIGHT_AXIS_DOWN_TOLERANCE = 0.9;
+ private static final double RIGHT_AXIS_RIGHT_TOLERANCE = 0.9;
+ private static final double RIGHT_AXIS_LEFT_TOLERANCE = -0.9;
+
+ private static final double LEFT_AXIS_UP_TOLERANCE = -0.9;
+ private static final double LEFT_AXIS_DOWN_TOLERANCE = 0.9;
+ private static final double LEFT_AXIS_RIGHT_TOLERANCE = 0.9;
+ private static final double LEFT_AXIS_LEFT_TOLERANCE = -0.9;
+
+ private static final double DEADZONE = 0.1;
+
+ private Joystick m_stick;
+
+ /**
+ * Add your docs here.
+ */
+ public XboxController(int portNumber){
+ m_stick = new Joystick(portNumber);
+ }
+
+ /**
+ * Add your docs here.
+ */
+ public Joystick getJoyStick() {
+ return m_stick;
+ }
+
+ /**
+ * Checks if the input falls within the deadzone.
+ * @param input from an axis on the controller
+ * @return true if input falls in deadzone, false if input falls outside deadzone
+ */
+ private boolean inDeadZone(double input){
+ return (Math.abs(input) < DEADZONE);
+ }
+
+ /**
+ * Updates an input to have a deadzone around the 0 position
+ * @param input from an axis on the controller
+ * @return updated input
+ */
+ private double getAxisWithDeadZoneCheck(double input){
+ if(inDeadZone(input)){
+ return 0.0;
+ } else {
+ return input;
+ }
+ }
+
+ public boolean getAButton(){
+ return m_stick.getRawButton(A_BUTTON);
+ }
+
+ public boolean getXButton(){
+ return m_stick.getRawButton(X_BUTTON);
+ }
+
+ public boolean getBButton(){
+ return m_stick.getRawButton(B_BUTTON);
+ }
+
+ public boolean getYButton(){
+ return m_stick.getRawButton(Y_BUTTON);
+ }
+
+ public boolean getBackButton(){
+ return m_stick.getRawButton(BACK_BUTTON);
+ }
+
+ public boolean getStartButton(){
+ return m_stick.getRawButton(START_BUTTON);
+ }
+
+ public boolean getLeftBumperButton(){
+ return m_stick.getRawButton(LEFT_BUMPER_BUTTON);
+ }
+
+ public boolean getRightBumperButton(){
+ return m_stick.getRawButton(RIGHT_BUMPER_BUTTON);
+ }
+
+ public boolean getLeftJoystickButton(){
+ return m_stick.getRawButton(LEFT_JOYSTICK_BUTTON);
+ }
+
+ public boolean getRightJoystickButton(){
+ return m_stick.getRawButton(RIGHT_JOYSTICK_BUTTON);
+ }
+
+ public double getLeftXAxis(){
+ return getAxisWithDeadZoneCheck(m_stick.getRawAxis(LEFT_X_AXIS));
+ }
+
+ public double getLeftYAxis(){
+ return getAxisWithDeadZoneCheck(m_stick.getRawAxis(LEFT_Y_AXIS));
+ }
+
+ public double getRightXAxis(){
+ return getAxisWithDeadZoneCheck(m_stick.getRawAxis(RIGHT_X_AXIS));
+ }
+
+ public double getRightYAxis(){
+ return getAxisWithDeadZoneCheck(m_stick.getRawAxis(RIGHT_Y_AXIS));
+ }
+
+ public double getLeftTriggerAxis(){
+ return getAxisWithDeadZoneCheck(m_stick.getRawAxis(LEFT_TRIGGER_AXIS));
+ }
+
+ public double getRightTriggerAxis(){
+ return getAxisWithDeadZoneCheck(m_stick.getRawAxis(RIGHT_TRIGGER_AXIS));
+ }
+
+ /**
+ * Get the angle input from the dpad.
+ * @return -1 if nothing is pressed, or the angle of the button pressed. 0 = up, 90 = right, etc.
+ */
+ public int getDpadAngle() {
+ return m_stick.getPOV(0);
+ }
+
+ public boolean getDPadLeft(){
+ return (m_stick.getRawAxis(LEFT_RIGHT_DPAD_AXIS) < LEFT_DPAD_TOLERANCE);
+ }
+
+ public boolean getDPadRight(){
+ return (m_stick.getRawAxis(LEFT_RIGHT_DPAD_AXIS) > RIGHT_DPAD_TOLERANCE);
+ }
+
+ public boolean getDPadTop(){
+ return (m_stick.getRawAxis(TOP_BOTTOM_DPAD_AXIS) < TOP_DPAD_TOLERANCE);
+ }
+
+ public boolean getDPadBottom(){
+ return (m_stick.getRawAxis(TOP_BOTTOM_DPAD_AXIS) > BOTTOM_DPAD_TOLERANCE);
+ }
+
+ public boolean getLeftTrigger(){
+ return (getLeftTriggerAxis() > LEFT_TRIGGER_TOLERANCE);
+ }
+
+ public boolean getRightTrigger(){
+ return (getRightTriggerAxis() > RIGHT_TRIGGER_TOLERANCE);
+ }
+
+ public boolean getRightAxisUpTrigger(){
+ return (getRightYAxis() < RIGHT_AXIS_UP_TOLERANCE);
+ }
+
+ public boolean getRightAxisDownTrigger(){
+ return (getRightYAxis() > RIGHT_AXIS_DOWN_TOLERANCE);
+ }
+
+ public boolean getRightAxisLeftTrigger(){
+ return (getRightXAxis() > RIGHT_AXIS_LEFT_TOLERANCE);
+ }
+
+ public boolean getRightAxisRightTrigger(){
+ return (getRightXAxis() > RIGHT_AXIS_RIGHT_TOLERANCE);
+ }
+
+ public boolean getLeftAxisUpTrigger(){
+ return (getLeftYAxis() < LEFT_AXIS_UP_TOLERANCE);
+ }
+
+ public boolean getLeftAxisDownTrigger(){
+ return (getLeftYAxis() > LEFT_AXIS_DOWN_TOLERANCE);
+ }
+
+ public boolean getLeftAxisLeftTrigger(){
+ return (getLeftXAxis() > LEFT_AXIS_LEFT_TOLERANCE);
+ }
+
+ public boolean getLeftAxisRightTrigger(){
+ return (getLeftXAxis() > LEFT_AXIS_RIGHT_TOLERANCE);
+ }
+}
\ No newline at end of file
diff --git a/src/main/java/frc4388/utility/controller/XboxTriggerButton.java b/src/main/java/frc4388/utility/controller/XboxTriggerButton.java
new file mode 100644
index 0000000..0a56841
--- /dev/null
+++ b/src/main/java/frc4388/utility/controller/XboxTriggerButton.java
@@ -0,0 +1,68 @@
+package frc4388.utility.controller;
+
+//import edu.wpi.first.wpilibj2.command.button.Trigger;
+
+/**
+ * Mapping for the Xbox controller triggers to allow triggers to be defined as
+ * buttons in {@link frc4388.robot.OI}. Checks to see if the given trigger
+ * exceeds a tolerance defined in {@link XboxController}.
+ */
+public class XboxTriggerButton {//extends Trigger {
+ public static final int RIGHT_TRIGGER = 0;
+ public static final int LEFT_TRIGGER = 1;
+ public static final int RIGHT_AXIS_UP_TRIGGER = 2;
+ public static final int RIGHT_AXIS_DOWN_TRIGGER = 3;
+ public static final int RIGHT_AXIS_RIGHT_TRIGGER = 4;
+ public static final int RIGHT_AXIS_LEFT_TRIGGER = 5;
+ public static final int LEFT_AXIS_UP_TRIGGER = 6;
+ public static final int LEFT_AXIS_DOWN_TRIGGER = 7;
+ public static final int LEFT_AXIS_RIGHT_TRIGGER = 8;
+ public static final int LEFT_AXIS_LEFT_TRIGGER = 9;
+
+ private XboxController m_controller;
+ private int m_trigger;
+
+ /**
+ * Creates a Trigger-Button mapped to a specific Xbox controller and trigger
+ */
+ public XboxTriggerButton(XboxController controller, int trigger) {
+ m_controller = controller;
+ m_trigger = trigger;
+ }
+
+ /** {@inheritDoc} */
+ // @Override
+ public boolean get() {
+ if (m_trigger == RIGHT_TRIGGER) {
+ return m_controller.getRightTrigger();
+ }
+ else if (m_trigger == LEFT_TRIGGER) {
+ return m_controller.getLeftTrigger();
+ }
+ else if (m_trigger == RIGHT_AXIS_UP_TRIGGER) {
+ return m_controller.getRightAxisUpTrigger();
+ }
+ else if (m_trigger == RIGHT_AXIS_DOWN_TRIGGER) {
+ return m_controller.getRightAxisDownTrigger();
+ }
+ else if (m_trigger == RIGHT_AXIS_RIGHT_TRIGGER) {
+ return m_controller.getRightAxisRightTrigger();
+ }
+ else if (m_trigger == RIGHT_AXIS_LEFT_TRIGGER) {
+ return m_controller.getRightAxisLeftTrigger();
+ }
+ else if (m_trigger == LEFT_AXIS_UP_TRIGGER) {
+ return m_controller.getLeftAxisUpTrigger();
+ }
+ else if (m_trigger == LEFT_AXIS_DOWN_TRIGGER) {
+ return m_controller.getLeftAxisDownTrigger();
+ }
+ else if (m_trigger == LEFT_AXIS_RIGHT_TRIGGER) {
+ return m_controller.getLeftAxisRightTrigger();
+ }
+ else if (m_trigger == LEFT_AXIS_LEFT_TRIGGER) {
+ return m_controller.getLeftAxisLeftTrigger();
+ }
+ return false;
+ }
+}
diff --git a/src/test/java/frc4388/mocks/MockPigeonIMU.java.old b/src/test/java/frc4388/mocks/MockPigeonIMU.java.old
new file mode 100644
index 0000000..ecddde7
--- /dev/null
+++ b/src/test/java/frc4388/mocks/MockPigeonIMU.java.old
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package frc4388.mocks;
+
+import com.ctre.phoenix.ErrorCode;
+import com.ctre.phoenix.sensors.PigeonIMU;
+
+/**
+ * Add your docs here.
+ */
+public class MockPigeonIMU extends PigeonIMU {
+ public int m_deviceNumber;
+ public double currentYaw;
+ public double currentPitch;
+ public double currentRoll;
+
+ public MockPigeonIMU(int deviceNumber) {
+ super(deviceNumber);
+ m_deviceNumber = deviceNumber;
+ }
+
+ @Override
+ public ErrorCode setYaw(double angleDeg) {
+ currentYaw = angleDeg;
+ return ErrorCode.OK;
+ }
+
+ /**
+ * @param currentPitch the Pitch to set
+ */
+ public void setCurrentPitch(double currentPitch) {
+ this.currentPitch = currentPitch;
+ }
+
+ /**
+ * @param currentRoll the Roll to set
+ */
+ public void setCurrentRoll(double currentRoll) {
+ this.currentRoll = currentRoll;
+ }
+
+ @Override
+ public ErrorCode getYawPitchRoll(double[] ypr_deg) {
+ ypr_deg[0] = currentYaw;
+ ypr_deg[1] = currentPitch;
+ ypr_deg[2] = currentRoll;
+ return ErrorCode.OK;
+ }
+}
diff --git a/src/test/java/frc4388/robot/subsystems/LEDSubsystemTest.old b/src/test/java/frc4388/robot/subsystems/LEDSubsystemTest.old
new file mode 100644
index 0000000..8fcbf53
--- /dev/null
+++ b/src/test/java/frc4388/robot/subsystems/LEDSubsystemTest.old
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package frc4388.robot.subsystems;
+
+import static org.junit.Assert.assertEquals;
+import static org.mockito.Mockito.mock;
+
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.*;
+import frc4388.robot.Constants.LEDConstants;
+import frc4388.utility.LEDPatterns;
+
+/**
+ * Add your docs here.
+ */
+public class LEDSubsystemTest {
+ @Test
+ public void testConstructor() {
+ // Arrange
+ Spark ledController = mock(Spark.class);
+
+ // Act
+ LED led = new LED(ledController);
+
+ // Assert
+ assertEquals(LEDConstants.DEFAULT_PATTERN.getValue(), led.getPattern().getValue(), 0.0001);
+ }
+
+ @Test
+ public void testPatterns() {
+ // Arrange
+ Spark ledController = mock(Spark.class);
+ LED led = new LED(ledController);
+
+ // Act
+ led.setPattern(LEDPatterns.RAINBOW_RAINBOW);
+
+ // Assert
+ assertEquals(LEDPatterns.RAINBOW_RAINBOW.getValue(), led.getPattern().getValue(), 0.0001);
+
+ // Act
+ led.setPattern(LEDPatterns.BLUE_BREATH);
+
+ // Assert
+ assertEquals(LEDPatterns.BLUE_BREATH.getValue(), led.getPattern().getValue(), 0.0001);
+
+ // Act
+ led.setPattern(LEDPatterns.SOLID_BLACK);
+
+ // Assert
+ assertEquals(LEDPatterns.SOLID_BLACK.getValue(), led.getPattern().getValue(), 0.0001);
+ }
+}
diff --git a/src/test/java/frc4388/utility/RobotGyroUtilityTest.old b/src/test/java/frc4388/utility/RobotGyroUtilityTest.old
new file mode 100644
index 0000000..8c0b1e5
--- /dev/null
+++ b/src/test/java/frc4388/utility/RobotGyroUtilityTest.old
@@ -0,0 +1,184 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package frc4388.utility;
+
+import static org.junit.Assert.*;
+import static org.mockito.Mockito.*;
+
+import com.kauailabs.navx.frc.AHRS;
+
+import org.junit.*;
+
+import frc4388.mocks.MockPigeonIMU;
+import frc4388.robot.Constants.DriveConstants;
+
+/**
+ * Add your docs here.
+ */
+public class RobotGyroUtilityTest {
+ // TODO UNTESTED: most functions for NavX
+
+ private RobotGyro gyroPigeon;
+ private RobotGyro gyroNavX;
+
+ @Test
+ public void testConstructor() {
+ // Arrange
+ MockPigeonIMU pigeon = new MockPigeonIMU(DriveConstants.DRIVE_PIGEON_ID);
+ AHRS navX = mock(AHRS.class);
+ gyroPigeon = new RobotGyro(pigeon);
+ gyroNavX = new RobotGyro(navX);
+
+ // Assert
+ assertEquals(true, gyroPigeon.m_isGyroAPigeon);
+ assertEquals(pigeon, gyroPigeon.getPigeon());
+ assertEquals(null, gyroPigeon.getNavX());
+ assertEquals(false, gyroNavX.m_isGyroAPigeon);
+ assertEquals(navX, gyroNavX.getNavX());
+ assertEquals(null, gyroNavX.getPigeon());
+ }
+
+ @Test
+ public void testHeadingPigeon() {
+ // Arrange
+ MockPigeonIMU pigeon = new MockPigeonIMU(DriveConstants.DRIVE_PIGEON_ID);
+ gyroPigeon = new RobotGyro(pigeon);
+
+ // Act & Assert
+ assertEquals(-90, gyroPigeon.getHeading(270), 0.0001);
+ assertEquals(-45, gyroPigeon.getHeading(315), 0.0001);
+ assertEquals(-60, gyroPigeon.getHeading(-60), 0.0001);
+ assertEquals(30, gyroPigeon.getHeading(30), 0.0001);
+ assertEquals(0, gyroPigeon.getHeading(0), 0.0001);
+ assertEquals(180, gyroPigeon.getHeading(180), 0.0001);
+ assertEquals(-180, gyroPigeon.getHeading(-180), 0.0001);
+ assertEquals(97, gyroPigeon.getHeading(1537), 0.0001);
+ assertEquals(99, gyroPigeon.getHeading(-2781), 0.0001);
+ }
+
+ @Test
+ public void testYawPitchRollPigeon() {
+ // Arrange
+ MockPigeonIMU pigeon = new MockPigeonIMU(DriveConstants.DRIVE_PIGEON_ID);
+ gyroPigeon = new RobotGyro(pigeon);
+
+ // Assert
+ assertEquals(0, gyroPigeon.getAngle(), 0.0001);
+
+ // Act
+ pigeon.setYaw(40);
+
+ // Assert
+ assertEquals(40, gyroPigeon.getAngle(), 0.0001);
+
+ // Act
+ gyroPigeon.reset();
+
+ // Assert
+ assertEquals(0, gyroPigeon.getAngle(), 0.0001);
+
+ // Act
+ pigeon.setYaw(-1457);
+ pigeon.setCurrentPitch(100);
+ pigeon.setCurrentRoll(100);
+
+ // Assert
+ assertEquals(-1457, gyroPigeon.getAngle(), 0.0001);
+ assertEquals(90, gyroPigeon.getPitch(), 0.0001);
+ assertEquals(90, gyroPigeon.getRoll(), 0.0001);
+
+ // Act
+ pigeon.setCurrentPitch(45);
+ pigeon.setCurrentRoll(45);
+
+ // Assert
+ assertEquals(45, gyroPigeon.getPitch(), 0.0001);
+ assertEquals(45, gyroPigeon.getRoll(), 0.0001);
+
+ // Act
+ pigeon.setCurrentPitch(0);
+ pigeon.setCurrentRoll(0);
+
+ // Assert
+ assertEquals(0, gyroPigeon.getPitch(), 0.0001);
+ assertEquals(0, gyroPigeon.getRoll(), 0.0001);
+
+ // Act
+ pigeon.setCurrentPitch(-60);
+ pigeon.setCurrentRoll(-60);
+
+ // Assert
+ assertEquals(-60, gyroPigeon.getPitch(), 0.0001);
+ assertEquals(-60, gyroPigeon.getRoll(), 0.0001);
+
+ // Act
+ pigeon.setCurrentPitch(-90);
+ pigeon.setCurrentRoll(-90);
+
+ // Assert
+ assertEquals(-90, gyroPigeon.getPitch(), 0.0001);
+ assertEquals(-90, gyroPigeon.getRoll(), 0.0001);
+
+ // Act
+ pigeon.setCurrentPitch(-100);
+ pigeon.setCurrentRoll(-100);
+
+ // Assert
+ assertEquals(-90, gyroPigeon.getPitch(), 0.0001);
+ assertEquals(-90, gyroPigeon.getRoll(), 0.0001);
+ }
+
+ @Test
+ public void testRatesPigeon() {
+ // Arrange
+ MockPigeonIMU pigeon = new MockPigeonIMU(DriveConstants.DRIVE_PIGEON_ID);
+ gyroPigeon = new RobotGyro(pigeon);
+ RobotTime robotTime = RobotTime.getInstance();
+ gyroPigeon.updatePigeonDeltas();
+
+ // Act
+ robotTime.m_deltaTime = 5;
+ pigeon.setYaw(0);
+ gyroPigeon.updatePigeonDeltas();
+
+ // Assert
+ assertEquals(0, gyroPigeon.getRate(), 1);
+
+ // Act
+ robotTime.m_deltaTime = 5;
+ pigeon.setYaw(90);
+ gyroPigeon.updatePigeonDeltas();
+
+ // Assert
+ assertEquals(18000, gyroPigeon.getRate(), 0.001);
+
+ // Act
+ robotTime.m_deltaTime = 5;
+ pigeon.setYaw(90);
+ gyroPigeon.updatePigeonDeltas();
+
+ // Assert
+ assertEquals(0, gyroPigeon.getRate(), 0.001);
+
+ // Act
+ robotTime.m_deltaTime = 3;
+ pigeon.setYaw(-30);
+ gyroPigeon.updatePigeonDeltas();
+
+ // Assert
+ assertEquals(-40000, gyroPigeon.getRate(), 0.001);
+
+ // Act
+ robotTime.m_deltaTime = 6;
+ pigeon.setYaw(690);
+ gyroPigeon.updatePigeonDeltas();
+
+ // Assert
+ assertEquals(120000, gyroPigeon.getRate(), 0.001);
+ }
+}
diff --git a/src/test/java/frc4388/utility/RobotTimeUtilityTest.old b/src/test/java/frc4388/utility/RobotTimeUtilityTest.old
new file mode 100644
index 0000000..2c31a34
--- /dev/null
+++ b/src/test/java/frc4388/utility/RobotTimeUtilityTest.old
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package frc4388.utility;
+
+import static org.junit.Assert.*;
+
+import org.junit.*;
+
+/**
+ * Add your docs here.
+ */
+public class RobotTimeUtilityTest {
+ RobotTime robotTime = RobotTime.getInstance();
+
+ @Test
+ public void testUpdateTimes() {
+ // Arrange
+ long lastTime;
+ robotTime.m_deltaTime = 0;
+ robotTime.m_robotTime = 0;
+ robotTime.m_lastRobotTime = 0;
+ robotTime.m_frameNumber = 0;
+ robotTime.endMatchTime();
+ robotTime.m_lastMatchTime = 0;
+
+ // Assert
+ assertEquals(0, robotTime.m_deltaTime);
+ assertEquals(0, robotTime.m_robotTime);
+ assertEquals(0, robotTime.m_lastRobotTime);
+ assertEquals(0, robotTime.m_frameNumber);
+ lastTime = robotTime.m_robotTime;
+
+ // Act
+ wait(1);
+ robotTime.updateTimes();
+
+ // Assert
+ assertEquals(true, robotTime.m_deltaTime > 0);
+ assertEquals(true, robotTime.m_robotTime > 0);
+ assertEquals(lastTime, robotTime.m_lastRobotTime);
+ assertEquals(1, robotTime.m_frameNumber);
+ lastTime = robotTime.m_robotTime;
+
+ // Act
+ wait(1);
+ robotTime.updateTimes();
+
+ // Assert
+ assertEquals(true, robotTime.m_deltaTime > 0);
+ assertEquals(true, robotTime.m_robotTime > 0);
+ assertEquals(lastTime, robotTime.m_lastRobotTime);
+ assertEquals(2, robotTime.m_frameNumber);
+ }
+
+ @Test
+ public void testMatchTime() {
+ // Arrange
+ long lastTime;
+
+ // Assert
+ assertEquals(0, robotTime.m_matchTime);
+ assertEquals(0, robotTime.m_lastMatchTime);
+ lastTime = robotTime.m_matchTime;
+
+ // Act
+ robotTime.startMatchTime();
+ wait(1);
+ robotTime.updateTimes();
+
+ // Assert
+ assertEquals(true, robotTime.m_matchTime > 0);
+ assertEquals(lastTime, robotTime.m_lastMatchTime);
+ lastTime = robotTime.m_matchTime;
+
+ // Act
+ wait(1);
+ robotTime.updateTimes();
+ robotTime.endMatchTime();
+
+ // Assert
+ assertEquals(0, robotTime.m_matchTime);
+ assertEquals(lastTime, robotTime.m_lastMatchTime);
+ lastTime = robotTime.m_matchTime;
+
+ // Act
+ wait(1);
+ robotTime.updateTimes();
+
+ // Assert
+ assertEquals(0, robotTime.m_matchTime);
+ assertEquals(lastTime, robotTime.m_lastMatchTime);
+ }
+
+ private void wait(int millis) {
+ try {
+ Thread.sleep(millis);
+ } catch (Exception e) {}
+ }
+}
diff --git a/template.config.js b/template.config.js
new file mode 100644
index 0000000..54f2425
--- /dev/null
+++ b/template.config.js
@@ -0,0 +1,31 @@
+/**
+ * This file is a configuration file generated by the `Template` extension on `vscode`
+ * @see https://marketplace.visualstudio.com/items?itemName=yongwoo.template
+ */
+module.exports = {
+ // You can change the template path to another path
+ templateRootPath: "./.templates",
+ // After copying the template file the `replaceFileTextFn` function is executed
+ replaceFileTextFn: (fileText, templateName, utils) => {
+ // @see https://www.npmjs.com/package/change-case
+ const { changeCase } = utils;
+ // You can change the text in the file
+ return fileText
+ .replace(/__templateName__/gm, templateName)
+ .replace(
+ /__templateNameToPascalCase__/gm,
+ changeCase.pascalCase(templateName)
+ )
+ .replace(
+ /__templateNameToParamCase__/gm,
+ changeCase.paramCase(templateName)
+ );
+ },
+ replaceFileNameFn: (fileName, templateName, utils) => {
+ const { path } = utils;
+ // @see https://nodejs.org/api/path.html#path_path_parse_path
+ const { base } = path.parse(fileName);
+ // You can change the file name
+ return base;
+ }
+};
diff --git a/vendordeps/NavX.json b/vendordeps/NavX.json
new file mode 100644
index 0000000..e978a5f
--- /dev/null
+++ b/vendordeps/NavX.json
@@ -0,0 +1,40 @@
+{
+ "fileName": "NavX.json",
+ "name": "NavX",
+ "version": "2024.1.0",
+ "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
+ "frcYear": "2024",
+ "mavenUrls": [
+ "https://dev.studica.com/maven/release/2024/"
+ ],
+ "jsonUrl": "https://dev.studica.com/releases/2024/NavX.json",
+ "javaDependencies": [
+ {
+ "groupId": "com.kauailabs.navx.frc",
+ "artifactId": "navx-frc-java",
+ "version": "2024.1.0"
+ }
+ ],
+ "jniDependencies": [],
+ "cppDependencies": [
+ {
+ "groupId": "com.kauailabs.navx.frc",
+ "artifactId": "navx-frc-cpp",
+ "version": "2024.1.0",
+ "headerClassifier": "headers",
+ "sourcesClassifier": "sources",
+ "sharedLibrary": false,
+ "libName": "navx_frc",
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "linuxathena",
+ "linuxraspbian",
+ "linuxarm32",
+ "linuxarm64",
+ "linuxx86-64",
+ "osxuniversal",
+ "windowsx86-64"
+ ]
+ }
+ ]
+}
\ No newline at end of file
diff --git a/vendordeps/Phoenix6.json b/vendordeps/Phoenix6.json
new file mode 100644
index 0000000..0322385
--- /dev/null
+++ b/vendordeps/Phoenix6.json
@@ -0,0 +1,339 @@
+{
+ "fileName": "Phoenix6.json",
+ "name": "CTRE-Phoenix (v6)",
+ "version": "24.3.0",
+ "frcYear": 2024,
+ "uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
+ "mavenUrls": [
+ "https://maven.ctr-electronics.com/release/"
+ ],
+ "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json",
+ "conflictsWith": [
+ {
+ "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a",
+ "errorMessage": "The combined Phoenix-6-And-5 vendordep is no longer supported. Please remove the vendordep and instead add both the latest Phoenix 6 vendordep and Phoenix 5 vendordep.",
+ "offlineFileName": "Phoenix6And5.json"
+ }
+ ],
+ "javaDependencies": [
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "wpiapi-java",
+ "version": "24.3.0"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "tools",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "tools-sim",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simTalonSRX",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simTalonFX",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simVictorSPX",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simPigeonIMU",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simCANCoder",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProTalonFX",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProCANcoder",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProPigeon2",
+ "version": "24.3.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "wpiapi-cpp",
+ "version": "24.3.0",
+ "libName": "CTRE_Phoenix6_WPI",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "tools",
+ "version": "24.3.0",
+ "libName": "CTRE_PhoenixTools",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "wpiapi-cpp-sim",
+ "version": "24.3.0",
+ "libName": "CTRE_Phoenix6_WPISim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "tools-sim",
+ "version": "24.3.0",
+ "libName": "CTRE_PhoenixTools_Sim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simTalonSRX",
+ "version": "24.3.0",
+ "libName": "CTRE_SimTalonSRX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simTalonFX",
+ "version": "24.3.0",
+ "libName": "CTRE_SimTalonFX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simVictorSPX",
+ "version": "24.3.0",
+ "libName": "CTRE_SimVictorSPX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simPigeonIMU",
+ "version": "24.3.0",
+ "libName": "CTRE_SimPigeonIMU",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simCANCoder",
+ "version": "24.3.0",
+ "libName": "CTRE_SimCANCoder",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProTalonFX",
+ "version": "24.3.0",
+ "libName": "CTRE_SimProTalonFX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProCANcoder",
+ "version": "24.3.0",
+ "libName": "CTRE_SimProCANcoder",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProPigeon2",
+ "version": "24.3.0",
+ "libName": "CTRE_SimProPigeon2",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ]
+}
\ No newline at end of file
diff --git a/vendordeps/WPILibNewCommands.json b/vendordeps/WPILibNewCommands.json
new file mode 100644
index 0000000..67bf389
--- /dev/null
+++ b/vendordeps/WPILibNewCommands.json
@@ -0,0 +1,38 @@
+{
+ "fileName": "WPILibNewCommands.json",
+ "name": "WPILib-New-Commands",
+ "version": "1.0.0",
+ "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266",
+ "frcYear": "2024",
+ "mavenUrls": [],
+ "jsonUrl": "",
+ "javaDependencies": [
+ {
+ "groupId": "edu.wpi.first.wpilibNewCommands",
+ "artifactId": "wpilibNewCommands-java",
+ "version": "wpilib"
+ }
+ ],
+ "jniDependencies": [],
+ "cppDependencies": [
+ {
+ "groupId": "edu.wpi.first.wpilibNewCommands",
+ "artifactId": "wpilibNewCommands-cpp",
+ "version": "wpilib",
+ "libName": "wpilibNewCommands",
+ "headerClassifier": "headers",
+ "sourcesClassifier": "sources",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "linuxathena",
+ "linuxarm32",
+ "linuxarm64",
+ "windowsx86-64",
+ "windowsx86",
+ "linuxx86-64",
+ "osxuniversal"
+ ]
+ }
+ ]
+}
diff --git a/vendordeps/navx_frc.json b/vendordeps/navx_frc.json
new file mode 100644
index 0000000..dca1d82
--- /dev/null
+++ b/vendordeps/navx_frc.json
@@ -0,0 +1,35 @@
+{
+ "fileName": "navx_frc.json",
+ "name": "KauaiLabs_navX_FRC",
+ "version": "3.1.413",
+ "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
+ "mavenUrls": [
+ "https://repo1.maven.org/maven2/"
+ ],
+ "jsonUrl": "https://www.kauailabs.com/dist/frc/2020/navx_frc.json",
+ "javaDependencies": [
+ {
+ "groupId": "com.kauailabs.navx.frc",
+ "artifactId": "navx-java",
+ "version": "3.1.413"
+ }
+ ],
+ "jniDependencies": [],
+ "cppDependencies": [
+ {
+ "groupId": "com.kauailabs.navx.frc",
+ "artifactId": "navx-cpp",
+ "version": "3.1.413",
+ "headerClassifier": "headers",
+ "sourcesClassifier": "sources",
+ "sharedLibrary": false,
+ "libName": "navx_frc",
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "linuxathena",
+ "linuxraspbian",
+ "windowsx86-64"
+ ]
+ }
+ ]
+}
\ No newline at end of file