diff --git a/FRC_20230425_143032.wpilog b/FRC_20230425_143032.wpilog new file mode 100644 index 0000000..dc87608 Binary files /dev/null and b/FRC_20230425_143032.wpilog differ diff --git a/FRC_20230426_150848.wpilog b/FRC_20230426_150848.wpilog new file mode 100644 index 0000000..a450848 Binary files /dev/null and b/FRC_20230426_150848.wpilog differ diff --git a/simgui.json b/simgui.json index 5319b5b..4f14d84 100644 --- a/simgui.json +++ b/simgui.json @@ -71,6 +71,8 @@ "/Shuffleboard/Subsystems/SwitchIdleModeCommmand": "Command", "/Shuffleboard/Subsystems/Tank": "Subsystem", "/Shuffleboard/Subsystems/Turret": "Subsystem", + "/Shuffleboard/Subsystems/Vision": "Subsystem", + "/Shuffleboard/Vision/Vision": "PIDController", "/SmartDashboard/Field": "Field2d", "/SmartDashboard/Scheduler": "Scheduler" }, diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index fcd8fd8..4fd1b46 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -5,6 +5,7 @@ package frc.robot; import edu.wpi.first.networktables.GenericEntry; +import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.XboxController; @@ -78,25 +79,30 @@ public RobotContainer() { // add a few things to the shuffleboard // joysticks - var tab = Shuffleboard.getTab("Subsystems"); - tab.add(m_Arm); - tab.add(m_AutoCommand); - tab.add(m_BalanceCommand); - tab.add(m_DecreaseMaxSpeedCommand); - tab.add(m_DriveCommand); - tab.add(m_FineDriveCommand); - tab.add(m_IncreaseMaxSpeedCommand); - tab.add(m_MoveArmYCommand); - tab.add(m_PDP); - tab.add(m_PlaceCubeSecondLevelCommand); - tab.add(m_Vision); - - tab.add(m_PID); - tab.add(m_PlaceConeSecondLevelCommand); - tab.add(m_Tank); - tab.add(m_Claw); + var subsystemsTab = Shuffleboard.getTab("Subsystems"); + var mainTab = Shuffleboard.getTab("Main"); + subsystemsTab.add(m_Arm); + subsystemsTab.add(m_AutoCommand); + subsystemsTab.add(m_BalanceCommand); + subsystemsTab.add(m_DecreaseMaxSpeedCommand); + subsystemsTab.add(m_DriveCommand); + subsystemsTab.add(m_FineDriveCommand); + subsystemsTab.add(m_IncreaseMaxSpeedCommand); + subsystemsTab.add(m_MoveArmYCommand); + subsystemsTab.add(m_PDP); + subsystemsTab.add(m_PlaceCubeSecondLevelCommand); + subsystemsTab.add(m_Vision); + + subsystemsTab.add(m_PID); + subsystemsTab.add(m_PlaceConeSecondLevelCommand); + subsystemsTab.add(m_Tank); + subsystemsTab.add(m_Claw); Logger.configureLoggingAndConfig(this, false); + + + + } /** diff --git a/src/main/java/frc/robot/commands/DriveForward.java b/src/main/java/frc/robot/commands/DriveForward.java new file mode 100644 index 0000000..c932756 --- /dev/null +++ b/src/main/java/frc/robot/commands/DriveForward.java @@ -0,0 +1,43 @@ +// 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.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.Tank; + +public class DriveForward extends CommandBase { + /** Creates a new DriveForward. */ + private Tank m_tank; + + public DriveForward(Tank tank) { + // Use addRequirements() here to declare subsystem dependencies. + m_tank = tank; + addRequirements(m_tank); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + + m_tank.arcadeDrive(0.5, 0); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + m_tank.arcadeDrive(0, 0); + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc/robot/commands/DriveForwardAndPickUpPieceCommand.java b/src/main/java/frc/robot/commands/DriveForwardAndPickUpPieceCommand.java new file mode 100644 index 0000000..ce07679 --- /dev/null +++ b/src/main/java/frc/robot/commands/DriveForwardAndPickUpPieceCommand.java @@ -0,0 +1,21 @@ +// 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.commands; + +import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup; + +// NOTE: Consider using this command inline, rather than writing a subclass. For more +// information, see: +// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html +public class DriveForwardAndPickUpPieceCommand extends ParallelDeadlineGroup { + /** Creates a new DriveForwardAndPickUpPieceCommand. */ + public DriveForwardAndPickUpPieceCommand() { + // Add the deadline command in the super() call. Add other commands using + // addCommands(). + super(new InstantCommand()); + // addCommands(new FooCommand(), new BarCommand()); + } +} diff --git a/src/main/java/frc/robot/commands/FineDriveCommand.java b/src/main/java/frc/robot/commands/FineDriveCommand.java index ce19a66..b59800d 100644 --- a/src/main/java/frc/robot/commands/FineDriveCommand.java +++ b/src/main/java/frc/robot/commands/FineDriveCommand.java @@ -4,6 +4,8 @@ package frc.robot.commands; +import edu.wpi.first.networktables.GenericEntry; +import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj2.command.CommandBase; import frc.robot.RebindHat; import frc.robot.subsystems.Tank; @@ -11,22 +13,25 @@ public class FineDriveCommand extends CommandBase { @SuppressWarnings({ "PMD.UnusedPrivateField", "PMD.SingularField" }) private final Tank m_drivebase; + private double speedMult = 0.43; + private GenericEntry multWidget; public FineDriveCommand(Tank subsystem) { m_drivebase = subsystem; addRequirements(m_drivebase); + multWidget = Shuffleboard.getTab("Fine Drive").add("Speed", speedMult).getEntry(); } @Override public void initialize() { - // nothing to do here + } @Override public void execute() { // double check getMaxSpeed(), might be wrong m_drivebase.arcadeDrive( - RebindHat.ControllerToYAxis() * 0.43, RebindHat.ControllerToXAxis() * 0.43); + RebindHat.ControllerToYAxis() * multWidget.getDouble(0), RebindHat.ControllerToXAxis() * multWidget.getDouble(0)); } @Override diff --git a/src/main/java/frc/robot/commands/SpinIntake.java b/src/main/java/frc/robot/commands/SpinIntake.java new file mode 100644 index 0000000..c9f87ab --- /dev/null +++ b/src/main/java/frc/robot/commands/SpinIntake.java @@ -0,0 +1,36 @@ +// 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.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc.robot.subsystems.Claw; + +public class SpinIntake extends CommandBase { + private Claw m_claw; + /** Creates a new SpinIntake. */ + public SpinIntake(Claw claw) { + // Use addRequirements() here to declare subsystem dependencies. + m_claw = claw; + addRequirements(m_claw); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() {} + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() {} + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) {} + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc/robot/commands/TrackPiece.java b/src/main/java/frc/robot/commands/TrackPiece.java index aaeff25..4c90e0a 100644 --- a/src/main/java/frc/robot/commands/TrackPiece.java +++ b/src/main/java/frc/robot/commands/TrackPiece.java @@ -23,12 +23,15 @@ public TrackPiece(Vision vision, Tank tank) { // Called when the command is initially scheduled. @Override public void initialize() { - m_Tank.arcadeDrive(0.05, m_Vision.getController().calculate(m_Vision.getMeasurement(), m_Vision.getSetpoint())); + //m_Tank.arcadeDrive(0.05, m_Vision.getController().calculate(m_Vision.getMeasurement(), m_Vision.getSetpoint())); + m_Vision.enable(); SmartDashboard.putString("a", "pid on"); + } @Override public void execute() { + SmartDashboard.putNumber(getName(), m_Vision.getController().calculate(m_Vision.getMeasurement(), m_Vision.getSetpoint())); } // Called once the command ends or is interrupted. diff --git a/src/main/java/frc/robot/subsystems/Tank.java b/src/main/java/frc/robot/subsystems/Tank.java index 41a6676..d75a92e 100644 --- a/src/main/java/frc/robot/subsystems/Tank.java +++ b/src/main/java/frc/robot/subsystems/Tank.java @@ -134,7 +134,7 @@ public Tank() { drive.setSafetyEnabled(false); drive.setExpiration(0.1); - drive.setMaxOutput(1.0); + drive.setMaxOutput(0.8); brakeMode = true; SmartDashboard.putBoolean("brakeMode", brakeMode); diff --git a/src/main/java/frc/robot/subsystems/Vision.java b/src/main/java/frc/robot/subsystems/Vision.java index a64d1ab..a876883 100644 --- a/src/main/java/frc/robot/subsystems/Vision.java +++ b/src/main/java/frc/robot/subsystems/Vision.java @@ -12,9 +12,9 @@ public class Vision extends PIDSubsystem { /** Creates a new Vision. */ - private static double kP = 0.18; - private static double kI = 0.025; - private static double kD = 0.3; + private static double kP = 0.02; + private static double kI = 0.05; + private static double kD = 0.0007; public PIDController pidController; public Tank m_tank; @@ -26,17 +26,33 @@ public Vision(Tank tank) { addChild(getName(), m_controller); m_tank = tank; + m_controller.setSetpoint(0); + m_controller.setTolerance(2); + m_controller.setIntegratorRange(-0.43, 0.43); Shuffleboard.getTab(getName()).add(m_controller); - + } @Override public void useOutput(double output, double setpoint) { // Use the output here - m_tank.arcadeDrive(0.05, output); + if (0.40 < output) { + output = 0.40; + } else if (-0.40 > output) { + output = -0.40; + } else if (0 < output && output < 0.40) { + output = 0.40; + } else if (-0.40 < output && output < 0) { + output = -0.40; + } + + m_tank.arcadeDrive(0, -output * 1); + SmartDashboard.putNumber("will this work?", output); + SmartDashboard.putNumber("setpoint", setpoint); + } @Override @@ -65,8 +81,8 @@ public void setTolerance(double tolerance) { @Override public void periodic() { super.periodic(); - SmartDashboard.putNumber("stuff again", m_controller.calculate(getMeasurement(), m_controller.getSetpoint())); + SmartDashboard.putNumber("calculated turning output from vision", + m_controller.calculate(getMeasurement(), m_controller.getSetpoint())); } - } diff --git a/vendordeps/PhoenixProAnd5-frc2023-latest.json b/vendordeps/PhoenixProAnd5-frc2023-latest.json deleted file mode 100644 index b98097e..0000000 --- a/vendordeps/PhoenixProAnd5-frc2023-latest.json +++ /dev/null @@ -1,458 +0,0 @@ -{ - "fileName": "PhoenixProAnd5.json", - "name": "CTRE-Phoenix (Pro And v5)", - "version": "23.0.8", - "frcYear": 2023, - "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a", - "mavenUrls": [ - "https://maven.ctr-electronics.com/release/" - ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/PhoenixProAnd5-frc2023-latest.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.8" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.30.4", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.30.4", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro", - "artifactId": "tools", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "tools-sim", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simTalonSRX", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simTalonFX", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simVictorSPX", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simPigeonIMU", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simCANCoder", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simProTalonFX", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simProCANcoder", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simProPigeon2", - "version": "23.0.8", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "wpiapi-cpp", - "version": "5.30.4", - "libName": "CTRE_Phoenix_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "api-cpp", - "version": "5.30.4", - "libName": "CTRE_Phoenix", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.30.4", - "libName": "CTRE_PhoenixCCI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenixpro", - "artifactId": "tools", - "version": "23.0.8", - "libName": "CTRE_PhoenixTools", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "5.30.4", - "libName": "CTRE_Phoenix_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "api-cpp-sim", - "version": "5.30.4", - "libName": "CTRE_PhoenixSim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.30.4", - "libName": "CTRE_PhoenixCCISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "tools-sim", - "version": "23.0.8", - "libName": "CTRE_PhoenixTools_Sim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simTalonSRX", - "version": "23.0.8", - "libName": "CTRE_SimTalonSRX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simTalonFX", - "version": "23.0.8", - "libName": "CTRE_SimTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simVictorSPX", - "version": "23.0.8", - "libName": "CTRE_SimVictorSPX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simPigeonIMU", - "version": "23.0.8", - "libName": "CTRE_SimPigeonIMU", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simCANCoder", - "version": "23.0.8", - "libName": "CTRE_SimCANCoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simProTalonFX", - "version": "23.0.8", - "libName": "CTRE_SimProTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simProCANcoder", - "version": "23.0.8", - "libName": "CTRE_SimProCANcoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "simProPigeon2", - "version": "23.0.8", - "libName": "CTRE_SimProPigeon2", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenixpro", - "artifactId": "wpiapi-cpp", - "version": "23.0.8", - "libName": "CTRE_PhoenixPro_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenixpro.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "23.0.8", - "libName": "CTRE_PhoenixPro_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} \ No newline at end of file diff --git a/vendordeps/PhoenixProAnd5.json b/vendordeps/PhoenixProAnd5.json index 5ff6314..21206b0 100644 --- a/vendordeps/PhoenixProAnd5.json +++ b/vendordeps/PhoenixProAnd5.json @@ -1,7 +1,7 @@ { "fileName": "PhoenixProAnd5.json", "name": "CTRE-Phoenix (Pro And v5)", - "version": "23.0.7", + "version": "23.0.12", "frcYear": 2023, "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a", "mavenUrls": [ @@ -22,7 +22,7 @@ { "groupId": "com.ctre.phoenixpro", "artifactId": "wpiapi-java", - "version": "23.0.7" + "version": "23.0.12" } ], "jniDependencies": [ @@ -55,7 +55,7 @@ { "groupId": "com.ctre.phoenixpro", "artifactId": "tools", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -68,7 +68,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "tools-sim", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -81,7 +81,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonSRX", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -94,7 +94,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonFX", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -107,7 +107,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simVictorSPX", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -120,7 +120,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simPigeonIMU", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -133,7 +133,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simCANCoder", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -146,7 +146,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProTalonFX", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -159,7 +159,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProCANcoder", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -172,7 +172,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProPigeon2", - "version": "23.0.7", + "version": "23.0.12", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -232,7 +232,7 @@ { "groupId": "com.ctre.phoenixpro", "artifactId": "tools", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -292,7 +292,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "tools-sim", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -307,7 +307,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonSRX", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -322,7 +322,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simTalonFX", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_SimTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -337,7 +337,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simVictorSPX", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -352,7 +352,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simPigeonIMU", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -367,7 +367,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simCANCoder", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -382,7 +382,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProTalonFX", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -397,7 +397,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProCANcoder", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -412,7 +412,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "simProPigeon2", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -427,7 +427,7 @@ { "groupId": "com.ctre.phoenixpro", "artifactId": "wpiapi-cpp", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_PhoenixPro_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -442,7 +442,7 @@ { "groupId": "com.ctre.phoenixpro.sim", "artifactId": "wpiapi-cpp-sim", - "version": "23.0.7", + "version": "23.0.12", "libName": "CTRE_PhoenixPro_WPISim", "headerClassifier": "headers", "sharedLibrary": true,