iViYT=fZ(|3Ox^$aWPp4a8h24tD<|8-!aK0lHgL$N7Efw}J
zVIB!7=T$U`ao1?upi5V4Et*-lTG0XvExbf!ya{cua==$WJyVG(CmA6Of*8E@DSE%L
z`V^$qz&RU$7G5mg;8;=#`@rRG`-uS
+ * The methods in this class return triggers. To get boolean values, use {@link Trigger#getAsBoolean()}
+ * ui&7ST0~#+}I^&?vcE*t47~Xq#YwvA^6^}
z`WkC)$AkNub|t@S!$8CBlwbV~?yp&@9h{D|3
BQoCAWo-$LRvM=F5MTle`M})t3vVv;2j0HZY&G
z22^iGhV@uaJh(Xo#s9osV>F{uK{QA@BES#&;#KsScf>y
zvs?vIbI>VrT<*!;XmQS=bhq%46-aambZ(8KU-wOO2=en~D}MCToB_u;Yz{)1ySrPZ
z@=$}EvjTdzTWU7c0ZI6L8=yP+YRD_eMMos}b5vY^S*~VZysrkq<`cK3>>v%uy7jgq
z0ilW9KjVDHLv0b<1K_`1IkbTOINs0=m-22c%M~l=^S}%hbli-3?BnNq?b`hx^HX2J
zIe6ECljRL0uBWb`%{EA=%!
+To pull the latest changes run `git submodule update --remote .\src\main\java\frc\lib\zylve`
\ No newline at end of file
diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java
new file mode 100644
index 0000000..8322941
--- /dev/null
+++ b/src/main/java/frc/robot/Constants.java
@@ -0,0 +1,137 @@
+package frc.robot;
+
+import com.pathplanner.lib.util.HolonomicPathFollowerConfig;
+import com.pathplanner.lib.util.PIDConstants;
+import com.pathplanner.lib.util.ReplanningConfig;
+import com.revrobotics.CANSparkBase.IdleMode;
+import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
+import edu.wpi.first.math.trajectory.TrapezoidProfile;
+import edu.wpi.first.math.util.Units;
+
+public final class Constants {
+ public static final class DriveConstants {
+ // Maximum allowed speeds.
+ public static final double MAXIMUM_SPEED_METRES_PER_SECOND = 4.8;
+ public static final double MAXIMUM_ANGULAR_SPEED_RADIANS_PER_SECOND = 2 * Math.PI;
+
+ public static final double DIRECTION_SLEW_RATE = 1.2; // radians per second
+ public static final double MAGNITUDE_SLEW_RATE = 1.8; // percent per second (1 = 100%)
+ public static final double ROTATION_SLEW_RATE = 2.0; // percent per second (1 = 100%)
+
+ public static final double TRACK_WIDTH = Units.inchesToMeters(19.5); // Distance between left and right wheels on robot
+ public static final double WHEEL_BASE = TRACK_WIDTH; // Distance between front and back wheels on robot
+
+ public static final double CHASSIS_RADIUS = Units.inchesToMeters(
+ (TRACK_WIDTH / 2) / Math.sin(45 * (Math.PI / 180)));
+
+ public static final SwerveDriveKinematics SWERVE_KINEMATICS = new SwerveDriveKinematics(
+ new Translation2d(WHEEL_BASE / 2, TRACK_WIDTH / 2),
+ new Translation2d(WHEEL_BASE / 2, -TRACK_WIDTH / 2),
+ new Translation2d(-WHEEL_BASE / 2, TRACK_WIDTH / 2),
+ new Translation2d(-WHEEL_BASE / 2, -TRACK_WIDTH / 2));
+
+ // Angular offset relative to chassis in radians.
+ public static final double FL_OFFSET = -Math.PI / 2;
+ public static final double FR_OFFSET = 0;
+ public static final double BL_OFFSET = Math.PI;
+ public static final double BR_OFFSET = Math.PI / 2;
+
+ public static final int FL_DRIVE_MOTOR = 3;
+ public static final int FR_DRIVE_MOTOR = 5;
+ public static final int BL_DRIVE_MOTOR = 1;
+ public static final int BR_DRIVE_MOTOR = 7;
+
+ public static final int FL_TURN_MOTOR = 4;
+ public static final int FR_TURN_MOTOR = 6;
+ public static final int BL_TURN_MOTOR = 2;
+ public static final int BR_TURN_MOTOR = 8;
+
+ public static final boolean GYRO_INVERTED = true;
+
+ public static final double SNAP_P = 0.01;
+ public static final double SNAP_I = 0;
+ public static final double SNAP_D = 0;
+
+ public static final double FLIP_P = 0.01;
+ public static final double FLIP_I = 0;
+ public static final double FLIP_D = 0;
+ }
+
+ public static final class ModuleConstants {
+ // Modules can have 12T, 13T, or 14T pinions. More teeth means it will drive faster.
+ public static final int DRIVE_PINION_TEETH = 12;
+
+ // Invert the turning encoder, since the output shaft rotates in the opposite direction of the steering motor in the MAXSwerve Module.
+ public static final boolean TURN_ENCODER_INVERTED = true;
+
+ public static final double DRIVE_MOTOR_FREE_SPEED_RPS = NeoConstants.FREE_SPEED_RPM / 60; // Revolutions per second
+ public static final double WHEEL_DIAMETER_METRES = Units.inchesToMeters(3);
+ public static final double WHEEL_CIRCUMFERENCE_METRES = WHEEL_DIAMETER_METRES * Math.PI;
+
+ // Bevel 45T, First Stage 22T, Bevel Pinion 15T
+ public static final double DRIVE_MOTOR_REDUCTION = (45.0 * 22) / (DRIVE_PINION_TEETH * 15);
+ public static final double DRIVE_WHEEL_FREE_SPEED_RPS = (DRIVE_MOTOR_FREE_SPEED_RPS * WHEEL_CIRCUMFERENCE_METRES) / DRIVE_MOTOR_REDUCTION;
+
+ public static final double DRIVE_ENCODER_POSITION_FACTOR = (WHEEL_DIAMETER_METRES * Math.PI) / DRIVE_MOTOR_REDUCTION; // Metres
+ public static final double DRIVE_ENCODER_VELOCITY_FACTOR = ((WHEEL_DIAMETER_METRES * Math.PI) / DRIVE_MOTOR_REDUCTION) / 60.0; // Metres per second
+
+ public static final double TURN_ENCODER_POSITION_FACTOR = (2 * Math.PI); // Radians
+ public static final double TURN_ENCODER_VELOCITY_FACTOR = (2 * Math.PI) / 60.0; // Radians per second
+
+ public static final double TURN_PID_MINIMUM_INPUT = 0; // Radians
+ public static final double TURN_PID_MAXIMUM_INPUT = TURN_ENCODER_POSITION_FACTOR; // Radians
+
+ public static final double DRIVE_P = 0.04;
+ public static final double DRIVE_I = 0;
+ public static final double DRIVE_D = 0;
+ public static final double DRIVE_FF = 1 / DRIVE_WHEEL_FREE_SPEED_RPS;
+
+ public static final double DRIVE_MINIMUM_OUTPUT = -1;
+ public static final double DRIVE_MAXIMUM_OUTPUT = 1;
+
+ public static final double TURN_P = 1;
+ public static final double TURN_I = 0;
+ public static final double TURN_D = 0;
+ public static final double TURN_FF = 0;
+ public static final double TURN_MINIMUM_OUTPUT = -1;
+ public static final double TURN_MAXIMUM_OUTPUT = 1;
+
+ public static final IdleMode DRIVE_IDLE_MODE = IdleMode.kBrake;
+ public static final IdleMode TURN_IDLE_MODE = IdleMode.kBrake;
+
+ public static final int DRIVE_MOTOR_CURRENT_LIMIT = 50; // Amps
+ public static final int TURN_MOTOR_CURRENT_LIMIT = 20; // Amps
+ }
+
+ public static final class OperatorConstants {
+ public static final int CONTROLLER_PORT = 0;
+ public static final double DEADBAND = 0.15;
+ public static final double OFFSET = 0.1;
+ }
+
+ public static final class AutonomousConstants {
+ public static final double MAXIMUM_SPEED_METRES_PER_SECOND = 4.8;
+ public static final double MAXIMUM_ACCELERATION_METRES_PER_SECOND_SQUARED = 2;
+ public static final double MAXIMUM_ANGULAR_SPEED_RADIANS_PER_SECOND = 2 * Math.PI;
+ public static final double MAXIMUM_ANGULAR_ACCELERATION_RADIANS_PER_SECOND_SQUARED = 5;
+
+ public static final double TRANSLATION_P = 1;
+ public static final double ROTATION_P = 1;
+
+ // Constraint for the motion profiled robot angle controller
+ public static final TrapezoidProfile.Constraints THETA_CONTROLLER_CONSTRAINTS = new TrapezoidProfile.Constraints(MAXIMUM_ANGULAR_SPEED_RADIANS_PER_SECOND,
+ MAXIMUM_ANGULAR_ACCELERATION_RADIANS_PER_SECOND_SQUARED);
+
+ public static final HolonomicPathFollowerConfig pathFollowConfig = new HolonomicPathFollowerConfig(
+ new PIDConstants(TRANSLATION_P, 0, 0),
+ new PIDConstants(ROTATION_P, 0, 0),
+ MAXIMUM_SPEED_METRES_PER_SECOND,
+ DriveConstants.CHASSIS_RADIUS,
+ new ReplanningConfig());
+ }
+
+ public static final class NeoConstants {
+ public static final double FREE_SPEED_RPM = 5676;
+ }
+}
diff --git a/src/main/java/frc/robot/Main.java b/src/main/java/frc/robot/Main.java
new file mode 100644
index 0000000..f85ca46
--- /dev/null
+++ b/src/main/java/frc/robot/Main.java
@@ -0,0 +1,12 @@
+package frc.robot;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+public final class Main {
+ private Main() {
+ }
+
+ public static void main(String... args) {
+ RobotBase.startRobot(Robot::new);
+ }
+}
diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java
new file mode 100644
index 0000000..3d84dcf
--- /dev/null
+++ b/src/main/java/frc/robot/Robot.java
@@ -0,0 +1,62 @@
+package frc.robot;
+
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.CommandScheduler;
+
+public class Robot extends TimedRobot {
+ private Command autonomousCommand;
+
+ private RobotContainer robotContainer;
+
+ @Override
+ public void robotInit() {
+ robotContainer = new RobotContainer();
+ }
+
+ @Override
+ public void robotPeriodic() {
+ CommandScheduler.getInstance().run();
+ }
+
+ @Override
+ public void disabledInit() {
+ }
+
+ @Override
+ public void disabledPeriodic() {
+ }
+
+ @Override
+ public void autonomousInit() {
+ autonomousCommand = robotContainer.getAutonomousCommand();
+
+ if(autonomousCommand != null) {
+ autonomousCommand.schedule();
+ }
+ }
+
+ @Override
+ public void autonomousPeriodic() {
+ }
+
+ @Override
+ public void teleopInit() {
+ if(autonomousCommand != null) {
+ autonomousCommand.cancel();
+ }
+ }
+
+ @Override
+ public void teleopPeriodic() {
+ }
+
+ @Override
+ public void testInit() {
+ CommandScheduler.getInstance().cancelAll();
+ }
+
+ @Override
+ public void testPeriodic() {
+ }
+}
diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java
new file mode 100644
index 0000000..8e33525
--- /dev/null
+++ b/src/main/java/frc/robot/RobotContainer.java
@@ -0,0 +1,50 @@
+package frc.robot;
+
+import com.pathplanner.lib.commands.PathPlannerAuto;
+import edu.wpi.first.math.MathUtil;
+import frc.lib.zylve.Controller;
+import frc.robot.Constants.OperatorConstants;
+import frc.robot.subsystems.SwerveDrive;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.RunCommand;
+import frc.robot.commands.FlipRotation;
+import frc.robot.commands.SnapRotation;
+
+public class RobotContainer {
+ private final SwerveDrive swerveDrive = new SwerveDrive();
+ private final SnapRotation snap90 = new SnapRotation(90, swerveDrive);
+ private final FlipRotation flip180 = new FlipRotation(swerveDrive);
+
+ Controller controller = new Controller(OperatorConstants.CONTROLLER_PORT);
+
+ public RobotContainer() {
+ configureButtonBindings();
+ swerveDrive.setDefaultCommand(
+ new RunCommand(
+ () -> swerveDrive.joystickDrive(
+ -MathUtil.applyDeadband(controller.getLeftY(), OperatorConstants.DEADBAND),
+ -MathUtil.applyDeadband(controller.getLeftX(), OperatorConstants.DEADBAND),
+ -MathUtil.applyDeadband(controller.getRightX(), OperatorConstants.DEADBAND),
+ true, true),
+ swerveDrive));
+
+ controller.getLeftTrigger().onTrue(snap90);
+ controller.getRightTrigger().whileTrue(flip180);
+ }
+
+ private void configureButtonBindings() {
+ controller.getLeftStick()
+ .whileTrue(new RunCommand(
+ () -> swerveDrive.lockPosition(),
+ swerveDrive));
+
+ controller.getRightStick()
+ .whileTrue(new RunCommand(
+ () -> swerveDrive.zeroHeading(),
+ swerveDrive));
+ }
+
+ public Command getAutonomousCommand() {
+ return new PathPlannerAuto("New Auto");
+ }
+}
diff --git a/src/main/java/frc/robot/commands/FlipRotation.java b/src/main/java/frc/robot/commands/FlipRotation.java
new file mode 100644
index 0000000..2793a8f
--- /dev/null
+++ b/src/main/java/frc/robot/commands/FlipRotation.java
@@ -0,0 +1,70 @@
+package frc.robot.commands;
+
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.controller.PIDController;
+import edu.wpi.first.wpilibj2.command.Command;
+import frc.robot.Constants.DriveConstants;
+import frc.robot.subsystems.SwerveDrive;
+
+public class FlipRotation extends Command {
+ private final SwerveDrive swerveDrive;
+ private final PIDController rotationPIDController;
+ private double targetAngle;
+
+ public FlipRotation(SwerveDrive swerveDrive) {
+ this.swerveDrive = swerveDrive;
+
+ rotationPIDController = new PIDController(DriveConstants.FLIP_P, DriveConstants.FLIP_I, DriveConstants.FLIP_D);
+ rotationPIDController.setTolerance(2);
+ }
+
+
+ @Override
+ public void initialize() {
+ targetAngle = this.getTargetAngle();
+ }
+
+
+ @Override
+ public void execute() {
+ rotationPIDController.setSetpoint(this.targetAngle);
+
+ double output = rotationPIDController.calculate(swerveDrive.getRotation2d().getDegrees());
+ output = MathUtil.clamp(output, -0.2, 0.2);
+
+ swerveDrive.setPIDInput(output);
+ }
+
+
+ @Override
+ public void end(boolean interrupted) {
+ swerveDrive.setPIDInput(null);
+ }
+
+
+ @Override
+ public boolean isFinished() {
+ return rotationPIDController.atSetpoint();
+ }
+
+ private double getTargetAngle() {
+ double currentRotation = swerveDrive.getRotation2d().getDegrees();
+
+ double y = currentRotation / 90;
+
+ y = Math.floor(y);
+
+ double lowerLimit = 90 * y;
+ double upperLimit = 90 * (y + 1);
+
+ double targetAngle;
+
+ if(Math.abs(currentRotation - upperLimit) > Math.abs(currentRotation - lowerLimit)) {
+ targetAngle = lowerLimit;
+ } else {
+ targetAngle = upperLimit;
+ }
+
+ return targetAngle - 180;
+ }
+}
diff --git a/src/main/java/frc/robot/commands/SnapRotation.java b/src/main/java/frc/robot/commands/SnapRotation.java
new file mode 100644
index 0000000..de050bb
--- /dev/null
+++ b/src/main/java/frc/robot/commands/SnapRotation.java
@@ -0,0 +1,68 @@
+package frc.robot.commands;
+
+import edu.wpi.first.wpilibj2.command.Command;
+import frc.robot.Constants.DriveConstants;
+import frc.robot.subsystems.SwerveDrive;
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.controller.PIDController;
+
+public class SnapRotation extends Command {
+ private final SwerveDrive swerveDrive;
+ private final PIDController rotationPIDController;
+ private final int angleSnap;
+ private double targetAngle;
+
+ public SnapRotation(int angleSnap, SwerveDrive swerveDrive) {
+ this.angleSnap = angleSnap;
+ this.swerveDrive = swerveDrive;
+
+ rotationPIDController = new PIDController(DriveConstants.SNAP_P, DriveConstants.SNAP_I, DriveConstants.SNAP_D);
+ rotationPIDController.setTolerance(2);
+ }
+
+ @Override
+ public void initialize() {
+ this.targetAngle = this.getNearestAngle();
+ }
+
+ @Override
+ public void execute() {
+ rotationPIDController.setSetpoint(this.targetAngle);
+
+ double output = MathUtil.clamp(rotationPIDController.calculate(swerveDrive.getRotation2d().getDegrees()), -1, 1);
+
+ swerveDrive.setPIDInput(output);
+ }
+
+ @Override
+ public void end(boolean interrupted) {
+ swerveDrive.setPIDInput(null);
+ }
+
+ @Override
+ public boolean isFinished() {
+ return rotationPIDController.atSetpoint();
+ }
+
+ private double getNearestAngle() {
+ double currentRotation = swerveDrive.getRotation2d().getDegrees();
+
+ double y = currentRotation / angleSnap;
+
+ y = Math.floor(y);
+
+ double lowerLimit = angleSnap * y;
+ double upperLimit = angleSnap * (y + 1);
+
+ double nearestAngle;
+
+ if(Math.abs(currentRotation - upperLimit) > Math.abs(currentRotation - lowerLimit)) {
+ nearestAngle = lowerLimit;
+ } else {
+ nearestAngle = upperLimit;
+ }
+
+ return nearestAngle;
+ }
+
+}
diff --git a/src/main/java/frc/robot/subsystems/SwerveDrive.java b/src/main/java/frc/robot/subsystems/SwerveDrive.java
new file mode 100644
index 0000000..fd32261
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/SwerveDrive.java
@@ -0,0 +1,278 @@
+package frc.robot.subsystems;
+
+import com.kauailabs.navx.frc.AHRS;
+import com.pathplanner.lib.auto.AutoBuilder;
+import edu.wpi.first.math.filter.SlewRateLimiter;
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.kinematics.ChassisSpeeds;
+import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
+import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
+import edu.wpi.first.math.kinematics.SwerveModuleState;
+import edu.wpi.first.util.WPIUtilJNI;
+import edu.wpi.first.wpilibj.SerialPort;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import frc.robot.Constants.AutonomousConstants;
+import frc.robot.Constants.DriveConstants;
+import frc.robot.Constants.OperatorConstants;
+import frc.utils.SwerveUtils;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+
+public class SwerveDrive extends SubsystemBase {
+ private final SwerveModule frontLeft = new SwerveModule(
+ DriveConstants.FL_DRIVE_MOTOR,
+ DriveConstants.FL_TURN_MOTOR,
+ DriveConstants.FL_OFFSET);
+
+ private final SwerveModule frontRight = new SwerveModule(
+ DriveConstants.FR_DRIVE_MOTOR,
+ DriveConstants.FR_TURN_MOTOR,
+ DriveConstants.FR_OFFSET);
+
+ private final SwerveModule backLeft = new SwerveModule(
+ DriveConstants.BL_DRIVE_MOTOR,
+ DriveConstants.BL_TURN_MOTOR,
+ DriveConstants.BL_OFFSET);
+
+ private final SwerveModule backRight = new SwerveModule(
+ DriveConstants.BR_DRIVE_MOTOR,
+ DriveConstants.BR_TURN_MOTOR,
+ DriveConstants.BR_OFFSET);
+
+ // Gyro.
+ private final AHRS gyro = new AHRS(SerialPort.Port.kUSB);
+
+ // Slew Rate filters to control acceleration.
+ private double currentRotation = 0.0;
+ private double currentTranslationDirection = 0.0;
+ private double currentTranslationMagnitude = 0.0;
+
+ private SlewRateLimiter magnitudeLimiter = new SlewRateLimiter(DriveConstants.MAGNITUDE_SLEW_RATE);
+ private SlewRateLimiter rotationLimiter = new SlewRateLimiter(DriveConstants.ROTATION_SLEW_RATE);
+ private double previousTime = WPIUtilJNI.now() * 1e-6;
+
+ private Double rotationPIDInput = null;
+
+ // Track robot position with odometry
+ SwerveDriveOdometry odometry = new SwerveDriveOdometry(
+ DriveConstants.SWERVE_KINEMATICS,
+ this.getRotation2d(),
+ new SwerveModulePosition[] {
+ frontLeft.getPosition(),
+ frontRight.getPosition(),
+ backLeft.getPosition(),
+ backRight.getPosition()
+ });
+
+ public SwerveDrive() {
+ this.zeroHeading();
+
+ AutoBuilder.configureHolonomic(
+ this::getPose,
+ this::resetOdometry,
+ this::getChassisSpeeds,
+ this::driveRelative,
+ AutonomousConstants.pathFollowConfig,
+ this);
+ }
+
+ @Override
+ public void periodic() {
+ SmartDashboard.putNumber("Radius", DriveConstants.CHASSIS_RADIUS);
+ odometry.update(
+ this.getRotation2d(),
+ new SwerveModulePosition[] {
+ frontLeft.getPosition(),
+ frontRight.getPosition(),
+ backLeft.getPosition(),
+ backRight.getPosition()
+ });
+
+ SmartDashboard.putNumber("Robot X", odometry.getPoseMeters().getX());
+ SmartDashboard.putNumber("Robot Y", odometry.getPoseMeters().getY());
+ SmartDashboard.putNumber("Robot Rotation", odometry.getPoseMeters().getRotation().getDegrees());
+ }
+
+ /**
+ * Returns the estimated position.
+ */
+ public Pose2d getPose() {
+ return odometry.getPoseMeters();
+ }
+
+ public ChassisSpeeds getChassisSpeeds() {
+ return DriveConstants.SWERVE_KINEMATICS.toChassisSpeeds(
+ new SwerveModuleState[] {
+ frontLeft.getState(),
+ frontRight.getState(),
+ backLeft.getState(),
+ backRight.getState()
+ });
+ }
+
+ /**
+ * Resets odometry to a specified pose.
+ */
+ public void resetOdometry(Pose2d pose) {
+ odometry.resetPosition(
+ this.getRotation2d(),
+ new SwerveModulePosition[] {
+ frontLeft.getPosition(),
+ frontRight.getPosition(),
+ backLeft.getPosition(),
+ backRight.getPosition()
+ },
+ pose);
+ }
+
+ public void setPIDInput(Double input) {
+ rotationPIDInput = input;
+ }
+
+ public void joystickDrive(double xSpeed, double ySpeed, double rSpeed, boolean fieldRelative, boolean rateLimit) {
+ xSpeed = Math.pow(xSpeed, 5);
+ ySpeed = Math.pow(ySpeed, 5);
+ rSpeed = Math.pow(rSpeed, 5);
+
+ xSpeed += (Math.abs(xSpeed) != 0 ? Math.signum(xSpeed) * OperatorConstants.OFFSET : 0.0);
+ ySpeed += (Math.abs(ySpeed) != 0 ? Math.signum(ySpeed) * OperatorConstants.OFFSET : 0.0);
+ rSpeed += (Math.abs(rSpeed) != 0 ? Math.signum(rSpeed) * OperatorConstants.OFFSET : 0.0);
+
+ this.drive(xSpeed, ySpeed, rSpeed, fieldRelative, rateLimit);
+ }
+
+ /**
+ * Method to drive the robot using joystick info.
+ *
+ * @param xSpeed Speed of the robot in the x direction (forward).
+ * @param ySpeed Speed of the robot in the y direction (sideways).
+ * @param rSpeed Angular rate of the robot.
+ * @param fieldRelative Whether the provided x and y speeds are relative to the field.
+ * @param rateLimit Whether to enable rate limiting for smoother control.
+ */
+ public void drive(double xSpeed, double ySpeed, double rSpeed, boolean fieldRelative, boolean rateLimit) {
+
+ if(rSpeed == 0 && rotationPIDInput != null) {
+ rSpeed = rotationPIDInput;
+ }
+
+
+ double xSpeedCommand;
+ double ySpeedCommand;
+
+ if(rateLimit) {
+ // Convert XY to polar for rate limiting
+ double inputTranslationDirection = Math.atan2(ySpeed, xSpeed);
+ double inputTranslationMagnitude = Math.sqrt(Math.pow(xSpeed, 2) + Math.pow(ySpeed, 2));
+
+ // Calculate based on acceleration estimate
+ double directionSlewRate;
+
+ if(currentTranslationMagnitude != 0.0) {
+ directionSlewRate = Math.abs(DriveConstants.DIRECTION_SLEW_RATE / currentTranslationMagnitude);
+ } else {
+ directionSlewRate = 500.0; // Instantaneous if not moving
+ }
+
+ double currentTime = WPIUtilJNI.now() * 1e-6;
+ double elapsedTime = currentTime - previousTime;
+ double angleDif = SwerveUtils.angleDifference(inputTranslationDirection, currentTranslationDirection);
+
+ if(angleDif < 0.45 * Math.PI) {
+ currentTranslationDirection = SwerveUtils.stepTowardsCircular(currentTranslationDirection, inputTranslationDirection, directionSlewRate * elapsedTime);
+ currentTranslationMagnitude = magnitudeLimiter.calculate(inputTranslationMagnitude);
+ } else if(angleDif > 0.85 * Math.PI) {
+ if(currentTranslationMagnitude > 1e-4) {
+ currentTranslationMagnitude = magnitudeLimiter.calculate(0.0);
+ } else {
+ currentTranslationDirection = SwerveUtils.wrapAngle(currentTranslationDirection + Math.PI);
+ currentTranslationMagnitude = magnitudeLimiter.calculate(inputTranslationMagnitude);
+ }
+ } else {
+ currentTranslationDirection = SwerveUtils.stepTowardsCircular(currentTranslationDirection, inputTranslationDirection, directionSlewRate * elapsedTime);
+ currentTranslationMagnitude = magnitudeLimiter.calculate(0.0);
+ }
+ previousTime = currentTime;
+
+ xSpeedCommand = currentTranslationMagnitude * Math.cos(currentTranslationDirection);
+ ySpeedCommand = currentTranslationMagnitude * Math.sin(currentTranslationDirection);
+ currentRotation = rotationLimiter.calculate(rSpeed);
+
+ } else {
+ xSpeedCommand = xSpeed;
+ ySpeedCommand = ySpeed;
+ currentRotation = rSpeed;
+ }
+
+ // Convert the commanded speeds into proper units
+ double xSpeedDelivered = xSpeedCommand * DriveConstants.MAXIMUM_SPEED_METRES_PER_SECOND;
+ double ySpeedDelivered = ySpeedCommand * DriveConstants.MAXIMUM_SPEED_METRES_PER_SECOND;
+ double rotDelivered = currentRotation * DriveConstants.MAXIMUM_ANGULAR_SPEED_RADIANS_PER_SECOND;
+
+ SwerveModuleState[] swerveModuleStates = DriveConstants.SWERVE_KINEMATICS.toSwerveModuleStates(
+ fieldRelative
+ ? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered, this.getRotation2d())
+ : new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered));
+
+ SwerveDriveKinematics.desaturateWheelSpeeds(swerveModuleStates, DriveConstants.MAXIMUM_SPEED_METRES_PER_SECOND);
+
+ frontLeft.setDesiredState(swerveModuleStates[0]);
+ frontRight.setDesiredState(swerveModuleStates[1]);
+ backLeft.setDesiredState(swerveModuleStates[2]);
+ backRight.setDesiredState(swerveModuleStates[3]);
+ }
+
+ public void driveRelative(ChassisSpeeds speeds) {
+ SwerveModuleState[] swerveModuleStates = DriveConstants.SWERVE_KINEMATICS.toSwerveModuleStates(speeds);
+ SwerveDriveKinematics.desaturateWheelSpeeds(swerveModuleStates, DriveConstants.MAXIMUM_SPEED_METRES_PER_SECOND);
+
+ frontLeft.setDesiredState(swerveModuleStates[0]);
+ frontRight.setDesiredState(swerveModuleStates[1]);
+ backLeft.setDesiredState(swerveModuleStates[2]);
+ backRight.setDesiredState(swerveModuleStates[3]);
+ }
+
+ /**
+ * Sets the wheels into an X formation to prevent movement. Use for defense or when the robot needs to be stationary.
+ */
+ public void lockPosition() {
+ frontLeft.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(45)));
+ frontRight.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(-45)));
+ backLeft.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(-45)));
+ backRight.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(45)));
+ }
+
+ public void setModuleStates(SwerveModuleState[] desiredStates) {
+ SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, DriveConstants.MAXIMUM_SPEED_METRES_PER_SECOND);
+
+ frontLeft.setDesiredState(desiredStates[0]);
+ frontRight.setDesiredState(desiredStates[1]);
+ backLeft.setDesiredState(desiredStates[2]);
+ backRight.setDesiredState(desiredStates[3]);
+ }
+
+ public void resetEncoders() {
+ frontLeft.resetEncoders();
+ backLeft.resetEncoders();
+ frontRight.resetEncoders();
+ backRight.resetEncoders();
+ }
+
+ public void zeroHeading() {
+ gyro.reset();
+ }
+
+ public Rotation2d getRotation2d() {
+ return gyro.getRotation2d();
+ }
+
+ /**
+ * How fast the robot is turning in degrees per second.
+ */
+ public double getTurnRate() {
+ return gyro.getRate() * (DriveConstants.GYRO_INVERTED ? -1.0 : 1.0);
+ }
+
+
+}
diff --git a/src/main/java/frc/robot/subsystems/SwerveModule.java b/src/main/java/frc/robot/subsystems/SwerveModule.java
new file mode 100644
index 0000000..b5bd3c9
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/SwerveModule.java
@@ -0,0 +1,141 @@
+package frc.robot.subsystems;
+
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.kinematics.SwerveModulePosition;
+import edu.wpi.first.math.kinematics.SwerveModuleState;
+import com.revrobotics.CANSparkMax;
+import com.revrobotics.CANSparkLowLevel.MotorType;
+import com.revrobotics.SparkAbsoluteEncoder.Type;
+import com.revrobotics.SparkPIDController;
+import com.revrobotics.AbsoluteEncoder;
+import com.revrobotics.RelativeEncoder;
+import frc.robot.Constants.ModuleConstants;
+
+public class SwerveModule {
+ private final CANSparkMax driveMotor;
+ private final CANSparkMax turnMotor;
+
+ private final RelativeEncoder driveEncoder;
+ private final AbsoluteEncoder turnEncoder;
+
+ private final SparkPIDController drivePIDController;
+ private final SparkPIDController turnPIDController;
+
+ private double angularOffset = 0;
+ private SwerveModuleState desiredState = new SwerveModuleState(0.0, new Rotation2d());
+
+ /**
+ * Constructs a MAXSwerveModule and configures the driving and turning motor, encoder, and PID controller. This configuration is specific to the REV MAXSwerve Module built with
+ * NEOs, SPARKS MAX, and a Through Bore Encoder.
+ */
+ public SwerveModule(int driveMotor, int turnMotor, double angularOffset) {
+ this.driveMotor = new CANSparkMax(driveMotor, MotorType.kBrushless);
+ this.turnMotor = new CANSparkMax(turnMotor, MotorType.kBrushless);
+
+ this.driveMotor.restoreFactoryDefaults();
+ this.turnMotor.restoreFactoryDefaults();
+
+ this.driveEncoder = this.driveMotor.getEncoder();
+ this.turnEncoder = this.turnMotor.getAbsoluteEncoder(Type.kDutyCycle);
+ this.drivePIDController = this.driveMotor.getPIDController();
+ this.turnPIDController = this.turnMotor.getPIDController();
+ this.drivePIDController.setFeedbackDevice(driveEncoder);
+ this.turnPIDController.setFeedbackDevice(turnEncoder);
+
+ this.driveEncoder.setPositionConversionFactor(ModuleConstants.DRIVE_ENCODER_POSITION_FACTOR);
+ this.driveEncoder.setVelocityConversionFactor(ModuleConstants.DRIVE_ENCODER_VELOCITY_FACTOR);
+
+ this.turnEncoder.setPositionConversionFactor(ModuleConstants.TURN_ENCODER_POSITION_FACTOR);
+ this.turnEncoder.setVelocityConversionFactor(ModuleConstants.TURN_ENCODER_VELOCITY_FACTOR);
+
+ // Invert the encoder because the output shaft rotates the opposite direction in the modules.
+ this.turnEncoder.setInverted(ModuleConstants.TURN_ENCODER_INVERTED);
+
+ /*
+ * Enable PID wrap around for the turning motor. This will allow the PID controller to go through 0 to get to the setpoint i.e. going from 350 degrees to 10 degrees will go
+ * through 0 rather than the other direction which is a longer route.
+ */
+ this.turnPIDController.setPositionPIDWrappingEnabled(true);
+ this.turnPIDController.setPositionPIDWrappingMinInput(ModuleConstants.TURN_PID_MINIMUM_INPUT);
+ this.turnPIDController.setPositionPIDWrappingMaxInput(ModuleConstants.TURN_PID_MAXIMUM_INPUT);
+
+ // Set the PID gains for the driving motor. Note these are example gains, and you
+ // may need to tune them for your own robot!
+ this.drivePIDController.setP(ModuleConstants.DRIVE_P);
+ this.drivePIDController.setI(ModuleConstants.DRIVE_I);
+ this.drivePIDController.setD(ModuleConstants.DRIVE_D);
+ this.drivePIDController.setFF(ModuleConstants.DRIVE_FF);
+ this.drivePIDController.setOutputRange(ModuleConstants.DRIVE_MINIMUM_OUTPUT, ModuleConstants.DRIVE_MAXIMUM_OUTPUT);
+
+ // Set the PID gains for the turning motor. Note these are example gains, and you
+ // may need to tune them for your own robot!
+ this.turnPIDController.setP(ModuleConstants.TURN_P);
+ this.turnPIDController.setI(ModuleConstants.TURN_I);
+ this.turnPIDController.setD(ModuleConstants.TURN_D);
+ this.turnPIDController.setFF(ModuleConstants.TURN_FF);
+ this.turnPIDController.setOutputRange(ModuleConstants.TURN_MINIMUM_OUTPUT, ModuleConstants.TURN_MAXIMUM_OUTPUT);
+
+ this.driveMotor.setIdleMode(ModuleConstants.DRIVE_IDLE_MODE);
+ this.turnMotor.setIdleMode(ModuleConstants.TURN_IDLE_MODE);
+ this.driveMotor.setSmartCurrentLimit(ModuleConstants.DRIVE_MOTOR_CURRENT_LIMIT);
+ this.turnMotor.setSmartCurrentLimit(ModuleConstants.TURN_MOTOR_CURRENT_LIMIT);
+
+ // Save the SPARK MAX configurations. If a SPARK MAX browns out during
+ // operation, it will maintain the above configurations.
+ this.driveMotor.burnFlash();
+ this.turnMotor.burnFlash();
+
+ this.angularOffset = angularOffset;
+ this.desiredState.angle = new Rotation2d(turnEncoder.getPosition());
+ this.driveEncoder.setPosition(0);
+ }
+
+ /**
+ * Returns the current state of the module.
+ */
+ public SwerveModuleState getState() {
+ return new SwerveModuleState(
+ driveEncoder.getVelocity(),
+ new Rotation2d(turnEncoder.getPosition() - angularOffset));
+ }
+
+ /**
+ * Returns the current position of the module.
+ */
+ public SwerveModulePosition getPosition() {
+ return new SwerveModulePosition(
+ driveEncoder.getPosition(),
+ new Rotation2d(turnEncoder.getPosition() - angularOffset));
+ }
+
+ /**
+ * Sets the desired state for the module.
+ *
+ * @param desiredState Desired state with speed and angle.
+ */
+ public void setDesiredState(SwerveModuleState desiredState) {
+ SwerveModuleState correctedState = new SwerveModuleState();
+ correctedState.speedMetersPerSecond = desiredState.speedMetersPerSecond;
+ correctedState.angle = desiredState.angle.plus(Rotation2d.fromRadians(angularOffset));
+
+ // Optimize to prevent having to turn more than 90 degrees.
+ SwerveModuleState optimizedState = SwerveModuleState.optimize(
+ correctedState,
+ new Rotation2d(turnEncoder.getPosition()));
+
+ // Drive towards setpoints.
+ drivePIDController.setReference(
+ optimizedState.speedMetersPerSecond,
+ CANSparkMax.ControlType.kVelocity);
+
+ turnPIDController.setReference(
+ optimizedState.angle.getRadians(),
+ CANSparkMax.ControlType.kPosition);
+
+ this.desiredState = desiredState;
+ }
+
+ public void resetEncoders() {
+ driveEncoder.setPosition(0);
+ }
+}
diff --git a/src/main/java/frc/utils/SwerveUtils.java b/src/main/java/frc/utils/SwerveUtils.java
new file mode 100644
index 0000000..937bc15
--- /dev/null
+++ b/src/main/java/frc/utils/SwerveUtils.java
@@ -0,0 +1,86 @@
+package frc.utils;
+
+public class SwerveUtils {
+
+ /**
+ * Steps a value towards a target with a specified step size.
+ *
+ * @param current The current or starting value. Can be positive or negative.
+ * @param target The target value the algorithm will step towards. Can be positive or negative.
+ * @param stepsize The maximum step size that can be taken.
+ * @return The new value for {@code _current} after performing the specified step towards the specified target.
+ */
+ public static double stepTowards(double current, double target, double stepsize) {
+ if(Math.abs(current - target) <= stepsize) {
+ return target;
+ } else if(target < current) {
+ return current - stepsize;
+ } else {
+ return current + stepsize;
+ }
+ }
+
+ /**
+ * Steps a value (angle) towards a target (angle) taking the shortest path with a specified step size.
+ *
+ * @param current The current or starting angle (in radians). Can lie outside the 0 to 2*PI range.
+ * @param target The target angle (in radians) the algorithm will step towards. Can lie outside the 0 to 2*PI range.
+ * @param stepsize The maximum step size that can be taken (in radians).
+ * @return The new angle (in radians) for {@code _current} after performing the specified step towards the specified target. This value will always lie in the range 0 to 2*PI
+ * (exclusive).
+ */
+ public static double stepTowardsCircular(double current, double target, double stepsize) {
+ current = wrapAngle(current);
+ target = wrapAngle(target);
+
+ double stepDirection = Math.signum(target - current);
+ double difference = Math.abs(current - target);
+
+ if(difference <= stepsize) {
+ return target;
+ } else if(difference > Math.PI) {
+ // does the system need to wrap over eventually?
+ // handle the special case where you can reach the target in one step while also wrapping
+ if(current + (2 * Math.PI) - target < stepsize || target + (2 * Math.PI) - current < stepsize) {
+ return target;
+ } else {
+ return wrapAngle(current - stepDirection * stepsize); // this will handle wrapping gracefully
+ }
+
+ } else {
+ return current + stepDirection * stepsize;
+ }
+ }
+
+ /**
+ * Finds the (unsigned) minimum difference between two angles including calculating across 0.
+ *
+ * @param angleA An angle (in radians).
+ * @param angleB An angle (in radians).
+ * @return The (unsigned) minimum difference between the two angles (in radians).
+ */
+ public static double angleDifference(double angleA, double angleB) {
+ double difference = Math.abs(angleA - angleB);
+ return difference > Math.PI ? (2 * Math.PI) - difference : difference;
+ }
+
+ /**
+ * Wraps an angle until it lies within the range from 0 to 2*PI (exclusive).
+ *
+ * @param angle The angle (in radians) to wrap. Can be positive or negative and can lie multiple wraps outside the output range.
+ * @return An angle (in radians) from 0 and 2*PI (exclusive).
+ */
+ public static double wrapAngle(double angle) {
+ double twoPi = 2 * Math.PI;
+
+ if(angle == twoPi) { // Handle this case separately to avoid floating point errors with the floor after the division in the case below
+ return 0.0;
+ } else if(angle > twoPi) {
+ return angle - twoPi * Math.floor(angle / twoPi);
+ } else if(angle < 0.0) {
+ return angle + twoPi * (Math.floor((-angle) / twoPi) + 1);
+ } else {
+ return angle;
+ }
+ }
+}
\ No newline at end of file
diff --git a/vendordeps/NavX.json b/vendordeps/NavX.json
new file mode 100644
index 0000000..2a29835
--- /dev/null
+++ b/vendordeps/NavX.json
@@ -0,0 +1,40 @@
+{
+ "fileName": "NavX.json",
+ "name": "NavX",
+ "version": "2024.0.1-beta-4",
+ "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.0.1-beta-4"
+ }
+ ],
+ "jniDependencies": [],
+ "cppDependencies": [
+ {
+ "groupId": "com.kauailabs.navx.frc",
+ "artifactId": "navx-frc-cpp",
+ "version": "2024.0.1-beta-4",
+ "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/PathplannerLib.json b/vendordeps/PathplannerLib.json
new file mode 100644
index 0000000..3e18a45
--- /dev/null
+++ b/vendordeps/PathplannerLib.json
@@ -0,0 +1,38 @@
+{
+ "fileName": "PathplannerLib.json",
+ "name": "PathplannerLib",
+ "version": "2024.0.0-beta-6.2",
+ "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
+ "frcYear": "2024",
+ "mavenUrls": [
+ "https://3015rangerrobotics.github.io/pathplannerlib/repo"
+ ],
+ "jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json",
+ "javaDependencies": [
+ {
+ "groupId": "com.pathplanner.lib",
+ "artifactId": "PathplannerLib-java",
+ "version": "2024.0.0-beta-6.2"
+ }
+ ],
+ "jniDependencies": [],
+ "cppDependencies": [
+ {
+ "groupId": "com.pathplanner.lib",
+ "artifactId": "PathplannerLib-cpp",
+ "version": "2024.0.0-beta-6.2",
+ "libName": "PathplannerLib",
+ "headerClassifier": "headers",
+ "sharedLibrary": false,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal",
+ "linuxathena",
+ "linuxarm32",
+ "linuxarm64"
+ ]
+ }
+ ]
+}
\ No newline at end of file
diff --git a/vendordeps/Phoenix5.json b/vendordeps/Phoenix5.json
new file mode 100644
index 0000000..d0fade6
--- /dev/null
+++ b/vendordeps/Phoenix5.json
@@ -0,0 +1,151 @@
+{
+ "fileName": "Phoenix5.json",
+ "name": "CTRE-Phoenix (v5)",
+ "version": "5.32.0-beta-5",
+ "frcYear": 2024,
+ "uuid": "ab676553-b602-441f-a38d-f1296eff6537",
+ "mavenUrls": [
+ "https://maven.ctr-electronics.com/release/"
+ ],
+ "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2024-beta-latest.json",
+ "requires": [
+ {
+ "uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
+ "errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.",
+ "offlineFileName": "Phoenix6.json",
+ "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-beta-latest.json"
+ }
+ ],
+ "javaDependencies": [
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "api-java",
+ "version": "5.32.0-beta-5"
+ },
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "wpiapi-java",
+ "version": "5.32.0-beta-5"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "cci",
+ "version": "5.32.0-beta-5",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "cci-sim",
+ "version": "5.32.0-beta-5",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "wpiapi-cpp",
+ "version": "5.32.0-beta-5",
+ "libName": "CTRE_Phoenix_WPI",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "api-cpp",
+ "version": "5.32.0-beta-5",
+ "libName": "CTRE_Phoenix",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "cci",
+ "version": "5.32.0-beta-5",
+ "libName": "CTRE_PhoenixCCI",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "wpiapi-cpp-sim",
+ "version": "5.32.0-beta-5",
+ "libName": "CTRE_Phoenix_WPISim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "api-cpp-sim",
+ "version": "5.32.0-beta-5",
+ "libName": "CTRE_PhoenixSim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "cci-sim",
+ "version": "5.32.0-beta-5",
+ "libName": "CTRE_PhoenixCCISim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ]
+}
\ No newline at end of file
diff --git a/vendordeps/Phoenix6.json b/vendordeps/Phoenix6.json
new file mode 100644
index 0000000..7020206
--- /dev/null
+++ b/vendordeps/Phoenix6.json
@@ -0,0 +1,339 @@
+{
+ "fileName": "Phoenix6.json",
+ "name": "CTRE-Phoenix (v6)",
+ "version": "24.0.0-beta-8",
+ "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-beta-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.0.0-beta-8"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "tools",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "tools-sim",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simTalonSRX",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simTalonFX",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simVictorSPX",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simPigeonIMU",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simCANCoder",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProTalonFX",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProCANcoder",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProPigeon2",
+ "version": "24.0.0-beta-8",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "wpiapi-cpp",
+ "version": "24.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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.0.0-beta-8",
+ "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/REVLib.json b/vendordeps/REVLib.json
new file mode 100644
index 0000000..0f3520e
--- /dev/null
+++ b/vendordeps/REVLib.json
@@ -0,0 +1,74 @@
+{
+ "fileName": "REVLib.json",
+ "name": "REVLib",
+ "version": "2024.2.0",
+ "frcYear": "2024",
+ "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
+ "mavenUrls": [
+ "https://maven.revrobotics.com/"
+ ],
+ "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json",
+ "javaDependencies": [
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "REVLib-java",
+ "version": "2024.2.0"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "REVLib-driver",
+ "version": "2024.2.0",
+ "skipInvalidPlatforms": true,
+ "isJar": false,
+ "validPlatforms": [
+ "windowsx86-64",
+ "windowsx86",
+ "linuxarm64",
+ "linuxx86-64",
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "REVLib-cpp",
+ "version": "2024.2.0",
+ "libName": "REVLib",
+ "headerClassifier": "headers",
+ "sharedLibrary": false,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "windowsx86",
+ "linuxarm64",
+ "linuxx86-64",
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
+ },
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "REVLib-driver",
+ "version": "2024.2.0",
+ "libName": "REVLibDriver",
+ "headerClassifier": "headers",
+ "sharedLibrary": false,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "windowsx86",
+ "linuxarm64",
+ "linuxx86-64",
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
+ }
+ ]
+}
\ 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"
+ ]
+ }
+ ]
+}