From 5a0f3fa2bda14c2adbcd9af3edfc2d2930eb9e9f Mon Sep 17 00:00:00 2001 From: rishabhreng Date: Tue, 19 Nov 2024 18:52:22 -0600 Subject: [PATCH] AdvKit-add spotless format --- AdvKit2024/.wpilib/wpilib_preferences.json | 10 +- AdvKit2024/build.gradle | 49 +- AdvKit2024/src/main/java/frc/robot/Robot.java | 34 +- .../main/java/frc/robot/RobotContainer.java | 2 +- .../frc/robot/subsystems/drive/Drive.java | 40 +- .../frc/robot/subsystems/drive/DriveIO.java | 3 +- .../robot/subsystems/drive/DriveIOSim.java | 4 +- .../subsystems/drive/DriveIOTalonFX.java | 47 +- .../frc/robot/subsystems/intake/Intake.java | 10 +- .../frc/robot/subsystems/intake/IntakeIO.java | 2 +- .../robot/subsystems/intake/IntakeIOSim.java | 6 +- .../subsystems/intake/IntakeIOTalonFX.java | 32 +- AdvKit2024/vendordeps/AdvantageKit.json | 82 +-- AdvKit2024/vendordeps/Phoenix6.json | 676 +++++++++--------- 14 files changed, 523 insertions(+), 474 deletions(-) diff --git a/AdvKit2024/.wpilib/wpilib_preferences.json b/AdvKit2024/.wpilib/wpilib_preferences.json index 66f767e..b642162 100644 --- a/AdvKit2024/.wpilib/wpilib_preferences.json +++ b/AdvKit2024/.wpilib/wpilib_preferences.json @@ -1,6 +1,6 @@ { - "enableCppIntellisense": false, - "currentLanguage": "java", - "projectYear": "2024", - "teamNumber": 6672 -} \ No newline at end of file + "enableCppIntellisense": false, + "currentLanguage": "java", + "projectYear": "2024", + "teamNumber": 6672 +} diff --git a/AdvKit2024/build.gradle b/AdvKit2024/build.gradle index 35e16db..ee84734 100644 --- a/AdvKit2024/build.gradle +++ b/AdvKit2024/build.gradle @@ -1,6 +1,7 @@ plugins { id "java" id "edu.wpi.first.GradleRIO" version "2024.3.2" + id 'com.diffplug.spotless' version '6.20.0' } java { @@ -108,7 +109,11 @@ wpi.sim.addDriverstation() // in order to make them all available at runtime. Also adding the manifest so WPILib // knows where to look for our Robot Class. jar { - from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } } + from { + configurations.runtimeClasspath.collect { + it.isDirectory() ? it : zipTree(it) + } + } from sourceSets.main.allSource manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS) duplicatesStrategy = DuplicatesStrategy.INCLUDE @@ -123,3 +128,45 @@ wpi.java.configureTestTasks(test) tasks.withType(JavaCompile) { options.compilerArgs.add '-XDstringConcat=inline' } + +// Spotless formatting +project.compileJava.dependsOn(spotlessApply) +spotless { + java { + target fileTree(".") { + include "**/*.java" + exclude "**/build/**", "**/build-*/**" + } + toggleOffOn() + googleJavaFormat() + removeUnusedImports() + trimTrailingWhitespace() + endWithNewline() + } + groovyGradle { + target fileTree(".") { + include "**/*.gradle" + exclude "**/build/**", "**/build-*/**" + } + greclipse() + indentWithSpaces(4) + trimTrailingWhitespace() + endWithNewline() + } + json { + target fileTree(".") { + include "**/*.json" + exclude "**/build/**", "**/build-*/**" + } + gson().indentWithSpaces(2) + } + format "misc", { + target fileTree(".") { + include "**/*.md", "**/.gitignore" + exclude "**/build/**", "**/build-*/**" + } + trimTrailingWhitespace() + indentWithSpaces(2) + endWithNewline() + } +} diff --git a/AdvKit2024/src/main/java/frc/robot/Robot.java b/AdvKit2024/src/main/java/frc/robot/Robot.java index a1a2b9c..3408fdb 100644 --- a/AdvKit2024/src/main/java/frc/robot/Robot.java +++ b/AdvKit2024/src/main/java/frc/robot/Robot.java @@ -4,15 +4,13 @@ package frc.robot; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandScheduler; import org.littletonrobotics.junction.LoggedRobot; import org.littletonrobotics.junction.Logger; import org.littletonrobotics.junction.networktables.NT4Publisher; import org.littletonrobotics.junction.wpilog.WPILOGWriter; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.CommandScheduler; - - public class Robot extends LoggedRobot { private Command m_autonomousCommand; @@ -22,21 +20,25 @@ public class Robot extends LoggedRobot { public void robotInit() { Logger.recordMetadata("ProjectName", "MyProject"); // Set a metadata value - // if (isReal()) { - // Logger.addDataReceiver(new WPILOGWriter()); // Log to a USB stick ("/U/logs") - // Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables - // new PowerDistribution(1, ModuleType.kRev); // Enables power distribution logging - // } else { - // setUseTiming(false); // Run as fast as possible - // String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope (or prompt the user) - // Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log - // Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); // Save outputs to a new log - // } + // if (isReal()) { + // Logger.addDataReceiver(new WPILOGWriter()); // Log to a USB stick ("/U/logs") + // Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables + // new PowerDistribution(1, ModuleType.kRev); // Enables power distribution logging + // } else { + // setUseTiming(false); // Run as fast as possible + // String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope + // (or prompt the user) + // Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log + // Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); // + // Save outputs to a new log + // } Logger.addDataReceiver(new WPILOGWriter()); // Log to a USB stick ("/U/logs") Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables - // Logger.disableDeterministicTimestamps() // See "Deterministic Timestamps" in the "Understanding Data Flow" page - Logger.start(); // Start logging! No more data receivers, replay sources, or metadata values may be added. + // Logger.disableDeterministicTimestamps() // See "Deterministic Timestamps" in the + // "Understanding Data Flow" page + Logger.start(); // Start logging! No more data receivers, replay sources, or metadata values may + // be added. m_robotContainer = new RobotContainer(); } diff --git a/AdvKit2024/src/main/java/frc/robot/RobotContainer.java b/AdvKit2024/src/main/java/frc/robot/RobotContainer.java index 101e0fd..f00850b 100644 --- a/AdvKit2024/src/main/java/frc/robot/RobotContainer.java +++ b/AdvKit2024/src/main/java/frc/robot/RobotContainer.java @@ -14,7 +14,7 @@ public class RobotContainer { private final Intake intake; private final Drive drive; - + public RobotContainer() { intake = new Intake(new IntakeIOSim()); drive = new Drive(new DriveIOSim()); diff --git a/AdvKit2024/src/main/java/frc/robot/subsystems/drive/Drive.java b/AdvKit2024/src/main/java/frc/robot/subsystems/drive/Drive.java index ce4d4d7..6139701 100644 --- a/AdvKit2024/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/AdvKit2024/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -1,39 +1,37 @@ package frc.robot.subsystems.drive; -import org.littletonrobotics.junction.AutoLogOutput; -import org.littletonrobotics.junction.Logger; +import static frc.robot.Constants.driverController; -import edu.wpi.first.math.kinematics.DifferentialDriveOdometry; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d; import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import static frc.robot.Constants.driverController; import java.util.function.DoubleSupplier; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; -public class Drive extends SubsystemBase{ +public class Drive extends SubsystemBase { DriveIO driveIO; DriveIOInputsAutoLogged inputs = new DriveIOInputsAutoLogged(); - @AutoLogOutput - public Mechanism2d leftMechanism2d = new Mechanism2d(1, 1); - private MechanismLigament2d leftMotorMechanismModifiable = leftMechanism2d.getRoot("leftMotor", 0.5, 0.5) - .append(new MechanismLigament2d("leftMotorAngle", 0.25, 0) - ); + @AutoLogOutput public Mechanism2d leftMechanism2d = new Mechanism2d(1, 1); + private MechanismLigament2d leftMotorMechanismModifiable = + leftMechanism2d + .getRoot("leftMotor", 0.5, 0.5) + .append(new MechanismLigament2d("leftMotorAngle", 0.25, 0)); - @AutoLogOutput - public Mechanism2d rightMechanism2d = new Mechanism2d(1, 1); - private MechanismLigament2d rightMotorMechanismModifiable = rightMechanism2d.getRoot("rightMotor", 0.5, 0.5) - .append(new MechanismLigament2d("rightMotorAngle", 0.25, 0) - ); + @AutoLogOutput public Mechanism2d rightMechanism2d = new Mechanism2d(1, 1); + private MechanismLigament2d rightMotorMechanismModifiable = + rightMechanism2d + .getRoot("rightMotor", 0.5, 0.5) + .append(new MechanismLigament2d("rightMotorAngle", 0.25, 0)); public Drive(DriveIO driveIO) { this.driveIO = driveIO; setDefaultCommand( - runArcadeDrive(() -> -driverController.getLeftY(), driverController::getRightX) - ); + runArcadeDrive(() -> -driverController.getLeftY(), driverController::getRightX)); } public void periodic() { @@ -45,8 +43,10 @@ public void periodic() { } public Command runArcadeDrive(DoubleSupplier speed, DoubleSupplier rotation) { - return run(() -> driveIO.setDriveVoltage( - speed.getAsDouble() + rotation.getAsDouble(), - speed.getAsDouble() - rotation.getAsDouble())); + return run( + () -> + driveIO.setDriveVoltage( + speed.getAsDouble() + rotation.getAsDouble(), + speed.getAsDouble() - rotation.getAsDouble())); } } diff --git a/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIO.java b/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIO.java index bee20ae..fabe5fc 100644 --- a/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIO.java +++ b/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIO.java @@ -16,7 +16,8 @@ public static class DriveIOInputs { public default void updateInputs(DriveIOInputs inputs) {} - public default void setDriveVelocity(double leftVelocityRadPerSec, double rightVelocityRadPerSec) {} + public default void setDriveVelocity( + double leftVelocityRadPerSec, double rightVelocityRadPerSec) {} public default void setDriveVoltage(double leftVolts, double rightVolts) {} } diff --git a/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIOSim.java b/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIOSim.java index 42d409a..b430d70 100644 --- a/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIOSim.java +++ b/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIOSim.java @@ -3,7 +3,7 @@ import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.wpilibj.simulation.DCMotorSim; -public class DriveIOSim implements DriveIO{ +public class DriveIOSim implements DriveIO { DCMotorSim leftDriveMotorSim = new DCMotorSim(DCMotor.getFalcon500(1), 1, 0.0001); DCMotorSim rightDriveMotorSim = new DCMotorSim(DCMotor.getFalcon500(1), 1, 0.0001); @@ -29,7 +29,7 @@ public void updateInputs(DriveIO.DriveIOInputs inputs) { inputs.leftDriveMotorAppliedVolts = leftDriveMotorAppliedVolts; inputs.leftDriveMotorPosRad = leftDriveMotorSim.getAngularPositionRad(); inputs.leftDriveMotorVelocityRadPerSec = leftDriveMotorSim.getAngularVelocityRadPerSec(); - + inputs.rightDriveMotorAppliedVolts = rightDriveMotorAppliedVolts; inputs.rightDriveMotorPosRad = rightDriveMotorSim.getAngularPositionRad(); inputs.rightDriveMotorVelocityRadPerSec = rightDriveMotorSim.getAngularVelocityRadPerSec(); diff --git a/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIOTalonFX.java b/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIOTalonFX.java index 878a190..f30193c 100644 --- a/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIOTalonFX.java +++ b/AdvKit2024/src/main/java/frc/robot/subsystems/drive/DriveIOTalonFX.java @@ -7,7 +7,6 @@ import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.NeutralModeValue; - import edu.wpi.first.math.util.Units; public class DriveIOTalonFX implements DriveIO { @@ -23,7 +22,7 @@ public class DriveIOTalonFX implements DriveIO { private StatusSignal leftDriveMotorPosRad = leftDriveMotor.getPosition(); private StatusSignal leftDriveMotorVelocityRadPerSec = leftDriveMotor.getVelocity(); private StatusSignal leftDriveMotorAppliedVolts = leftDriveMotor.getMotorVoltage(); - + private StatusSignal rightDriveMotorPosRad = rightDriveMotor.getPosition(); private StatusSignal rightDriveMotorVelocityRadPerSec = rightDriveMotor.getVelocity(); private StatusSignal rightDriveMotorAppliedVolts = rightDriveMotor.getMotorVoltage(); @@ -31,17 +30,21 @@ public class DriveIOTalonFX implements DriveIO { public DriveIOTalonFX() { leftDriveMotor.setInverted(false); rightDriveMotor.setInverted(true); - leftDriveMotor.getConfigurator().apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake)); - rightDriveMotor.getConfigurator().apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake)); + leftDriveMotor + .getConfigurator() + .apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake)); + rightDriveMotor + .getConfigurator() + .apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake)); BaseStatusSignal.setUpdateFrequencyForAll( - 60, - leftDriveMotorPosRad, - leftDriveMotorVelocityRadPerSec, - leftDriveMotorAppliedVolts, - rightDriveMotorPosRad, - rightDriveMotorVelocityRadPerSec, - rightDriveMotorAppliedVolts); + 60, + leftDriveMotorPosRad, + leftDriveMotorVelocityRadPerSec, + leftDriveMotorAppliedVolts, + rightDriveMotorPosRad, + rightDriveMotorVelocityRadPerSec, + rightDriveMotorAppliedVolts); leftDriveMotor.optimizeBusUtilization(); rightDriveMotor.optimizeBusUtilization(); } @@ -61,20 +64,22 @@ public void setDriveVoltage(double leftVolts, double rightVolts) { @Override public void updateInputs(DriveIOInputs inputs) { BaseStatusSignal.refreshAll( - leftDriveMotorPosRad, - leftDriveMotorVelocityRadPerSec, - leftDriveMotorAppliedVolts, - rightDriveMotorPosRad, - rightDriveMotorVelocityRadPerSec, - rightDriveMotorAppliedVolts - ); + leftDriveMotorPosRad, + leftDriveMotorVelocityRadPerSec, + leftDriveMotorAppliedVolts, + rightDriveMotorPosRad, + rightDriveMotorVelocityRadPerSec, + rightDriveMotorAppliedVolts); inputs.leftDriveMotorAppliedVolts = leftDriveMotorAppliedVolts.getValueAsDouble(); inputs.leftDriveMotorPosRad = Units.rotationsToRadians(leftDriveMotorPosRad.getValueAsDouble()); - inputs.leftDriveMotorVelocityRadPerSec = Units.rotationsToRadians(leftDriveMotorVelocityRadPerSec.getValueAsDouble()); + inputs.leftDriveMotorVelocityRadPerSec = + Units.rotationsToRadians(leftDriveMotorVelocityRadPerSec.getValueAsDouble()); inputs.rightDriveMotorAppliedVolts = rightDriveMotorAppliedVolts.getValueAsDouble(); - inputs.rightDriveMotorPosRad = Units.rotationsToRadians(rightDriveMotorPosRad.getValueAsDouble()); - inputs.rightDriveMotorVelocityRadPerSec = Units.rotationsToRadians(rightDriveMotorVelocityRadPerSec.getValueAsDouble()); + inputs.rightDriveMotorPosRad = + Units.rotationsToRadians(rightDriveMotorPosRad.getValueAsDouble()); + inputs.rightDriveMotorVelocityRadPerSec = + Units.rotationsToRadians(rightDriveMotorVelocityRadPerSec.getValueAsDouble()); } } diff --git a/AdvKit2024/src/main/java/frc/robot/subsystems/intake/Intake.java b/AdvKit2024/src/main/java/frc/robot/subsystems/intake/Intake.java index 2a70e87..f5b8279 100644 --- a/AdvKit2024/src/main/java/frc/robot/subsystems/intake/Intake.java +++ b/AdvKit2024/src/main/java/frc/robot/subsystems/intake/Intake.java @@ -2,11 +2,10 @@ import static frc.robot.Constants.driverController; -import org.littletonrobotics.junction.Logger; - import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.Logger; public class Intake extends SubsystemBase { private IntakeIO intakeIO; @@ -25,9 +24,8 @@ public void periodic() { public Command intakeCommand() { return Commands.sequence( - runOnce(() -> intakeIO.setIntakeVoltage(2.0)), - Commands.waitSeconds(2.0), - runOnce(() -> intakeIO.setIntakeVoltage(0.0)) - ); + runOnce(() -> intakeIO.setIntakeVoltage(2.0)), + Commands.waitSeconds(2.0), + runOnce(() -> intakeIO.setIntakeVoltage(0.0))); } } diff --git a/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIO.java b/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIO.java index 5a7ab83..32644e2 100644 --- a/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIO.java +++ b/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIO.java @@ -10,7 +10,7 @@ public static class IntakeIOInputs { public double intakeVelocityRadPerSec = 0.0; } - public default void updateInputs(IntakeIOInputs inputs) {} + public default void updateInputs(IntakeIOInputs inputs) {} public default void setIntakeVelocity(double velocityRadPerSec) {} diff --git a/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIOSim.java b/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIOSim.java index dcef061..e0332fc 100644 --- a/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIOSim.java +++ b/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIOSim.java @@ -16,8 +16,9 @@ public class IntakeIOSim implements IntakeIO { @Override public void setIntakeVelocity(double velocityRadPerSec) { intakeMotorSim.setInputVoltage( - intakeFeedforward.calculate(velocityRadPerSec) + intakeController.calculate(intakeMotorSim.getAngularVelocityRadPerSec(), velocityRadPerSec) - ); + intakeFeedforward.calculate(velocityRadPerSec) + + intakeController.calculate( + intakeMotorSim.getAngularVelocityRadPerSec(), velocityRadPerSec)); } @Override @@ -33,5 +34,4 @@ public void updateInputs(IntakeIOInputs inputs) { inputs.intakePosRad = intakeMotorSim.getAngularPositionRad(); inputs.intakeVelocityRadPerSec = intakeMotorSim.getAngularVelocityRadPerSec(); } - } diff --git a/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIOTalonFX.java b/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIOTalonFX.java index 165f68b..4d70223 100644 --- a/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIOTalonFX.java +++ b/AdvKit2024/src/main/java/frc/robot/subsystems/intake/IntakeIOTalonFX.java @@ -7,7 +7,6 @@ import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.NeutralModeValue; - import edu.wpi.first.math.util.Units; public class IntakeIOTalonFX implements IntakeIO { @@ -20,27 +19,24 @@ public class IntakeIOTalonFX implements IntakeIO { private VoltageOut voltageOut = new VoltageOut(0.0); private VelocityVoltage velocityVoltage = new VelocityVoltage(0.0); -public IntakeIOTalonFX() { - intakeMotor.getConfigurator().apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake)); + public IntakeIOTalonFX() { + intakeMotor + .getConfigurator() + .apply(new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake)); - BaseStatusSignal.setUpdateFrequencyForAll( - 60, - intakePosRot, - intakeVelocityRotPerSec, - intakeAppliedVolts); - intakeMotor.optimizeBusUtilization(); -} + BaseStatusSignal.setUpdateFrequencyForAll( + 60, intakePosRot, intakeVelocityRotPerSec, intakeAppliedVolts); + intakeMotor.optimizeBusUtilization(); + } @Override public void updateInputs(IntakeIOInputs inputs) { - BaseStatusSignal.refreshAll( - intakePosRot, - intakeVelocityRotPerSec, - intakeAppliedVolts); - - inputs.intakePosRad = Units.rotationsToRadians(intakePosRot.getValueAsDouble()); - inputs.intakeVelocityRadPerSec = Units.rotationsToRadians(intakeVelocityRotPerSec.getValueAsDouble()); - inputs.intakeAppliedVolts = intakeAppliedVolts.getValueAsDouble(); + BaseStatusSignal.refreshAll(intakePosRot, intakeVelocityRotPerSec, intakeAppliedVolts); + + inputs.intakePosRad = Units.rotationsToRadians(intakePosRot.getValueAsDouble()); + inputs.intakeVelocityRadPerSec = + Units.rotationsToRadians(intakeVelocityRotPerSec.getValueAsDouble()); + inputs.intakeAppliedVolts = intakeAppliedVolts.getValueAsDouble(); } @Override diff --git a/AdvKit2024/vendordeps/AdvantageKit.json b/AdvKit2024/vendordeps/AdvantageKit.json index 63dacbb..1f57c3b 100644 --- a/AdvKit2024/vendordeps/AdvantageKit.json +++ b/AdvKit2024/vendordeps/AdvantageKit.json @@ -1,42 +1,42 @@ { - "fileName": "AdvantageKit.json", - "name": "AdvantageKit", - "version": "3.2.1", - "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", - "frcYear": "2024", - "mavenUrls": [], - "jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json", - "javaDependencies": [ - { - "groupId": "org.littletonrobotics.akit.junction", - "artifactId": "wpilib-shim", - "version": "3.2.1" - }, - { - "groupId": "org.littletonrobotics.akit.junction", - "artifactId": "junction-core", - "version": "3.2.1" - }, - { - "groupId": "org.littletonrobotics.akit.conduit", - "artifactId": "conduit-api", - "version": "3.2.1" - } - ], - "jniDependencies": [ - { - "groupId": "org.littletonrobotics.akit.conduit", - "artifactId": "conduit-wpilibio", - "version": "3.2.1", - "skipInvalidPlatforms": false, - "isJar": false, - "validPlatforms": [ - "linuxathena", - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ] - } - ], - "cppDependencies": [] -} \ No newline at end of file + "fileName": "AdvantageKit.json", + "name": "AdvantageKit", + "version": "3.2.1", + "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", + "frcYear": "2024", + "mavenUrls": [], + "jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json", + "javaDependencies": [ + { + "groupId": "org.littletonrobotics.akit.junction", + "artifactId": "wpilib-shim", + "version": "3.2.1" + }, + { + "groupId": "org.littletonrobotics.akit.junction", + "artifactId": "junction-core", + "version": "3.2.1" + }, + { + "groupId": "org.littletonrobotics.akit.conduit", + "artifactId": "conduit-api", + "version": "3.2.1" + } + ], + "jniDependencies": [ + { + "groupId": "org.littletonrobotics.akit.conduit", + "artifactId": "conduit-wpilibio", + "version": "3.2.1", + "skipInvalidPlatforms": false, + "isJar": false, + "validPlatforms": [ + "linuxathena", + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ] + } + ], + "cppDependencies": [] +} diff --git a/AdvKit2024/vendordeps/Phoenix6.json b/AdvKit2024/vendordeps/Phoenix6.json index 0322385..1f0cf3a 100644 --- a/AdvKit2024/vendordeps/Phoenix6.json +++ b/AdvKit2024/vendordeps/Phoenix6.json @@ -1,339 +1,339 @@ { - "fileName": "Phoenix6.json", - "name": "CTRE-Phoenix (v6)", - "version": "24.3.0", - "frcYear": 2024, - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", - "mavenUrls": [ - "https://maven.ctr-electronics.com/release/" - ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json", - "conflictsWith": [ - { - "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a", - "errorMessage": "The combined Phoenix-6-And-5 vendordep is no longer supported. Please remove the vendordep and instead add both the latest Phoenix 6 vendordep and Phoenix 5 vendordep.", - "offlineFileName": "Phoenix6And5.json" - } - ], - "javaDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-java", - "version": "24.3.0" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonFX", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "24.3.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-cpp", - "version": "24.3.0", - "libName": "CTRE_Phoenix6_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "24.3.0", - "libName": "CTRE_PhoenixTools", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "24.3.0", - "libName": "CTRE_Phoenix6_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "24.3.0", - "libName": "CTRE_PhoenixTools_Sim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "24.3.0", - "libName": "CTRE_SimTalonSRX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonFX", - "version": "24.3.0", - "libName": "CTRE_SimTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "24.3.0", - "libName": "CTRE_SimVictorSPX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "24.3.0", - "libName": "CTRE_SimPigeonIMU", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "24.3.0", - "libName": "CTRE_SimCANCoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "24.3.0", - "libName": "CTRE_SimProTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "24.3.0", - "libName": "CTRE_SimProCANcoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "24.3.0", - "libName": "CTRE_SimProPigeon2", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} \ No newline at end of file + "fileName": "Phoenix6.json", + "name": "CTRE-Phoenix (v6)", + "version": "24.3.0", + "frcYear": 2024, + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json", + "conflictsWith": [ + { + "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a", + "errorMessage": "The combined Phoenix-6-And-5 vendordep is no longer supported. Please remove the vendordep and instead add both the latest Phoenix 6 vendordep and Phoenix 5 vendordep.", + "offlineFileName": "Phoenix6And5.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "24.3.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "24.3.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "24.3.0", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "24.3.0", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "24.3.0", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "24.3.0", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "24.3.0", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "24.3.0", + "libName": "CTRE_SimTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "24.3.0", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "24.3.0", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "24.3.0", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "24.3.0", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "24.3.0", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "24.3.0", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +}