diff --git a/src/main/java/frc/robot/intake/IntakeSubsystem.java b/src/main/java/frc/robot/intake/IntakeSubsystem.java index 8a87f35..5d33af4 100644 --- a/src/main/java/frc/robot/intake/IntakeSubsystem.java +++ b/src/main/java/frc/robot/intake/IntakeSubsystem.java @@ -5,7 +5,6 @@ package frc.robot.intake; import com.revrobotics.*; - import edu.wpi.first.math.filter.LinearFilter; import frc.robot.util.scheduling.LifecycleSubsystem; import frc.robot.util.scheduling.SubsystemPriority; @@ -15,12 +14,12 @@ public class IntakeSubsystem extends LifecycleSubsystem { private final LinearFilter voltageFilter = LinearFilter.movingAverage(7); private final LinearFilter velocityFilter = LinearFilter.movingAverage(7); - //7 is a placeholder not tuned + // 7 is a placeholder not tuned private final CANSparkMax motor; private final RelativeEncoder encoder; private IntakeState goalState; private HeldGamePiece gamePiece = HeldGamePiece.NOTHING; - + public IntakeSubsystem(CANSparkMax motor) { super(SubsystemPriority.INTAKE); this.motor = motor; @@ -36,7 +35,8 @@ public void setGoalState(IntakeState intakeState) { goalState = intakeState; } -@Override + + @Override public void robotPeriodic() { Logger.getInstance().recordOutput("Intake/State", goalState.toString()); Logger.getInstance().recordOutput("Intake/HeldGamePiece", gamePiece.toString()); @@ -66,17 +66,22 @@ public void enabledPeriodic() { // Game piece detection double motorVelocity = velocityFilter.calculate(encoder.getVelocity()); double intakeVoltage = voltageFilter.calculate(motor.getAppliedOutput()) * 12.0; - double theoreticalSpeed = intakeVoltage * (5700.0/12.0); //Neo Max is 5700 - double threshold = theoreticalSpeed * 0.5; + double theoreticalSpeed = intakeVoltage * (5700.0 / 12.0); // Neo Max is 5700 + double threshold = theoreticalSpeed * 0.5; if (motorVelocity < threshold && goalState == IntakeState.INTAKE_CONE) { gamePiece = HeldGamePiece.CONE; } else if (motorVelocity < threshold && goalState == IntakeState.INTAKE_CUBE) { gamePiece = HeldGamePiece.CUBE; - } else if (motorVelocity > threshold && (goalState == IntakeState.OUTTAKE_CONE || goalState == IntakeState.OUTTAKE_CUBE)) { + } else if (motorVelocity > threshold + && (goalState == IntakeState.OUTTAKE_CONE || goalState == IntakeState.OUTTAKE_CUBE)) { gamePiece = HeldGamePiece.NOTHING; } } + public IntakeState getIntakeState() { + return goalState; + } + public boolean atGoal(IntakeState state) { if (goalState != state) { return false; diff --git a/src/main/java/frc/robot/lights/BlinkPattern.java b/src/main/java/frc/robot/lights/BlinkPattern.java new file mode 100644 index 0000000..6bf8959 --- /dev/null +++ b/src/main/java/frc/robot/lights/BlinkPattern.java @@ -0,0 +1,11 @@ +// 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 frc.robot.lights; + +public enum BlinkPattern { + SOLID, + BLINK_SLOW, + BLINK_FAST; +} diff --git a/src/main/java/frc/robot/lights/LightsSubsystem.java b/src/main/java/frc/robot/lights/LightsSubsystem.java new file mode 100644 index 0000000..9c27199 --- /dev/null +++ b/src/main/java/frc/robot/lights/LightsSubsystem.java @@ -0,0 +1,106 @@ +// 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 frc.robot.lights; + +import com.ctre.phoenix.led.CANdle; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.util.Color; +import edu.wpi.first.wpilibj.util.Color8Bit; +import frc.robot.fms.FmsSubsystem; +import frc.robot.intake.HeldGamePiece; +import frc.robot.intake.IntakeState; +import frc.robot.intake.IntakeSubsystem; +import frc.robot.managers.superstructure.SuperstructureManager; +import frc.robot.util.scheduling.LifecycleSubsystem; +import frc.robot.util.scheduling.SubsystemPriority; + +public class LightsSubsystem extends LifecycleSubsystem { + + private static final double FAST_BLINK_DURATION = 0.08; + private static final double SLOW_BLINK_DURATION = 0.25; + + private final CANdle candle; + private final IntakeSubsystem intake; + private final SuperstructureManager superstructure; + + private final Timer blinkTimer = new Timer(); + private Color color = Color.kWhite; + // TODO: Copy paste blink pattern enum from other repo + private BlinkPattern blinkPattern = BlinkPattern.SOLID; + + public LightsSubsystem( + CANdle candle, IntakeSubsystem intake, SuperstructureManager superstructure) { + super(SubsystemPriority.LIGHTS); + this.candle = candle; + this.intake = intake; + this.superstructure = superstructure; + } + + public void enabledPeriodic() { + HeldGamePiece gamePiece = intake.getGamePiece(); + IntakeState intakeMode = intake.getIntakeState(); + HeldGamePiece superstructureMode = superstructure.getMode(); + + if (DriverStation.isDisabled()) { + if (FmsSubsystem.isRedAlliance()) { + color = Color.kRed; + blinkPattern = BlinkPattern.SOLID; + } else { + color = Color.kBlue; + blinkPattern = BlinkPattern.SOLID; + } + } else if (gamePiece == HeldGamePiece.CUBE) { + if (intakeMode == IntakeState.INTAKE_CUBE) { + color = Color.kPurple; + blinkPattern = BlinkPattern.BLINK_FAST; + } else { + color = Color.kPurple; + blinkPattern = BlinkPattern.SOLID; + } + } else if (gamePiece == HeldGamePiece.CONE) { + if (intakeMode == IntakeState.INTAKE_CONE) { + color = Color.kYellow; + blinkPattern = BlinkPattern.BLINK_FAST; + } else { + color = Color.kYellow; + blinkPattern = BlinkPattern.SOLID; + } + } else if (superstructureMode == HeldGamePiece.CUBE) { + color = Color.kPurple; + blinkPattern = BlinkPattern.BLINK_SLOW; + } else if (superstructureMode == HeldGamePiece.CONE) { + color = Color.kYellow; + blinkPattern = BlinkPattern.BLINK_SLOW; + } else { + color = Color.kWhite; + blinkPattern = BlinkPattern.SOLID; + } + + Color8Bit color8Bit = new Color8Bit(color); + if (blinkPattern == BlinkPattern.SOLID) { + candle.setLEDs(color8Bit.red, color8Bit.green, color8Bit.blue); + } else { + double time = blinkTimer.get(); + double onDuration = 0; + double offDuration = 0; + + if (blinkPattern == BlinkPattern.BLINK_FAST) { + onDuration = FAST_BLINK_DURATION; + offDuration = FAST_BLINK_DURATION * 2; + } else if (blinkPattern == BlinkPattern.BLINK_SLOW) { + onDuration = SLOW_BLINK_DURATION; + offDuration = SLOW_BLINK_DURATION * 2; + } + + if (time >= offDuration) { + blinkTimer.reset(); + candle.setLEDs(0, 0, 0); + } else if (time >= onDuration) { + candle.setLEDs(color8Bit.red, color8Bit.green, color8Bit.blue); + } + } + } +} diff --git a/src/main/java/frc/robot/managers/superstructure/Positions.java b/src/main/java/frc/robot/managers/superstructure/Positions.java index 2045820..5517b75 100644 --- a/src/main/java/frc/robot/managers/superstructure/Positions.java +++ b/src/main/java/frc/robot/managers/superstructure/Positions.java @@ -7,22 +7,34 @@ import edu.wpi.first.math.geometry.Rotation2d; public class Positions { - public static final SuperstructurePosition STOWED = new SuperstructurePosition(Rotation2d.fromDegrees(0), Rotation2d.fromDegrees(0)); - - public static final SuperstructurePosition INTAKING_CUBE_FLOOR = new SuperstructurePosition(Rotation2d.fromDegrees(20), Rotation2d.fromDegrees(135)); - public static final SuperstructurePosition INTAKING_CUBE_SHELF = new SuperstructurePosition(Rotation2d.fromDegrees(90), Rotation2d.fromDegrees(180)); - - public static final SuperstructurePosition CUBE_NODE_LOW = new SuperstructurePosition(Rotation2d.fromDegrees(-20), Rotation2d.fromDegrees(-135)); - public static final SuperstructurePosition CUBE_NODE_MID = new SuperstructurePosition(Rotation2d.fromDegrees(-75), Rotation2d.fromDegrees(-190)); - public static final SuperstructurePosition CUBE_NODE_HIGH = new SuperstructurePosition(Rotation2d.fromDegrees(-100), Rotation2d.fromDegrees(-190)); - - public static final SuperstructurePosition INTAKING_CONE_FLOOR = new SuperstructurePosition(Rotation2d.fromDegrees(20), Rotation2d.fromDegrees(135)); - public static final SuperstructurePosition INTAKING_CONE_SHELF = new SuperstructurePosition(Rotation2d.fromDegrees(90), Rotation2d.fromDegrees(180)); - public static final SuperstructurePosition INTAKING_CONE_SINGLE_SUBSTATION = new SuperstructurePosition(Rotation2d.fromDegrees(0), Rotation2d.fromDegrees(30)); - - public static final SuperstructurePosition CONE_NODE_LOW = new SuperstructurePosition(Rotation2d.fromDegrees(-20), Rotation2d.fromDegrees(-135)); - public static final SuperstructurePosition CONE_NODE_MID = new SuperstructurePosition(Rotation2d.fromDegrees(-75), Rotation2d.fromDegrees(-190)); - public static final SuperstructurePosition CONE_NODE_HIGH = new SuperstructurePosition(Rotation2d.fromDegrees(-100), Rotation2d.fromDegrees(-190)); + public static final SuperstructurePosition STOWED = + new SuperstructurePosition(Rotation2d.fromDegrees(0), Rotation2d.fromDegrees(0)); + + public static final SuperstructurePosition INTAKING_CUBE_FLOOR = + new SuperstructurePosition(Rotation2d.fromDegrees(20), Rotation2d.fromDegrees(135)); + public static final SuperstructurePosition INTAKING_CUBE_SHELF = + new SuperstructurePosition(Rotation2d.fromDegrees(90), Rotation2d.fromDegrees(180)); + + public static final SuperstructurePosition CUBE_NODE_LOW = + new SuperstructurePosition(Rotation2d.fromDegrees(-20), Rotation2d.fromDegrees(-135)); + public static final SuperstructurePosition CUBE_NODE_MID = + new SuperstructurePosition(Rotation2d.fromDegrees(-75), Rotation2d.fromDegrees(-190)); + public static final SuperstructurePosition CUBE_NODE_HIGH = + new SuperstructurePosition(Rotation2d.fromDegrees(-100), Rotation2d.fromDegrees(-190)); + + public static final SuperstructurePosition INTAKING_CONE_FLOOR = + new SuperstructurePosition(Rotation2d.fromDegrees(20), Rotation2d.fromDegrees(135)); + public static final SuperstructurePosition INTAKING_CONE_SHELF = + new SuperstructurePosition(Rotation2d.fromDegrees(90), Rotation2d.fromDegrees(180)); + public static final SuperstructurePosition INTAKING_CONE_SINGLE_SUBSTATION = + new SuperstructurePosition(Rotation2d.fromDegrees(0), Rotation2d.fromDegrees(30)); + + public static final SuperstructurePosition CONE_NODE_LOW = + new SuperstructurePosition(Rotation2d.fromDegrees(-20), Rotation2d.fromDegrees(-135)); + public static final SuperstructurePosition CONE_NODE_MID = + new SuperstructurePosition(Rotation2d.fromDegrees(-75), Rotation2d.fromDegrees(-190)); + public static final SuperstructurePosition CONE_NODE_HIGH = + new SuperstructurePosition(Rotation2d.fromDegrees(-100), Rotation2d.fromDegrees(-190)); private Positions() {} } diff --git a/src/main/java/frc/robot/managers/superstructure/SuperstructureManager.java b/src/main/java/frc/robot/managers/superstructure/SuperstructureManager.java index b5ab483..b8364a3 100644 --- a/src/main/java/frc/robot/managers/superstructure/SuperstructureManager.java +++ b/src/main/java/frc/robot/managers/superstructure/SuperstructureManager.java @@ -6,6 +6,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import frc.robot.intake.HeldGamePiece; import frc.robot.intake.IntakeSubsystem; import frc.robot.util.scheduling.LifecycleSubsystem; import frc.robot.util.scheduling.SubsystemPriority; @@ -17,6 +18,7 @@ public class SuperstructureManager extends LifecycleSubsystem { private WristSubsystem wrist; private IntakeSubsystem intake; private SuperstructureState goalState; + private HeldGamePiece mode = HeldGamePiece.CUBE; public SuperstructureManager(SuperstructureMotionManager motionManager, IntakeSubsystem intake) { super(SubsystemPriority.SUPERSTRUCTURE_MANAGER); @@ -48,4 +50,12 @@ public Command setStateCommand(SuperstructureState newGoalState) { return Commands.runOnce(() -> setGoal(newGoalState)) .andThen(Commands.waitUntil(() -> atGoal(newGoalState))); } + + public void setMode(HeldGamePiece mode) { + this.mode = mode; + } + + public HeldGamePiece getMode() { + return mode; + } } diff --git a/src/main/java/frc/robot/managers/superstructure/SuperstructureMotionManager.java b/src/main/java/frc/robot/managers/superstructure/SuperstructureMotionManager.java index db2b12d..1abb5d5 100644 --- a/src/main/java/frc/robot/managers/superstructure/SuperstructureMotionManager.java +++ b/src/main/java/frc/robot/managers/superstructure/SuperstructureMotionManager.java @@ -25,8 +25,7 @@ public SuperstructureMotionManager(WristSubsystem shoulder, WristSubsystem wrist } public boolean atPosition(SuperstructurePosition position) { - return shoulder.atAngle(position.shoulderAngle) - && wrist.atAngle(position.wristAngle); + return shoulder.atAngle(position.shoulderAngle) && wrist.atAngle(position.wristAngle); } public void set(SuperstructurePosition newGoalPosition) { diff --git a/src/main/java/frc/robot/shoulder/ShoulderSubsystem.java b/src/main/java/frc/robot/shoulder/ShoulderSubsystem.java index 1701584..446f8cd 100644 --- a/src/main/java/frc/robot/shoulder/ShoulderSubsystem.java +++ b/src/main/java/frc/robot/shoulder/ShoulderSubsystem.java @@ -1,16 +1,18 @@ -package frc.robot.shoulder; +// 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. -import org.littletonrobotics.junction.Logger; +package frc.robot.shoulder; import com.revrobotics.CANSparkMax; import com.revrobotics.CANSparkMax.ControlType; import com.revrobotics.RelativeEncoder; import com.revrobotics.SparkMaxPIDController; - import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.util.scheduling.LifecycleSubsystem; import frc.robot.util.scheduling.SubsystemPriority; +import org.littletonrobotics.junction.Logger; public class ShoulderSubsystem extends LifecycleSubsystem { private final CANSparkMax motor; @@ -43,22 +45,24 @@ public void enabledPeriodic() { pid.setReference(goalAngle.getRotations(), ControlType.kSmartMotion); } -@Override -public void robotPeriodic(){ - Logger.getInstance().recordOutput("Shoulder/MainMotor/Velocity", encoder.getVelocity()); - Logger.getInstance().recordOutput("Shoulder/FollowerMotor/Velocity", encoder.getVelocity()); - Logger.getInstance().recordOutput("Shoulder/MainMotor/Angle", getWristAngle().getDegrees()); - Logger.getInstance().recordOutput("Shoulder/FollowerMotor/Angle", getWristAngle().getDegrees()); - Logger.getInstance().recordOutput("Shoulder/MainMotor/GoalAngle", goalAngle.getDegrees()); - Logger.getInstance().recordOutput("Shoulder/FollowerMotor/GoalAngle", goalAngle.getDegrees()); - Logger.getInstance().recordOutput("Shoulder/MainMotor/DutyCycleOutput", motor.getAppliedOutput()); - Logger.getInstance().recordOutput("Shoulder/FollowerMotor/DutyCycleOutput", motor.getAppliedOutput()); - Logger.getInstance().recordOutput("Shoulder/MainMotor/StatorCurrent", motor.getOutputCurrent()); - Logger.getInstance().recordOutput("Shoulder/FollowerMotor/StatorCurrent", motor.getOutputCurrent()); - -} + @Override + public void robotPeriodic() { + Logger.getInstance().recordOutput("Shoulder/MainMotor/Velocity", encoder.getVelocity()); + Logger.getInstance().recordOutput("Shoulder/FollowerMotor/Velocity", encoder.getVelocity()); + Logger.getInstance().recordOutput("Shoulder/MainMotor/Angle", getWristAngle().getDegrees()); + Logger.getInstance().recordOutput("Shoulder/FollowerMotor/Angle", getWristAngle().getDegrees()); + Logger.getInstance().recordOutput("Shoulder/MainMotor/GoalAngle", goalAngle.getDegrees()); + Logger.getInstance().recordOutput("Shoulder/FollowerMotor/GoalAngle", goalAngle.getDegrees()); + Logger.getInstance() + .recordOutput("Shoulder/MainMotor/DutyCycleOutput", motor.getAppliedOutput()); + Logger.getInstance() + .recordOutput("Shoulder/FollowerMotor/DutyCycleOutput", motor.getAppliedOutput()); + Logger.getInstance().recordOutput("Shoulder/MainMotor/StatorCurrent", motor.getOutputCurrent()); + Logger.getInstance() + .recordOutput("Shoulder/FollowerMotor/StatorCurrent", motor.getOutputCurrent()); + } -public void set(Rotation2d angle) { + public void set(Rotation2d angle) { goalAngle = angle; } @@ -78,4 +82,3 @@ private Rotation2d getWristAngle() { return Rotation2d.fromRotations(encoder.getPosition()); } } - diff --git a/src/main/java/frc/robot/util/scheduling/SubsystemPriority.java b/src/main/java/frc/robot/util/scheduling/SubsystemPriority.java index d676032..c33100a 100644 --- a/src/main/java/frc/robot/util/scheduling/SubsystemPriority.java +++ b/src/main/java/frc/robot/util/scheduling/SubsystemPriority.java @@ -21,6 +21,7 @@ public enum SubsystemPriority { LOCALIZATION(9), FMS(0), + LIGHTS(0), RUMBLE_CONTROLLER(0); final int value; diff --git a/src/main/java/frc/robot/wrist/WristSubsystem.java b/src/main/java/frc/robot/wrist/WristSubsystem.java index 6c04065..dbf12b0 100644 --- a/src/main/java/frc/robot/wrist/WristSubsystem.java +++ b/src/main/java/frc/robot/wrist/WristSubsystem.java @@ -1,15 +1,18 @@ +// 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 frc.robot.wrist; -import org.littletonrobotics.junction.Logger; import com.revrobotics.CANSparkMax; import com.revrobotics.CANSparkMax.ControlType; import com.revrobotics.RelativeEncoder; import com.revrobotics.SparkMaxPIDController; - import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import frc.robot.util.scheduling.LifecycleSubsystem; import frc.robot.util.scheduling.SubsystemPriority; +import org.littletonrobotics.junction.Logger; public class WristSubsystem extends LifecycleSubsystem { private final CANSparkMax motor; diff --git a/vendordeps/Phoenix6.json b/vendordeps/PhoenixProAnd5.json similarity index 55% rename from vendordeps/Phoenix6.json rename to vendordeps/PhoenixProAnd5.json index f6fd334..327679f 100644 --- a/vendordeps/Phoenix6.json +++ b/vendordeps/PhoenixProAnd5.json @@ -1,13 +1,25 @@ { - "javaDependencies": [{ - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-java", - "version": "23.2.2" - }], - "fileName": "Phoenix6.json", + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.30.4" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.30.4" + }, + { + "groupId": "com.ctre.phoenixpro", + "artifactId": "wpiapi-java", + "version": "23.0.12" + } + ], + "fileName": "PhoenixProAnd5.json", "frcYear": 2023, - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2023-latest.json", - "name": "CTRE-Phoenix (v6)", + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/PhoenixProAnd5-frc2023-latest.json", + "name": "CTRE-Phoenix (Pro And v5)", "jniDependencies": [ { "simMode": "hwsim", @@ -16,11 +28,37 @@ "linuxx86-64", "linuxathena" ], - "groupId": "com.ctre.phoenix6", + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "skipInvalidPlatforms": true, + "isJar": false, + "version": "5.30.4" + }, + { + "simMode": "swsim", + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "skipInvalidPlatforms": true, + "isJar": false, + "version": "5.30.4" + }, + { + "simMode": "hwsim", + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "groupId": "com.ctre.phoenixpro", "artifactId": "tools", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" }, { "simMode": "swsim", @@ -29,11 +67,11 @@ "linuxx86-64", "osxuniversal" ], - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "tools-sim", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" }, { "simMode": "swsim", @@ -42,11 +80,11 @@ "linuxx86-64", "osxuniversal" ], - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonSRX", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" }, { "simMode": "swsim", @@ -55,11 +93,11 @@ "linuxx86-64", "osxuniversal" ], - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonFX", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" }, { "simMode": "swsim", @@ -68,11 +106,11 @@ "linuxx86-64", "osxuniversal" ], - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simVictorSPX", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" }, { "simMode": "swsim", @@ -81,11 +119,11 @@ "linuxx86-64", "osxuniversal" ], - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simPigeonIMU", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" }, { "simMode": "swsim", @@ -94,11 +132,11 @@ "linuxx86-64", "osxuniversal" ], - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simCANCoder", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" }, { "simMode": "swsim", @@ -107,11 +145,11 @@ "linuxx86-64", "osxuniversal" ], - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProTalonFX", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" }, { "simMode": "swsim", @@ -120,11 +158,11 @@ "linuxx86-64", "osxuniversal" ], - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProCANcoder", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" }, { "simMode": "swsim", @@ -133,22 +171,37 @@ "linuxx86-64", "osxuniversal" ], - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProPigeon2", "skipInvalidPlatforms": true, "isJar": false, - "version": "23.2.2" + "version": "23.0.12" } ], "mavenUrls": ["https://maven.ctr-electronics.com/release/"], "cppDependencies": [ { "simMode": "hwsim", - "groupId": "com.ctre.phoenix6", - "libName": "CTRE_Phoenix6_WPI", + "groupId": "com.ctre.phoenix", + "libName": "CTRE_Phoenix_WPI", "artifactId": "wpiapi-cpp", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "5.30.4", + "headerClassifier": "headers", + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "sharedLibrary": true + }, + { + "simMode": "hwsim", + "groupId": "com.ctre.phoenix", + "libName": "CTRE_Phoenix", + "artifactId": "api-cpp", + "skipInvalidPlatforms": true, + "version": "5.30.4", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -159,11 +212,26 @@ }, { "simMode": "hwsim", - "groupId": "com.ctre.phoenix6", + "groupId": "com.ctre.phoenix", + "libName": "CTRE_PhoenixCCI", + "artifactId": "cci", + "skipInvalidPlatforms": true, + "version": "5.30.4", + "headerClassifier": "headers", + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "sharedLibrary": true + }, + { + "simMode": "hwsim", + "groupId": "com.ctre.phoenixpro", "libName": "CTRE_PhoenixTools", "artifactId": "tools", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -174,11 +242,26 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", - "libName": "CTRE_Phoenix6_WPISim", + "groupId": "com.ctre.phoenix.sim", + "libName": "CTRE_Phoenix_WPISim", "artifactId": "wpiapi-cpp-sim", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "5.30.4", + "headerClassifier": "headers", + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "sharedLibrary": true + }, + { + "simMode": "swsim", + "groupId": "com.ctre.phoenix.sim", + "libName": "CTRE_PhoenixSim", + "artifactId": "api-cpp-sim", + "skipInvalidPlatforms": true, + "version": "5.30.4", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -189,11 +272,26 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenix.sim", + "libName": "CTRE_PhoenixCCISim", + "artifactId": "cci-sim", + "skipInvalidPlatforms": true, + "version": "5.30.4", + "headerClassifier": "headers", + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "sharedLibrary": true + }, + { + "simMode": "swsim", + "groupId": "com.ctre.phoenixpro.sim", "libName": "CTRE_PhoenixTools_Sim", "artifactId": "tools-sim", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -204,11 +302,11 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "libName": "CTRE_SimTalonSRX", "artifactId": "simTalonSRX", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -219,11 +317,11 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "libName": "CTRE_SimTalonFX", "artifactId": "simTalonFX", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -234,11 +332,11 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "libName": "CTRE_SimVictorSPX", "artifactId": "simVictorSPX", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -249,11 +347,11 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "libName": "CTRE_SimPigeonIMU", "artifactId": "simPigeonIMU", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -264,11 +362,11 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "libName": "CTRE_SimCANCoder", "artifactId": "simCANCoder", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -279,11 +377,11 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "libName": "CTRE_SimProTalonFX", "artifactId": "simProTalonFX", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -294,11 +392,11 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "libName": "CTRE_SimProCANcoder", "artifactId": "simProCANcoder", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -309,11 +407,41 @@ }, { "simMode": "swsim", - "groupId": "com.ctre.phoenix6.sim", + "groupId": "com.ctre.phoenixpro.sim", "libName": "CTRE_SimProPigeon2", "artifactId": "simProPigeon2", "skipInvalidPlatforms": true, - "version": "23.2.2", + "version": "23.0.12", + "headerClassifier": "headers", + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "sharedLibrary": true + }, + { + "simMode": "hwsim", + "groupId": "com.ctre.phoenixpro", + "libName": "CTRE_PhoenixPro_WPI", + "artifactId": "wpiapi-cpp", + "skipInvalidPlatforms": true, + "version": "23.0.12", + "headerClassifier": "headers", + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "sharedLibrary": true + }, + { + "simMode": "swsim", + "groupId": "com.ctre.phoenixpro.sim", + "libName": "CTRE_PhoenixPro_WPISim", + "artifactId": "wpiapi-cpp-sim", + "skipInvalidPlatforms": true, + "version": "23.0.12", "headerClassifier": "headers", "binaryPlatforms": [ "windowsx86-64", @@ -323,6 +451,6 @@ "sharedLibrary": true } ], - "version": "23.2.2", - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19" + "version": "23.0.12", + "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a" } diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index b2efdcf..90e07c8 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,73 +1,67 @@ { - "fileName": "REVLib.json", - "name": "REVLib", - "version": "2023.1.3", - "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", - "mavenUrls": [ - "https://maven.revrobotics.com/" + "javaDependencies": [{ + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2023.1.3" + }], + "fileName": "REVLib.json", + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json", + "name": "REVLib", + "jniDependencies": [{ + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" ], - "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json", - "javaDependencies": [ - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-java", - "version": "2023.1.3" - } - ], - "jniDependencies": [ - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-driver", - "version": "2023.1.3", - "skipInvalidPlatforms": true, - "isJar": false, - "validPlatforms": [ - "windowsx86-64", - "windowsx86", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - } - ], - "cppDependencies": [ - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-cpp", - "version": "2023.1.3", - "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": "2023.1.3", - "libName": "REVLibDriver", - "headerClassifier": "headers", - "sharedLibrary": false, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "windowsx86", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - } - ] + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "skipInvalidPlatforms": true, + "isJar": false, + "version": "2023.1.3" + }], + "mavenUrls": ["https://maven.revrobotics.com/"], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "libName": "REVLib", + "artifactId": "REVLib-cpp", + "skipInvalidPlatforms": true, + "version": "2023.1.3", + "headerClassifier": "headers", + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ], + "sharedLibrary": false + }, + { + "groupId": "com.revrobotics.frc", + "libName": "REVLibDriver", + "artifactId": "REVLib-driver", + "skipInvalidPlatforms": true, + "version": "2023.1.3", + "headerClassifier": "headers", + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ], + "sharedLibrary": false + } + ], + "version": "2023.1.3", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb" }