diff --git a/.github/workflows/Build_and_Simulate.yml b/.github/workflows/Build_and_Simulate.yml
new file mode 100644
index 0000000..0afbdc1
--- /dev/null
+++ b/.github/workflows/Build_and_Simulate.yml
@@ -0,0 +1,51 @@
+# This is a basic workflow to build robot code.
+
+name: Build_and_Simulate
+
+# Controls when the action will run. Triggers the workflow on push or pull request
+# events but only for the main branch.
+on:
+ push:
+ branches: [ main ]
+ pull_request:
+ branches: [ main ]
+
+# A workflow run is made up of one or more jobs that can run sequentially or in parallel
+jobs:
+ # This workflow contains a single job called "build"
+ BuildSim:
+ # The type of runner that the job will run on
+ runs-on: ubuntu-latest
+
+ # This grabs the WPILib docker container
+ container: wpilib/roborio-cross-ubuntu:2024-22.04
+
+ # Steps represent a sequence of tasks that will be executed as part of the job
+ steps:
+ # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it
+ - uses: actions/checkout@v4
+
+ # Declares the repository safe and not under dubious ownership.
+ - name: Add repository to git safe directories
+ run: git config --global --add safe.directory $GITHUB_WORKSPACE
+
+ # Grant execute permission for gradlew
+ - name: Grant execute permission for gradlew
+ run: chmod +x gradlew
+
+
+ # Runs a single command using the runners shell
+ - name: Build robot code
+ run: ./gradlew build
+
+ - name: Simulate Robot Code
+ id: Simulation
+ continue-on-error: true
+ run: |
+ timeout 15s ./gradlew simulateJava
+
+ - name: Check if simulation was able to run for full time or if it exited early
+ run: |
+ exit $Code
+ env:
+ Code: ${{steps.simulation.outcome == 'failure' && '0' || '1'}}
diff --git a/.vscode/settings.json b/.vscode/settings.json
index 612cdd0..cfb9086 100644
--- a/.vscode/settings.json
+++ b/.vscode/settings.json
@@ -56,5 +56,6 @@
"edu.wpi.first.math.proto.*",
"edu.wpi.first.math.**.proto.*",
"edu.wpi.first.math.**.struct.*",
- ]
+ ],
+ "java.format.settings.url": "eclipse-formatter.xml"
}
diff --git a/gradlew b/gradlew
old mode 100644
new mode 100755
diff --git a/simgui-ds.json b/simgui-ds.json
index 73cc713..9b518cc 100644
--- a/simgui-ds.json
+++ b/simgui-ds.json
@@ -15,9 +15,13 @@
"decayRate": 0.0,
"incKey": 82,
"keyRate": 0.009999999776482582
+ },
+ {
+ "decKey": 75,
+ "incKey": 76
}
],
- "axisCount": 3,
+ "axisCount": 5,
"buttonCount": 4,
"buttonKeys": [
90,
@@ -42,12 +46,10 @@
{
"axisConfig": [
{
- "decKey": 74,
- "incKey": 76
+ "decKey": 74
},
{
- "decKey": 73,
- "incKey": 75
+ "decKey": 73
}
],
"axisCount": 2,
@@ -88,5 +90,16 @@
"buttonCount": 0,
"povCount": 0
}
+ ],
+ "robotJoysticks": [
+ {
+ "guid": "030000005e0400008e02000014010000"
+ },
+ {
+ "guid": "030000004c050000c405000000000000"
+ },
+ {
+ "useGamepad": true
+ }
]
}
diff --git a/src/main/deploy/swerve/neo/controllerproperties.json b/src/main/deploy/swerve/neo/controllerproperties.json
new file mode 100644
index 0000000..669097e
--- /dev/null
+++ b/src/main/deploy/swerve/neo/controllerproperties.json
@@ -0,0 +1,8 @@
+{
+ "angleJoystickRadiusDeadband": 0.5,
+ "heading": {
+ "p": 0.4,
+ "i": 0,
+ "d": 0.01
+ }
+}
\ No newline at end of file
diff --git a/src/main/deploy/swerve/neo/modules/backleft.json b/src/main/deploy/swerve/neo/modules/backleft.json
new file mode 100644
index 0000000..6c6c7d9
--- /dev/null
+++ b/src/main/deploy/swerve/neo/modules/backleft.json
@@ -0,0 +1,26 @@
+{
+ "drive": {
+ "type": "sparkmax_neo",
+ "id": 7,
+ "canbus": null
+ },
+ "angle": {
+ "type": "sparkmax_neo",
+ "id": 8,
+ "canbus": null
+ },
+ "encoder": {
+ "type": "cancoder",
+ "id": 12,
+ "canbus": null
+ },
+ "inverted": {
+ "drive": false,
+ "angle": false
+ },
+ "absoluteEncoderOffset": 6.504,
+ "location": {
+ "front": -12,
+ "left": 12
+ }
+}
\ No newline at end of file
diff --git a/src/main/deploy/swerve/neo/modules/backright.json b/src/main/deploy/swerve/neo/modules/backright.json
new file mode 100644
index 0000000..4f9f082
--- /dev/null
+++ b/src/main/deploy/swerve/neo/modules/backright.json
@@ -0,0 +1,26 @@
+{
+ "drive": {
+ "type": "sparkmax_neo",
+ "id": 5,
+ "canbus": null
+ },
+ "angle": {
+ "type": "sparkmax_neo",
+ "id": 6,
+ "canbus": null
+ },
+ "encoder": {
+ "type": "cancoder",
+ "id": 11,
+ "canbus": null
+ },
+ "inverted": {
+ "drive": false,
+ "angle": false
+ },
+ "absoluteEncoderOffset": -18.281,
+ "location": {
+ "front": -12,
+ "left": -12
+ }
+}
\ No newline at end of file
diff --git a/src/main/deploy/swerve/neo/modules/frontleft.json b/src/main/deploy/swerve/neo/modules/frontleft.json
new file mode 100644
index 0000000..a3ef16b
--- /dev/null
+++ b/src/main/deploy/swerve/neo/modules/frontleft.json
@@ -0,0 +1,26 @@
+{
+ "drive": {
+ "type": "sparkmax_neo",
+ "id": 4,
+ "canbus": null
+ },
+ "angle": {
+ "type": "sparkmax_neo",
+ "id": 3,
+ "canbus": null
+ },
+ "encoder": {
+ "type": "cancoder",
+ "id": 9,
+ "canbus": null
+ },
+ "inverted": {
+ "drive": false,
+ "angle": false
+ },
+ "absoluteEncoderOffset": -114.609,
+ "location": {
+ "front": 12,
+ "left": 12
+ }
+}
\ No newline at end of file
diff --git a/src/main/deploy/swerve/neo/modules/frontright.json b/src/main/deploy/swerve/neo/modules/frontright.json
new file mode 100644
index 0000000..b60f22f
--- /dev/null
+++ b/src/main/deploy/swerve/neo/modules/frontright.json
@@ -0,0 +1,26 @@
+{
+ "drive": {
+ "type": "sparkmax_neo",
+ "id": 2,
+ "canbus": null
+ },
+ "angle": {
+ "type": "sparkmax_neo",
+ "id": 1,
+ "canbus": null
+ },
+ "encoder": {
+ "type": "cancoder",
+ "id": 10,
+ "canbus": null
+ },
+ "inverted": {
+ "drive": false,
+ "angle": false
+ },
+ "absoluteEncoderOffset": -50.977,
+ "location": {
+ "front": 12,
+ "left": -12
+ }
+}
\ No newline at end of file
diff --git a/src/main/deploy/swerve/neo/modules/physicalproperties.json b/src/main/deploy/swerve/neo/modules/physicalproperties.json
new file mode 100644
index 0000000..d7ae5ab
--- /dev/null
+++ b/src/main/deploy/swerve/neo/modules/physicalproperties.json
@@ -0,0 +1,23 @@
+{
+ "conversionFactors": {
+ "angle": {
+ "gearRatio": 12.8,
+ "factor": 0
+ },
+ "drive": {
+ "gearRatio": 8.14,
+ "diameter": 4,
+ "factor": 0
+ }
+ },
+ "currentLimit": {
+ "drive": 40,
+ "angle": 20
+ },
+ "rampRate": {
+ "drive": 0.25,
+ "angle": 0.25
+ },
+ "wheelGripCoefficientOfFriction": 1.19,
+ "optimalVoltage": 12
+}
\ No newline at end of file
diff --git a/src/main/deploy/swerve/neo/modules/pidfproperties.json b/src/main/deploy/swerve/neo/modules/pidfproperties.json
new file mode 100644
index 0000000..b494bce
--- /dev/null
+++ b/src/main/deploy/swerve/neo/modules/pidfproperties.json
@@ -0,0 +1,16 @@
+{
+ "drive": {
+ "p": 0.00023,
+ "i": 0.0000002,
+ "d": 1,
+ "f": 0,
+ "iz": 0
+ },
+ "angle": {
+ "p": 0.0020645,
+ "i": 0,
+ "d": 0,
+ "f": 0.001,
+ "iz": 0
+ }
+}
\ No newline at end of file
diff --git a/src/main/deploy/swerve/neo/swervedrive.json b/src/main/deploy/swerve/neo/swervedrive.json
new file mode 100644
index 0000000..fb2b0b8
--- /dev/null
+++ b/src/main/deploy/swerve/neo/swervedrive.json
@@ -0,0 +1,14 @@
+{
+ "imu": {
+ "type": "pigeon2",
+ "id": 13,
+ "canbus": "canivore"
+ },
+ "invertedIMU": true,
+ "modules": [
+ "frontleft.json",
+ "frontright.json",
+ "backleft.json",
+ "backright.json"
+ ]
+}
\ No newline at end of file
diff --git a/src/main/java/com/spartronics4915/frc2025/Constants.java b/src/main/java/com/spartronics4915/frc2025/Constants.java
index 2e0afec..9e35e0e 100644
--- a/src/main/java/com/spartronics4915/frc2025/Constants.java
+++ b/src/main/java/com/spartronics4915/frc2025/Constants.java
@@ -1,5 +1,46 @@
+// 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 com.spartronics4915.frc2025;
-public class Constants {
+import edu.wpi.first.math.util.Units;
+
+/**
+ * The Constants class provides a convenient place for teams to hold robot-wide
+ * numerical or boolean
+ * constants. This class should not be used for any other purpose. All constants
+ * should be declared
+ * globally (i.e. public static). Do not put anything functional in this class.
+ *
+ *
+ * It is advised to statically import this class (or one of its inner classes)
+ * wherever the
+ * constants are needed, to reduce verbosity.
+ */
+public final class Constants {
+ public static final class OI {
+ public static final int kDriverControllerPort = 0;
+ public static final int kOperatorControllerPort = 1;
+
+ public static final double kStickDeadband = 0.05;
+
+ public static final double kDriverTriggerDeadband = 0.3;
+ public static final double kOperatorTriggerDeadband = 0.3;
+ }
+
+ public static final class Drive {
+ public static final double kTrackWidth = Units.inchesToMeters(22.475);
+ public static final double kWheelbase = Units.inchesToMeters(22.475);
+ public static final double kChassisRadius = Math.hypot(
+ kTrackWidth / 2, kWheelbase / 2);
+
+ public static final double kMaxSpeed = Units.feetToMeters(15.1);
+ public static final double kMaxAngularSpeed = kMaxSpeed * Math.PI / kChassisRadius;
+
+ }
+ public static class OperatorConstants {
+ public static final int kDriverControllerPort = 0;
+ }
}
diff --git a/src/main/java/com/spartronics4915/frc2025/Main.java b/src/main/java/com/spartronics4915/frc2025/Main.java
index 19aead9..9de2677 100644
--- a/src/main/java/com/spartronics4915/frc2025/Main.java
+++ b/src/main/java/com/spartronics4915/frc2025/Main.java
@@ -6,9 +6,19 @@
import edu.wpi.first.wpilibj.RobotBase;
+/**
+ * Do NOT add any static variables to this class, or any initialization at all. Unless you know what
+ * you are doing, do not modify this file except to change the parameter class to the startRobot
+ * call.
+ */
public final class Main {
private Main() {}
+ /**
+ * Main initialization function. Do not perform any initialization here.
+ *
+ *
If you change your main robot class, change the parameter type.
+ */
public static void main(String... args) {
RobotBase.startRobot(Robot::new);
}
diff --git a/src/main/java/com/spartronics4915/frc2025/Robot.java b/src/main/java/com/spartronics4915/frc2025/Robot.java
index bfa4cc4..9fb4134 100644
--- a/src/main/java/com/spartronics4915/frc2025/Robot.java
+++ b/src/main/java/com/spartronics4915/frc2025/Robot.java
@@ -4,70 +4,103 @@
package com.spartronics4915.frc2025;
+import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
+/**
+ * The methods in this class are called automatically corresponding to each mode, as described in
+ * the TimedRobot documentation. If you change the name of this class or the package after creating
+ * this project, you must also update the Main.java file in the project.
+ */
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
- private RobotContainer m_robotContainer;
+ private final RobotContainer m_robotContainer;
- @Override
- public void robotInit() {
+ /**
+ * This function is run when the robot is first started up and should be used for any
+ * initialization code.
+ */
+ public Robot() {
+ // Instantiate our RobotContainer. This will perform all our button bindings, and put our
+ // autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();
}
+ /**
+ * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics
+ * that you want ran during disabled, autonomous, teleoperated and test.
+ *
+ *
This runs after the mode specific periodic functions, but before LiveWindow and
+ * SmartDashboard integrated updating.
+ */
@Override
public void robotPeriodic() {
+ // Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled
+ // commands, running already-scheduled commands, removing finished or interrupted commands,
+ // and running subsystem periodic() methods. This must be called from the robot's periodic
+ // block in order for anything in the Command-based framework to work.
CommandScheduler.getInstance().run();
}
+ /** This function is called once each time the robot enters Disabled mode. */
@Override
public void disabledInit() {}
@Override
public void disabledPeriodic() {}
- @Override
- public void disabledExit() {}
-
+ /** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
@Override
public void autonomousInit() {
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
+ // schedule the autonomous command (example)
if (m_autonomousCommand != null) {
m_autonomousCommand.schedule();
}
}
+ /** This function is called periodically during autonomous. */
@Override
public void autonomousPeriodic() {}
- @Override
- public void autonomousExit() {}
-
@Override
public void teleopInit() {
+ // This makes sure that the autonomous stops running when
+ // teleop starts running. If you want the autonomous to
+ // continue until interrupted by another command, remove
+ // this line or comment it out.
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();
}
}
+ /** This function is called periodically during operator control. */
@Override
public void teleopPeriodic() {}
- @Override
- public void teleopExit() {}
-
@Override
public void testInit() {
+ // Cancels all running commands at the start of test mode.
CommandScheduler.getInstance().cancelAll();
}
+ /** This function is called periodically during test mode. */
@Override
public void testPeriodic() {}
+ /** This function is called once when the robot is first started up. */
+ @Override
+ public void simulationInit() {
+
+ DriverStation.silenceJoystickConnectionWarning(true);
+ }
+
+ /** This function is called periodically whilst in simulation. */
@Override
- public void testExit() {}
+ public void simulationPeriodic() {}
+
}
diff --git a/src/main/java/com/spartronics4915/frc2025/RobotContainer.java b/src/main/java/com/spartronics4915/frc2025/RobotContainer.java
index 64aae19..e520cc3 100644
--- a/src/main/java/com/spartronics4915/frc2025/RobotContainer.java
+++ b/src/main/java/com/spartronics4915/frc2025/RobotContainer.java
@@ -4,17 +4,110 @@
package com.spartronics4915.frc2025;
+import com.spartronics4915.frc2025.Constants.OperatorConstants;
+import com.spartronics4915.frc2025.commands.Autos;
+import com.spartronics4915.frc2025.commands.SwerveTeleopCommand;
+import com.spartronics4915.frc2025.commands.vision.AimAndDriveBase;
+import com.spartronics4915.frc2025.subsystems.SwerveSubsystem;
+import com.spartronics4915.frc2025.subsystems.vision.NoteLocatorSim;
+import com.spartronics4915.frc2025.subsystems.vision.TargetDetectorInterface;
+
+import java.io.File;
+
+import edu.wpi.first.wpilibj.Filesystem;
+import edu.wpi.first.wpilibj.RobotBase;
+import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
+import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
+import edu.wpi.first.wpilibj2.command.button.Trigger;
+/**
+ * This class is where the bulk of the robot should be declared. Since
+ * Command-based is a
+ * "declarative" paradigm, very little robot logic should actually be handled in
+ * the {@link Robot}
+ * periodic methods (other than the scheduler calls). Instead, the structure of
+ * the robot (including
+ * subsystems, commands, and trigger mappings) should be declared here.
+ */
public class RobotContainer {
+ // The robot's subsystems and commands are defined here...
+ public final SwerveSubsystem swerveSubsystem = new SwerveSubsystem(new File(Filesystem.getDeployDirectory(),
+ "swerve/neo"));
+
+ private final CommandXboxController driverController = new CommandXboxController(
+ OperatorConstants.kDriverControllerPort);
+
+ public final TargetDetectorInterface noteDetector;
+
+ public final SwerveTeleopCommand swerveTeleopCommand = new SwerveTeleopCommand(swerveSubsystem, driverController);
+ // Replace with CommandPS4Controller or CommandJoystick if needed
+
+ private final SendableChooser autoChooser;
+ /**
+ * The container for the robot. Contains subsystems, OI devices, and commands.
+ */
public RobotContainer() {
+
+ if (RobotBase.isSimulation()) {
+ noteDetector = new NoteLocatorSim(swerveSubsystem);
+ } else {
+ noteDetector = null;
+ }
+
+ // Configure the trigger bindings
configureBindings();
+
+ // Need to initialize this here after vision is configured.
+ // Need to clean up initialization flow to make it more clear
+ autoChooser = buildAutoChooser();
+
}
- private void configureBindings() {}
+ /**
+ * Use this method to define your trigger->command mappings. Triggers can be
+ * created via the
+ * {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with
+ * an arbitrary
+ * predicate, or via the named factories in {@link
+ * edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for
+ * {@link
+ * CommandXboxController
+ * Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller
+ * PS4} controllers or
+ * {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight
+ * joysticks}.
+ */
+ private void configureBindings() {
+ driverController.a().whileTrue(new AimAndDriveBase(noteDetector, swerveSubsystem,
+ driverController.getHID(), 16, 360));
+
+ swerveSubsystem.setDefaultCommand(swerveTeleopCommand);
+ }
+
+ /**
+ * Use this to pass the autonomous command to the main {@link Robot} class.
+ *
+ * @return the command to run in autonomous
+ */
public Command getAutonomousCommand() {
- return Commands.print("No autonomous command configured");
+
+ // return Autos.driveToNote(swerveSubsystem, noteDetector);
+ return autoChooser.getSelected();
+
}
+
+ private SendableChooser buildAutoChooser() {
+ SendableChooser chooser = new SendableChooser();
+
+ chooser.setDefaultOption("None", Commands.none());
+ chooser.addOption("DriveToNote", Autos.driveToNote(swerveSubsystem, noteDetector));
+ SmartDashboard.putData("Auto Chooser", chooser);
+
+ return chooser;
+ }
+
}
diff --git a/src/main/java/com/spartronics4915/frc2025/commands/Autos.java b/src/main/java/com/spartronics4915/frc2025/commands/Autos.java
new file mode 100644
index 0000000..ed1ae46
--- /dev/null
+++ b/src/main/java/com/spartronics4915/frc2025/commands/Autos.java
@@ -0,0 +1,29 @@
+// 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 com.spartronics4915.frc2025.commands;
+
+import com.spartronics4915.frc2025.commands.vision.AimDriveToTargetWIthTimeout;
+import com.spartronics4915.frc2025.subsystems.SwerveSubsystem;
+import com.spartronics4915.frc2025.subsystems.vision.TargetDetectorInterface;
+import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
+import edu.wpi.first.wpilibj2.command.Command;
+
+public final class Autos {
+ /** Example static factory for an autonomous command. */
+ public static Command moveToPointAuto(SwerveSubsystem swerve) {
+
+ Translation2d targetPose = new Translation2d(2.9, 7);
+ Constraints driveConstraints = new Constraints(2, 2);
+ return new DriveToPointCommand(targetPose, driveConstraints,
+ 0.2, 0.1, swerve);
+ }
+
+ public static Command driveToNote(SwerveSubsystem swerve, TargetDetectorInterface detector) {
+
+ return new AimDriveToTargetWIthTimeout(detector, swerve, 4, 0.5, 180).andThen(swerve.stopChassisCommand());
+ }
+
+}
diff --git a/src/main/java/com/spartronics4915/frc2025/commands/DriveToPointCommand.java b/src/main/java/com/spartronics4915/frc2025/commands/DriveToPointCommand.java
new file mode 100644
index 0000000..a9b6604
--- /dev/null
+++ b/src/main/java/com/spartronics4915/frc2025/commands/DriveToPointCommand.java
@@ -0,0 +1,93 @@
+package com.spartronics4915.frc2025.commands;
+
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.kinematics.ChassisSpeeds;
+import edu.wpi.first.math.trajectory.TrapezoidProfile;
+import edu.wpi.first.math.trajectory.TrapezoidProfile.State;
+import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
+import edu.wpi.first.wpilibj2.command.Command;
+import com.spartronics4915.frc2025.subsystems.SwerveSubsystem;
+
+public class DriveToPointCommand extends Command {
+
+ private final Translation2d targetPoint;
+ private final TrapezoidProfile translationProfile;
+ private final SwerveSubsystem swerve;
+ private final double closeEnoughThreshold;
+ private double velocitySetpoint;
+ private boolean nearGoal;
+ private final double minimumSpeed;
+
+ /*
+ * Command that uses a trapezoidal profile to drive to a point in a smooth
+ * fashion.
+ */
+
+ public DriveToPointCommand(Translation2d targetPoint, Constraints translationContraints,
+ double closeEnoughThreshold, double minimumSpeed,
+ SwerveSubsystem swerve) {
+ this.targetPoint = targetPoint;
+ this.translationProfile = new TrapezoidProfile(translationContraints);
+ this.swerve = swerve;
+ this.closeEnoughThreshold = closeEnoughThreshold;
+ this.minimumSpeed = minimumSpeed;
+
+ velocitySetpoint = 0;
+ nearGoal = false;
+
+ addRequirements(swerve);
+ }
+
+ @Override
+ public void initialize() {
+
+ velocitySetpoint = 0;
+ nearGoal = false;
+ }
+
+ @Override
+ public void execute() {
+
+ Pose2d currPose = swerve.getPose();
+ Translation2d translationToTarget = targetPoint.minus(currPose.getTranslation());
+ double distanceRemaining = translationToTarget.getNorm();
+
+ if((distanceRemaining < closeEnoughThreshold) || nearGoal) {
+
+ nearGoal = true;
+ return;
+ }
+ // ChassisSpeeds currChassisSpeeds = swerve.getFieldVelocity();
+ // double currVelocity = Math.hypot(currChassisSpeeds.vxMetersPerSecond,
+ // currChassisSpeeds.vyMetersPerSecond);
+
+ final double dT = 1 / 50.;
+
+ State goalState = new State(distanceRemaining, 0);
+ State currentState = new State(0, velocitySetpoint);
+ State outputState = translationProfile.calculate(dT, currentState, goalState);
+
+ double driveVelocity = outputState.velocity;
+
+ if(driveVelocity < minimumSpeed) {
+ driveVelocity = minimumSpeed;
+ }
+
+ Translation2d driveTranslation = translationToTarget.div(translationToTarget.getNorm())
+ .times(driveVelocity);
+
+ ChassisSpeeds newChassisSpeeds = new ChassisSpeeds(driveTranslation.getX(),
+ driveTranslation.getY(), 0);
+
+ swerve.driveFieldOriented(newChassisSpeeds);
+ velocitySetpoint = outputState.velocity;
+ }
+
+ @Override
+ public boolean isFinished() {
+
+ return nearGoal;
+ }
+
+}
diff --git a/src/main/java/com/spartronics4915/frc2025/commands/SwerveTeleopCommand.java b/src/main/java/com/spartronics4915/frc2025/commands/SwerveTeleopCommand.java
new file mode 100644
index 0000000..73fbc9b
--- /dev/null
+++ b/src/main/java/com/spartronics4915/frc2025/commands/SwerveTeleopCommand.java
@@ -0,0 +1,87 @@
+package com.spartronics4915.frc2025.commands;
+
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.kinematics.ChassisSpeeds;
+import edu.wpi.first.wpilibj.DriverStation;
+import edu.wpi.first.wpilibj.RobotBase;
+import edu.wpi.first.wpilibj.XboxController;
+import edu.wpi.first.wpilibj.DriverStation.Alliance;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
+import com.spartronics4915.frc2025.Constants.Drive;
+import com.spartronics4915.frc2025.Constants.OI;
+import com.spartronics4915.frc2025.subsystems.SwerveSubsystem;
+
+public class SwerveTeleopCommand extends Command {
+
+ private final SwerveSubsystem swerveSubsystem;
+ private final CommandXboxController driverController;
+ private boolean useFieldRelative;
+
+ public SwerveTeleopCommand(SwerveSubsystem swerveSubsystem, CommandXboxController driverController) {
+
+ this.swerveSubsystem = swerveSubsystem;
+ this.driverController = driverController;
+
+ setFieldRelative(true);
+ addRequirements(swerveSubsystem);
+
+ }
+
+ static public ChassisSpeeds computeVelocitiesFromController(XboxController driverController) {
+
+ ChassisSpeeds cs = new ChassisSpeeds();
+
+ // Need to verify that we are using the right axes.
+ final double inputxraw = driverController.getLeftY() * -1.0;
+ final double inputyraw = driverController.getLeftX() * -1.0;
+ final double inputomegaraw;
+ if (RobotBase.isSimulation()) {
+ inputomegaraw = driverController.getRawAxis(3) * -1.0;
+ } else {
+ inputomegaraw = driverController.getRightY() * -1.0; // consider changing from angular velocity
+ // control to direct angle control
+ }
+
+ final double inputx = applyResponseCurve(MathUtil.applyDeadband(inputxraw, OI.kStickDeadband));
+ final double inputy = applyResponseCurve(MathUtil.applyDeadband(inputyraw, OI.kStickDeadband));
+ final double inputomega = applyResponseCurve(MathUtil.applyDeadband(inputomegaraw, OI.kStickDeadband));
+
+ cs.vxMetersPerSecond = inputx * Drive.kMaxSpeed;
+ cs.vyMetersPerSecond = inputy * Drive.kMaxSpeed;
+ cs.omegaRadiansPerSecond = inputomega * Drive.kMaxAngularSpeed;
+
+ return cs;
+ }
+
+ @Override
+ public void execute() {
+
+ ChassisSpeeds cs = computeVelocitiesFromController(driverController.getHID());
+
+ boolean useFieldRelative = getFieldRelative();
+ if (DriverStation.getAlliance().isPresent() && DriverStation.getAlliance().get() == Alliance.Red
+ && useFieldRelative) {
+ cs.vxMetersPerSecond = -cs.vxMetersPerSecond;
+ cs.vyMetersPerSecond = -cs.vyMetersPerSecond;
+ }
+
+ if (useFieldRelative) {
+ swerveSubsystem.driveFieldOriented(cs);
+ } else {
+ swerveSubsystem.drive(cs);
+ }
+ }
+
+ static private double applyResponseCurve(double x) {
+ return Math.signum(x) * Math.pow(x, 2);
+ }
+
+ public void setFieldRelative(boolean fieldRelative) {
+ useFieldRelative = fieldRelative;
+ }
+
+ public boolean getFieldRelative() {
+ return useFieldRelative;
+ }
+}
diff --git a/src/main/java/com/spartronics4915/frc2025/commands/vision/AimAndDriveBase.java b/src/main/java/com/spartronics4915/frc2025/commands/vision/AimAndDriveBase.java
new file mode 100644
index 0000000..dcbb62d
--- /dev/null
+++ b/src/main/java/com/spartronics4915/frc2025/commands/vision/AimAndDriveBase.java
@@ -0,0 +1,59 @@
+package com.spartronics4915.frc2025.commands.vision;
+
+import java.util.Optional;
+
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.controller.PIDController;
+import edu.wpi.first.math.kinematics.ChassisSpeeds;
+import edu.wpi.first.wpilibj.XboxController;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import edu.wpi.first.wpilibj2.command.Command;
+import com.spartronics4915.frc2025.commands.SwerveTeleopCommand;
+import com.spartronics4915.frc2025.subsystems.SwerveSubsystem;
+import com.spartronics4915.frc2025.subsystems.vision.TargetDetectorInterface;
+import com.spartronics4915.frc2025.subsystems.vision.TargetDetectorInterface.Detection;
+
+public class AimAndDriveBase extends Command {
+
+ private final TargetDetectorInterface targetDetector;
+ private final SwerveSubsystem swerveSubsystem;
+ private final PIDController pidController;
+ private final double maxRotVelocity;
+ private final XboxController driverController;
+
+ public AimAndDriveBase(TargetDetectorInterface targetDetector, SwerveSubsystem swerveSubsystem,
+ XboxController driverController,
+ double kP, double maxRotVelocity) {
+
+ this.targetDetector = targetDetector;
+ this.swerveSubsystem = swerveSubsystem;
+ this.pidController = new PIDController(kP, 0, 0);
+ this.maxRotVelocity = maxRotVelocity;
+ this.driverController = driverController;
+ }
+
+ @Override
+ public void execute() {
+
+ ChassisSpeeds cs = SwerveTeleopCommand.computeVelocitiesFromController(driverController);
+ Optional detection = targetDetector.getClosestVisibleTarget();
+
+ // Set the rotational velocity to zero because it will be replaced later.
+ // If there is no detection, it will drive forward
+ cs.omegaRadiansPerSecond = 0;
+
+ if(detection.isPresent()) {
+
+ double tx;
+
+ tx = detection.get().tx();
+ double angleVelocity = pidController.calculate(tx, 0);
+ angleVelocity = MathUtil.clamp(angleVelocity, -this.maxRotVelocity, this.maxRotVelocity);
+ SmartDashboard.putNumber("angleVelocity", angleVelocity);
+ double inputRotVelocity = angleVelocity / 180 * Math.PI;
+ cs.omegaRadiansPerSecond = inputRotVelocity;
+ }
+
+ swerveSubsystem.drive(cs);
+ }
+}
diff --git a/src/main/java/com/spartronics4915/frc2025/commands/vision/AimDriveToTargetWIthTimeout.java b/src/main/java/com/spartronics4915/frc2025/commands/vision/AimDriveToTargetWIthTimeout.java
new file mode 100644
index 0000000..97ed3b6
--- /dev/null
+++ b/src/main/java/com/spartronics4915/frc2025/commands/vision/AimDriveToTargetWIthTimeout.java
@@ -0,0 +1,120 @@
+package com.spartronics4915.frc2025.commands.vision;
+
+import java.util.Optional;
+
+import edu.wpi.first.math.MathUtil;
+import edu.wpi.first.math.controller.PIDController;
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.kinematics.ChassisSpeeds;
+import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj2.command.Command;
+import com.spartronics4915.frc2025.subsystems.SwerveSubsystem;
+import com.spartronics4915.frc2025.subsystems.vision.TargetDetectorInterface;
+import com.spartronics4915.frc2025.subsystems.vision.TargetDetectorInterface.Detection;
+
+public class AimDriveToTargetWIthTimeout extends Command {
+
+ private final TargetDetectorInterface targetDetector;
+ private final double timeoutThreshold;
+ private Timer timeoutTimer;
+ private final SwerveSubsystem swerveSubsystem;
+ private boolean finished;
+ private Rotation2d lastHeadingSetpoint;
+ private final PIDController pidController;
+ private final double maxRotVelocity;
+
+ // The default behavior is that the command will keep driving towards the last
+ // detected location
+ // if the detection is lost, until the timeout. At the timeout, it just exits,
+ // no new drive commands
+ // are issued. It is up to the following command to issue the next step to the
+ // robot.
+
+ // TODO: Add a max velocity magnitude to clamp.
+
+ public AimDriveToTargetWIthTimeout(TargetDetectorInterface targetDetector, SwerveSubsystem swerveSubsystem,
+ double kP, double timeoutThreshold, double maxRotVelocity) {
+
+ this.targetDetector = targetDetector;
+ this.timeoutThreshold = timeoutThreshold;
+ this.swerveSubsystem = swerveSubsystem;
+ this.pidController = new PIDController(kP, 0, 0);
+ this.maxRotVelocity = maxRotVelocity;
+
+ timeoutTimer = new Timer();
+ finished = false;
+
+ addRequirements(swerveSubsystem);
+ }
+
+ @Override
+ public void initialize() {
+ timeoutTimer.stop();
+ timeoutTimer.reset();
+
+ lastHeadingSetpoint = null;
+ }
+
+ @Override
+ public boolean isFinished() {
+ return finished;
+ }
+
+ @Override
+ public void execute() {
+
+ Optional detection = targetDetector.getClosestVisibleTarget();
+ if (lastHeadingSetpoint == null) {
+ lastHeadingSetpoint = swerveSubsystem.getPose().getRotation();
+ }
+
+ Rotation2d currHeadingSetpoint;
+ double tx;
+ if (finished) {
+ return;
+ }
+
+ if (detection.isEmpty()) {
+
+ timeoutTimer.start();
+ // If the timer is running and has passed the threshold, return.
+ if (timeoutTimer.hasElapsed(timeoutThreshold)) {
+ finished = true;
+ return;
+ } else {
+ // Otherwise, don't update the setpoint, that way the motion continues smoothly
+ // until we
+ // reacquire
+
+ currHeadingSetpoint = lastHeadingSetpoint;
+ tx = currHeadingSetpoint.minus(swerveSubsystem.getPose().getRotation()).getDegrees();
+ }
+ } else {
+
+ tx = detection.get().tx();
+
+ currHeadingSetpoint = swerveSubsystem.getPose().getRotation().plus(Rotation2d.fromDegrees(tx));
+ lastHeadingSetpoint = currHeadingSetpoint;
+
+ double angleVelocity = pidController.calculate(tx, 0);
+
+ angleVelocity = MathUtil.clamp(angleVelocity, -this.maxRotVelocity, this.maxRotVelocity);
+
+ double inputAngleVelocity = angleVelocity / 180 * Math.PI;
+
+ swerveSubsystem.drive(new ChassisSpeeds(computeForwardVelocity(), 0, inputAngleVelocity));
+
+ if (timeoutTimer.isRunning()) {
+ // If it is not empty, we can reset the timeout timer. Because we got a
+ // detection
+ timeoutTimer.stop();
+ timeoutTimer.reset();
+ }
+ }
+
+ }
+
+ public double computeForwardVelocity() {
+ return 1;
+ }
+}
diff --git a/src/main/java/com/spartronics4915/frc2025/subsystems/SwerveSubsystem.java b/src/main/java/com/spartronics4915/frc2025/subsystems/SwerveSubsystem.java
new file mode 100644
index 0000000..857b978
--- /dev/null
+++ b/src/main/java/com/spartronics4915/frc2025/subsystems/SwerveSubsystem.java
@@ -0,0 +1,82 @@
+package com.spartronics4915.frc2025.subsystems;
+
+import java.io.File;
+import java.io.IOException;
+
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.kinematics.ChassisSpeeds;
+import edu.wpi.first.wpilibj2.command.Command;
+import edu.wpi.first.wpilibj2.command.Commands;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+import swervelib.SwerveDrive;
+import swervelib.parser.SwerveParser;
+import com.spartronics4915.frc2025.Constants.Drive;
+
+import static edu.wpi.first.units.Units.Meter;
+
+public class SwerveSubsystem extends SubsystemBase {
+
+ private final SwerveDrive swerveDrive;
+
+ public SwerveSubsystem(File directory) {
+
+ try {
+ swerveDrive = new SwerveParser(directory).createSwerveDrive(Drive.kMaxSpeed,
+ new Pose2d(new Translation2d(Meter.of(2),
+ Meter.of(5)),
+ Rotation2d.fromDegrees(180)));
+
+ } catch (IOException e) {
+ throw new RuntimeException(e);
+ }
+ swerveDrive.setHeadingCorrection(false); // Heading correction should only be used while controlling the robot
+ // via angle.
+ swerveDrive.setCosineCompensator(false);// !SwerveDriveTelemetry.isSimulation); // Disables cosine compensation
+ // for simulations since it causes discrepancies not seen in real life.
+ swerveDrive.setAngularVelocityCompensation(true,
+ true,
+ 0.1); // Correct for skew that gets worse as angular velocity increases. Start with a
+ // coefficient of 0.1.
+ swerveDrive.setModuleEncoderAutoSynchronize(false,
+ 1); // Enable if you want to resynchronize your absolute encoders and motor encoders
+ // periodically when they are not moving.
+ swerveDrive.pushOffsetsToEncoders(); // Set the absolute encoder to be used over the internal encoder and push
+ // the offsets onto it. Throws warning if not possible
+
+ swerveDrive.resetOdometry(new Pose2d(1.5, 5, Rotation2d.fromDegrees(45)));
+
+ }
+
+ // External API for sending explicit driving commands to the swerve drive
+ public void drive(ChassisSpeeds chassisSpeeds) {
+
+ swerveDrive.drive(chassisSpeeds);
+ }
+
+ public void driveFieldOriented(ChassisSpeeds chassisSpeeds) {
+ swerveDrive.driveFieldOriented(chassisSpeeds);
+ }
+
+ public Pose2d getPose() {
+
+ return swerveDrive.getPose();
+ }
+
+ public ChassisSpeeds getFieldVelocity() {
+
+ return swerveDrive.getFieldVelocity();
+ }
+
+ public void stopChassis() {
+
+ drive(new ChassisSpeeds());
+ }
+
+ public Command stopChassisCommand() {
+
+ return Commands.runOnce(() -> stopChassis(), this);
+ }
+
+}
diff --git a/src/main/java/com/spartronics4915/frc2025/subsystems/vision/NoteLocatorSim.java b/src/main/java/com/spartronics4915/frc2025/subsystems/vision/NoteLocatorSim.java
new file mode 100644
index 0000000..c8d10b6
--- /dev/null
+++ b/src/main/java/com/spartronics4915/frc2025/subsystems/vision/NoteLocatorSim.java
@@ -0,0 +1,96 @@
+package com.spartronics4915.frc2025.subsystems.vision;
+
+import java.util.ArrayList;
+import java.util.List;
+import java.util.OptionalDouble;
+// import java.util.Random;
+import java.util.Optional;
+
+import edu.wpi.first.math.geometry.Pose2d;
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.geometry.Translation2d;
+import com.spartronics4915.frc2025.subsystems.SwerveSubsystem;
+
+public class NoteLocatorSim implements TargetDetectorInterface {
+
+ // private final Random random = new Random();
+
+ SwerveSubsystem swerveDrive;
+ final static ArrayList noteLocations = new ArrayList<>(List.of(new Translation2d(2.9, 7),
+ new Translation2d(2.9, 5.5), new Translation2d(2.9, 4.1)));
+
+ public NoteLocatorSim(SwerveSubsystem swerveDrive) {
+ this.swerveDrive = swerveDrive;
+ }
+
+ public Optional getClosestVisibleTarget() {
+
+ double minDist = 1e6;
+ Pose2d currPose = swerveDrive.getPose();
+ Translation2d currPosition = currPose.getTranslation();
+
+ final double MAX_DEGREES = 27;
+ final double ROBOT_HEIGHT = 0.3; // Meters
+ // final double VERT_TOP_VISIBILITY_THRESH = -20; // Degrees
+ final double VERT_BOT_VISIBILITY_THRESH = -40; // Degrees
+ Optional bestNote = Optional.empty();
+
+ for (Translation2d currNoteLoc : noteLocations) {
+ Translation2d botNoteVec = currNoteLoc.minus(currPosition);
+ Rotation2d botNoteAngle = botNoteVec.getAngle();
+ Rotation2d viewCenterNoteAngle = currPose.getRotation().minus(botNoteAngle);
+ Rotation2d vertAngle = new Rotation2d(botNoteVec.getNorm(), -ROBOT_HEIGHT);
+ double dist = botNoteVec.getNorm();
+
+ if (Math.abs(viewCenterNoteAngle.getDegrees()) > MAX_DEGREES) {
+ continue;
+ }
+
+ double vertAngleDegrees = vertAngle.getDegrees();
+ if ((vertAngleDegrees < VERT_BOT_VISIBILITY_THRESH)) {
+ continue;
+ }
+
+ if (dist < minDist) {
+
+ bestNote = Optional
+ .of(new Detection(viewCenterNoteAngle.getDegrees(), vertAngle.getDegrees(), dist));
+ minDist = dist;
+ }
+ // System.out.println("view center: " + viewCenterNoteAngle.getDegrees() + " " +
+ // "vert: "
+ // + vertAngle.getDegrees() + " " + currPosition + " " + currNoteLoc);
+
+ }
+
+ // if (bestNote.isPresent()) {
+ // double prob = random.nextDouble();
+
+ // if (prob < 0.25) {
+ // System.out.println("Dropped out");
+ // bestNote = Optional.empty();
+ // }
+ // }
+
+ return bestNote;
+ }
+
+ // Assuming that we don't care about Ty, just return a constant value.
+
+ public double getTy() {
+ return 10;
+
+ }
+
+ // Finds the angle from the center of the closest note. Will filter over 27
+ // degrees
+ // TODO: This still needs to be completed.
+
+ public OptionalDouble getTx() {
+ // final double MAX_ANGLE_DEGREES = 27;
+
+ return OptionalDouble.of(10);
+
+ }
+
+}
diff --git a/src/main/java/com/spartronics4915/frc2025/subsystems/vision/TargetDetectorInterface.java b/src/main/java/com/spartronics4915/frc2025/subsystems/vision/TargetDetectorInterface.java
new file mode 100644
index 0000000..85e1f93
--- /dev/null
+++ b/src/main/java/com/spartronics4915/frc2025/subsystems/vision/TargetDetectorInterface.java
@@ -0,0 +1,11 @@
+package com.spartronics4915.frc2025.subsystems.vision;
+
+import java.util.Optional;
+
+public interface TargetDetectorInterface {
+
+ public static record Detection(double tx, double ty, double estimatedDistance) {};
+
+ public Optional getClosestVisibleTarget();
+
+}
diff --git a/vendordeps/PathplannerLib-2025.1.1.json b/vendordeps/PathplannerLib-2025.1.1.json
new file mode 100644
index 0000000..6322388
--- /dev/null
+++ b/vendordeps/PathplannerLib-2025.1.1.json
@@ -0,0 +1,38 @@
+{
+ "fileName": "PathplannerLib-2025.1.1.json",
+ "name": "PathplannerLib",
+ "version": "2025.1.1",
+ "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
+ "frcYear": "2025",
+ "mavenUrls": [
+ "https://3015rangerrobotics.github.io/pathplannerlib/repo"
+ ],
+ "jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json",
+ "javaDependencies": [
+ {
+ "groupId": "com.pathplanner.lib",
+ "artifactId": "PathplannerLib-java",
+ "version": "2025.1.1"
+ }
+ ],
+ "jniDependencies": [],
+ "cppDependencies": [
+ {
+ "groupId": "com.pathplanner.lib",
+ "artifactId": "PathplannerLib-cpp",
+ "version": "2025.1.1",
+ "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-5.35.0.json b/vendordeps/Phoenix5-5.35.0.json
new file mode 100644
index 0000000..e2e3247
--- /dev/null
+++ b/vendordeps/Phoenix5-5.35.0.json
@@ -0,0 +1,171 @@
+{
+ "fileName": "Phoenix5-5.35.0.json",
+ "name": "CTRE-Phoenix (v5)",
+ "version": "5.35.0",
+ "frcYear": "2025",
+ "uuid": "ab676553-b602-441f-a38d-f1296eff6537",
+ "mavenUrls": [
+ "https://maven.ctr-electronics.com/release/"
+ ],
+ "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-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-frc2025-latest.json",
+ "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json"
+ }
+ ],
+ "conflictsWith": [
+ {
+ "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af",
+ "errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.",
+ "offlineFileName": "Phoenix6-replay-frc2025-latest.json"
+ },
+ {
+ "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df",
+ "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.",
+ "offlineFileName": "Phoenix5-replay-frc2025-latest.json"
+ }
+ ],
+ "javaDependencies": [
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "api-java",
+ "version": "5.35.0"
+ },
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "wpiapi-java",
+ "version": "5.35.0"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "cci",
+ "version": "5.35.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "cci-sim",
+ "version": "5.35.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "wpiapi-cpp",
+ "version": "5.35.0",
+ "libName": "CTRE_Phoenix_WPI",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "api-cpp",
+ "version": "5.35.0",
+ "libName": "CTRE_Phoenix",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix",
+ "artifactId": "cci",
+ "version": "5.35.0",
+ "libName": "CTRE_PhoenixCCI",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "wpiapi-cpp-sim",
+ "version": "5.35.0",
+ "libName": "CTRE_Phoenix_WPISim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "api-cpp-sim",
+ "version": "5.35.0",
+ "libName": "CTRE_PhoenixSim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix.sim",
+ "artifactId": "cci-sim",
+ "version": "5.35.0",
+ "libName": "CTRE_PhoenixCCISim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ]
+}
\ No newline at end of file
diff --git a/vendordeps/Phoenix6-25.1.0.json b/vendordeps/Phoenix6-25.1.0.json
new file mode 100644
index 0000000..473f6a8
--- /dev/null
+++ b/vendordeps/Phoenix6-25.1.0.json
@@ -0,0 +1,389 @@
+{
+ "fileName": "Phoenix6-25.1.0.json",
+ "name": "CTRE-Phoenix (v6)",
+ "version": "25.1.0",
+ "frcYear": "2025",
+ "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-frc2025-latest.json",
+ "conflictsWith": [
+ {
+ "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af",
+ "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.",
+ "offlineFileName": "Phoenix6-replay-frc2025-latest.json"
+ }
+ ],
+ "javaDependencies": [
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "wpiapi-java",
+ "version": "25.1.0"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "api-cpp",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "tools",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "api-cpp-sim",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "tools-sim",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simTalonSRX",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simVictorSPX",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simPigeonIMU",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simCANCoder",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProTalonFX",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProCANcoder",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProPigeon2",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProCANrange",
+ "version": "25.1.0",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "wpiapi-cpp",
+ "version": "25.1.0",
+ "libName": "CTRE_Phoenix6_WPI",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6",
+ "artifactId": "tools",
+ "version": "25.1.0",
+ "libName": "CTRE_PhoenixTools",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "linuxathena"
+ ],
+ "simMode": "hwsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "wpiapi-cpp-sim",
+ "version": "25.1.0",
+ "libName": "CTRE_Phoenix6_WPISim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "tools-sim",
+ "version": "25.1.0",
+ "libName": "CTRE_PhoenixTools_Sim",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simTalonSRX",
+ "version": "25.1.0",
+ "libName": "CTRE_SimTalonSRX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simVictorSPX",
+ "version": "25.1.0",
+ "libName": "CTRE_SimVictorSPX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simPigeonIMU",
+ "version": "25.1.0",
+ "libName": "CTRE_SimPigeonIMU",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simCANCoder",
+ "version": "25.1.0",
+ "libName": "CTRE_SimCANCoder",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProTalonFX",
+ "version": "25.1.0",
+ "libName": "CTRE_SimProTalonFX",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProCANcoder",
+ "version": "25.1.0",
+ "libName": "CTRE_SimProCANcoder",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProPigeon2",
+ "version": "25.1.0",
+ "libName": "CTRE_SimProPigeon2",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ },
+ {
+ "groupId": "com.ctre.phoenix6.sim",
+ "artifactId": "simProCANrange",
+ "version": "25.1.0",
+ "libName": "CTRE_SimProCANrange",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxx86-64",
+ "linuxarm64",
+ "osxuniversal"
+ ],
+ "simMode": "swsim"
+ }
+ ]
+}
\ No newline at end of file
diff --git a/vendordeps/REVLib-2025.0.0.json b/vendordeps/REVLib-2025.0.0.json
new file mode 100644
index 0000000..cde6011
--- /dev/null
+++ b/vendordeps/REVLib-2025.0.0.json
@@ -0,0 +1,74 @@
+{
+ "fileName": "REVLib-2025.0.0.json",
+ "name": "REVLib",
+ "version": "2025.0.0",
+ "frcYear": "2025",
+ "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
+ "mavenUrls": [
+ "https://maven.revrobotics.com/"
+ ],
+ "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json",
+ "javaDependencies": [
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "REVLib-java",
+ "version": "2025.0.0"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "REVLib-driver",
+ "version": "2025.0.0",
+ "skipInvalidPlatforms": true,
+ "isJar": false,
+ "validPlatforms": [
+ "windowsx86-64",
+ "windowsx86",
+ "linuxarm64",
+ "linuxx86-64",
+ "linuxathena",
+ "linuxarm32",
+ "osxuniversal"
+ ]
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "com.revrobotics.frc",
+ "artifactId": "REVLib-cpp",
+ "version": "2025.0.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": "2025.0.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/ReduxLib_2025.json b/vendordeps/ReduxLib_2025.json
new file mode 100644
index 0000000..6988e45
--- /dev/null
+++ b/vendordeps/ReduxLib_2025.json
@@ -0,0 +1,72 @@
+{
+ "fileName": "ReduxLib_2025.json",
+ "name": "ReduxLib",
+ "version": "2025.0.0-beta2",
+ "frcYear": 2025,
+ "uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd",
+ "mavenUrls": [
+ "https://maven.reduxrobotics.com/"
+ ],
+ "jsonUrl": "https://frcsdk.reduxrobotics.com/ReduxLib_2025.json",
+ "javaDependencies": [
+ {
+ "groupId": "com.reduxrobotics.frc",
+ "artifactId": "ReduxLib-java",
+ "version": "2025.0.0-beta2"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "groupId": "com.reduxrobotics.frc",
+ "artifactId": "ReduxLib-driver",
+ "version": "2025.0.0-beta2",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "linuxathena",
+ "linuxx86-64",
+ "linuxarm32",
+ "linuxarm64",
+ "osxuniversal",
+ "windowsx86-64"
+ ]
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "com.reduxrobotics.frc",
+ "artifactId": "ReduxLib-cpp",
+ "version": "2025.0.0-beta2",
+ "libName": "ReduxLib",
+ "headerClassifier": "headers",
+ "sourcesClassifier": "sources",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "linuxathena",
+ "linuxx86-64",
+ "linuxarm32",
+ "linuxarm64",
+ "osxuniversal",
+ "windowsx86-64"
+ ]
+ },
+ {
+ "groupId": "com.reduxrobotics.frc",
+ "artifactId": "ReduxLib-driver",
+ "version": "2025.0.0-beta2",
+ "libName": "ReduxCore",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "linuxathena",
+ "linuxx86-64",
+ "linuxarm32",
+ "linuxarm64",
+ "osxuniversal",
+ "windowsx86-64"
+ ]
+ }
+ ]
+}
\ No newline at end of file
diff --git a/vendordeps/Studica-2025.1.1-beta-3.json b/vendordeps/Studica-2025.1.1-beta-3.json
new file mode 100644
index 0000000..2f64aaf
--- /dev/null
+++ b/vendordeps/Studica-2025.1.1-beta-3.json
@@ -0,0 +1,71 @@
+{
+ "fileName": "Studica-2025.1.1-beta-3.json",
+ "name": "Studica",
+ "version": "2025.1.1-beta-3",
+ "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
+ "frcYear": "2025",
+ "mavenUrls": [
+ "https://dev.studica.com/maven/release/2025/"
+ ],
+ "jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.1.1-beta-3.json",
+ "cppDependencies": [
+ {
+ "artifactId": "Studica-cpp",
+ "binaryPlatforms": [
+ "linuxathena",
+ "linuxarm32",
+ "linuxarm64",
+ "linuxx86-64",
+ "osxuniversal",
+ "windowsx86-64"
+ ],
+ "groupId": "com.studica.frc",
+ "headerClassifier": "headers",
+ "libName": "Studica",
+ "sharedLibrary": false,
+ "skipInvalidPlatforms": true,
+ "version": "2025.1.1-beta-3"
+ },
+ {
+ "artifactId": "Studica-driver",
+ "binaryPlatforms": [
+ "linuxathena",
+ "linuxarm32",
+ "linuxarm64",
+ "linuxx86-64",
+ "osxuniversal",
+ "windowsx86-64"
+ ],
+ "groupId": "com.studica.frc",
+ "headerClassifier": "headers",
+ "libName": "StudicaDriver",
+ "sharedLibrary": false,
+ "skipInvalidPlatforms": true,
+ "version": "2025.1.1-beta-3"
+ }
+ ],
+ "javaDependencies": [
+ {
+ "artifactId": "Studica-java",
+ "groupId": "com.studica.frc",
+ "version": "2025.1.1-beta-3"
+ }
+ ],
+ "jniDependencies": [
+ {
+ "artifactId": "Studica-driver",
+ "groupId": "com.studica.frc",
+ "isJar": false,
+ "skipInvalidPlatforms": true,
+ "validPlatforms": [
+ "linuxathena",
+ "linuxarm32",
+ "linuxarm64",
+ "linuxx86-64",
+ "osxuniversal",
+ "windowsx86-64"
+ ],
+ "version": "2025.1.1-beta-3"
+ }
+ ]
+}
\ No newline at end of file
diff --git a/vendordeps/ThriftyLib.json b/vendordeps/ThriftyLib.json
new file mode 100644
index 0000000..05bb40b
--- /dev/null
+++ b/vendordeps/ThriftyLib.json
@@ -0,0 +1,20 @@
+{
+ "fileName": "ThriftyLib.json",
+ "name": "ThriftyLib",
+ "version": "0.9.3",
+ "frcYear": "2025",
+ "uuid": "60b2694b-9e6e-4026-81ee-6f167946f4b0",
+ "mavenUrls": [
+ "https://docs.home.thethriftybot.com"
+ ],
+ "jsonUrl": "https://docs.home.thethriftybot.com/ThriftyLib.json",
+ "javaDependencies": [
+ {
+ "groupId": "com.thethriftybot.frc",
+ "artifactId": "ThriftyLib-java",
+ "version": "0.9.3"
+ }
+ ],
+ "jniDependencies": [],
+ "cppDependencies": []
+}
\ No newline at end of file
diff --git a/vendordeps/maple-sim.json b/vendordeps/maple-sim.json
new file mode 100644
index 0000000..6e06bf7
--- /dev/null
+++ b/vendordeps/maple-sim.json
@@ -0,0 +1,26 @@
+{
+ "fileName": "maple-sim.json",
+ "name": "maplesim",
+ "version": "0.2.6",
+ "frcYear": "2025",
+ "uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b",
+ "mavenUrls": [
+ "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/repos/releases",
+ "https://repo1.maven.org/maven2"
+ ],
+ "jsonUrl": "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/maple-sim.json",
+ "javaDependencies": [
+ {
+ "groupId": "org.ironmaple",
+ "artifactId": "maplesim-java",
+ "version": "0.2.6"
+ },
+ {
+ "groupId": "org.dyn4j",
+ "artifactId": "dyn4j",
+ "version": "5.0.2"
+ }
+ ],
+ "jniDependencies": [],
+ "cppDependencies": []
+}
\ No newline at end of file
diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json
new file mode 100644
index 0000000..c7318be
--- /dev/null
+++ b/vendordeps/photonlib.json
@@ -0,0 +1,71 @@
+{
+ "fileName": "photonlib.json",
+ "name": "photonlib",
+ "version": "v2025.0.0-beta-8",
+ "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004",
+ "frcYear": "2025",
+ "mavenUrls": [
+ "https://maven.photonvision.org/repository/internal",
+ "https://maven.photonvision.org/repository/snapshots"
+ ],
+ "jsonUrl": "https://maven.photonvision.org/repository/internal/org/photonvision/photonlib-json/1.0/photonlib-json-1.0.json",
+ "jniDependencies": [
+ {
+ "groupId": "org.photonvision",
+ "artifactId": "photontargeting-cpp",
+ "version": "v2025.0.0-beta-8",
+ "skipInvalidPlatforms": true,
+ "isJar": false,
+ "validPlatforms": [
+ "windowsx86-64",
+ "linuxathena",
+ "linuxx86-64",
+ "osxuniversal"
+ ]
+ }
+ ],
+ "cppDependencies": [
+ {
+ "groupId": "org.photonvision",
+ "artifactId": "photonlib-cpp",
+ "version": "v2025.0.0-beta-8",
+ "libName": "photonlib",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxathena",
+ "linuxx86-64",
+ "osxuniversal"
+ ]
+ },
+ {
+ "groupId": "org.photonvision",
+ "artifactId": "photontargeting-cpp",
+ "version": "v2025.0.0-beta-8",
+ "libName": "photontargeting",
+ "headerClassifier": "headers",
+ "sharedLibrary": true,
+ "skipInvalidPlatforms": true,
+ "binaryPlatforms": [
+ "windowsx86-64",
+ "linuxathena",
+ "linuxx86-64",
+ "osxuniversal"
+ ]
+ }
+ ],
+ "javaDependencies": [
+ {
+ "groupId": "org.photonvision",
+ "artifactId": "photonlib-java",
+ "version": "v2025.0.0-beta-8"
+ },
+ {
+ "groupId": "org.photonvision",
+ "artifactId": "photontargeting-java",
+ "version": "v2025.0.0-beta-8"
+ }
+ ]
+}
\ No newline at end of file
diff --git a/vendordeps/yagsl.json b/vendordeps/yagsl.json
new file mode 100644
index 0000000..8d82af9
--- /dev/null
+++ b/vendordeps/yagsl.json
@@ -0,0 +1,64 @@
+{
+ "fileName": "yagsl.json",
+ "name": "YAGSL",
+ "version": "2025.1.1",
+ "frcYear": "2025",
+ "uuid": "1ccce5a4-acd2-4d18-bca3-4b8047188400",
+ "mavenUrls": [
+ "https://broncbotz3481.github.io/YAGSL-Lib/yagsl/repos"
+ ],
+ "jsonUrl": "https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json",
+ "javaDependencies": [
+ {
+ "groupId": "swervelib",
+ "artifactId": "YAGSL-java",
+ "version": "2025.1.1"
+ }
+ ],
+ "requires": [
+ {
+ "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
+ "errorMessage": "REVLib is required!",
+ "offlineFileName": "REVLib.json",
+ "onlineUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json"
+ },
+ {
+ "uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd",
+ "errorMessage": "ReduxLib is required!",
+ "offlineFileName": "ReduxLib_2025.json",
+ "onlineUrl": "https://frcsdk.reduxrobotics.com/ReduxLib_2025.json"
+ },
+ {
+ "uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
+ "errorMessage": "Phoenix6 is required!",
+ "offlineFileName": "Phoenix6-frc2025-beta-latest.json",
+ "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json"
+ },
+ {
+ "uuid": "ab676553-b602-441f-a38d-f1296eff6537",
+ "errorMessage": "Phoenix5 is required!",
+ "offlineFileName": "Phoenix5.json",
+ "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-beta-latest.json"
+ },
+ {
+ "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
+ "errorMessage": "NavX is required!",
+ "offlineFileName": "Studica-2025.1.1-beta-3.json",
+ "onlineUrl": "https://dev.studica.com/releases/2025/Studica-2025.1.1-beta-3.json"
+ },
+ {
+ "uuid": "60b2694b-9e6e-4026-81ee-6f167946f4b0",
+ "errorMessage": "ThriftyLib is required!",
+ "offlineFileName": "ThriftyLib.json",
+ "onlineUrl": "https://docs.home.thethriftybot.com/ThriftyLib.json"
+ },
+ {
+ "uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b",
+ "errorMessage": "MapleSim is requires for simulation",
+ "offlineFileName": "maple-sim.json",
+ "onlineUrl": "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/maple-sim.json"
+ }
+ ],
+ "jniDependencies": [],
+ "cppDependencies": []
+}
\ No newline at end of file