diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json new file mode 100644 index 0000000..d2a15b8 --- /dev/null +++ b/.wpilib/wpilib_preferences.json @@ -0,0 +1,6 @@ +{ + "currentLanguage": "none", + "enableCppIntellisense": false, + "projectYear": "2025", + "teamNumber": 199 +} diff --git a/src/main/java/org/carlmontrobotics/Constants.java b/src/main/java/org/carlmontrobotics/Constants.java index 6d6986d..553e56c 100644 --- a/src/main/java/org/carlmontrobotics/Constants.java +++ b/src/main/java/org/carlmontrobotics/Constants.java @@ -1,15 +1,35 @@ package org.carlmontrobotics; +import edu.wpi.first.wpilibj.StadiaController.Button; + public final class Constants { - // public static final class Drivetrain { - // public static final double MAX_SPEED_MPS = 2; - // } public static final class OI { public static final class Driver { - public static final int port = 0; + public static final int DRIVE_CONTROLLER_PORT = 0; } public static final class Manipulator { - public static final int port = 1; + public static final int MANIPULATOR_CONTROLLER_PORT = 1; + public static final int OUTTAKE_BUTTON = Button.kA.value; + public static final int INTAKE_BUTTON = Button.kB.value; } } + public static final class CoralEffectorc{ + public final static int CORAL_MOTOR_PORT = 30; + public final static int CORAL_LIMIT_SWITCH_PORT = 0; + public final static int CORAL_DISTANCE_SENSOR_PORT = 6; + public final static int CORAL_DISTANCE_SENSOR_DISTANCE = 150; //mm + public final static double CORAL_INTAKE_ERR = .1;//encoder units - rotations + public final static double INPUT_FAST_SPEED = 0.2; //TODO: tune this + public final static double INPUT_SLOW_SPEED = 0.1; //TODO: tune this + public final static double OUTPUT_SPEED = 0.5; //TODO: tune this + public final static double CORAL_EFFECTOR_DISTANCE_SENSOR_OFFSET = -0.1; //TOD: tune this? + public final static double KP = 1.3; //TODO: tune this + public final static double KI = 0; + public final static double KD = 0; + public final static double INTAKE_TIME_OUT = 0.25; + public final static double OUTTAKE_TIME_OUT = 10; + public final static double MANUAL_INTAKE_TIME_OUT = 1; + public final static double COAST_VELOCITY_AT_INPUT = 300; + //public final static int LIMIT_SWITCH_PORT = 7; //TODO: Change + } } diff --git a/src/main/java/org/carlmontrobotics/Robot.java b/src/main/java/org/carlmontrobotics/Robot.java index 0bd19d3..55e89f2 100644 --- a/src/main/java/org/carlmontrobotics/Robot.java +++ b/src/main/java/org/carlmontrobotics/Robot.java @@ -4,6 +4,8 @@ package org.carlmontrobotics; +import org.carlmontrobotics.commands.CoralIntake; + import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; @@ -17,7 +19,6 @@ public class Robot extends TimedRobot { private Command m_autonomousCommand; private RobotContainer m_robotContainer; - @Override public void robotInit() { m_robotContainer = new RobotContainer(); diff --git a/src/main/java/org/carlmontrobotics/RobotContainer.java b/src/main/java/org/carlmontrobotics/RobotContainer.java index 836869c..904a4fc 100644 --- a/src/main/java/org/carlmontrobotics/RobotContainer.java +++ b/src/main/java/org/carlmontrobotics/RobotContainer.java @@ -9,10 +9,24 @@ // import org.carlmontrobotics.commands.*; import static org.carlmontrobotics.Constants.OI; +import java.util.function.BooleanSupplier; + +import org.carlmontrobotics.Constants.OI; +import org.carlmontrobotics.Constants.OI.Manipulator; +import org.carlmontrobotics.commands.CoralIntake; +import org.carlmontrobotics.commands.CoralOuttake; +import org.carlmontrobotics.commands.StopCoralMotor; +import org.carlmontrobotics.commands.TapCoralIn; +import org.carlmontrobotics.commands.CoralIntakeManual; +import org.carlmontrobotics.subsystems.CoralEffector; + +//limit switch +import edu.wpi.first.wpilibj.DigitalInput; //controllers import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.XboxController.Axis; - +import edu.wpi.first.wpilibj.XboxController.Button; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; //commands import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -25,15 +39,24 @@ import edu.wpi.first.wpilibj2.command.button.POVButton; import edu.wpi.first.wpilibj2.command.button.Trigger; +//constats +import static org.carlmontrobotics.Constants.CoralEffectorc.*; +import static org.carlmontrobotics.Constants.OI.Driver.*; +import static org.carlmontrobotics.Constants.OI.Manipulator.*; + public class RobotContainer { //1. using GenericHID allows us to use different kinds of controllers //2. Use absolute paths from constants to reduce confusion - public final GenericHID driverController = new GenericHID(OI.Driver.port); - public final GenericHID manipulatorController = new GenericHID(OI.Manipulator.port); + public final GenericHID driverController = new GenericHID(DRIVE_CONTROLLER_PORT); + public final GenericHID manipulatorController = new GenericHID(MANIPULATOR_CONTROLLER_PORT); + public final CoralEffector coralEffector = new CoralEffector(); - public RobotContainer() { + //public final DigitalInput limitSwitch = new DigitalInput(LIMIT_SWITCH_PORT); + public RobotContainer() { + SmartDashboard.putData("Coral Intake", new CoralIntake(coralEffector)); + SmartDashboard.putData("coral out", new CoralOuttake(coralEffector)); setDefaultCommands(); setBindingsDriver(); setBindingsManipulator(); @@ -49,7 +72,26 @@ private void setDefaultCommands() { // )); } private void setBindingsDriver() {} - private void setBindingsManipulator() {} + private void setBindingsManipulator() { + // new JoystickButton(manipulatorController, OI.Manipulator.OUTAKE_BUTTON) + // .whileTrue(new CoralOutake(coralEffector)) + // .whileFalse(new CoralIntake(coralEffector)); + // new JoystickButton(manipulatorController, OI.Manipulator.INTAKE_BUTTON) + // .whileTrue(new ManualCoralIntake()); + + axisTrigger(manipulatorController, Axis.kLeftTrigger) + .whileTrue(new CoralIntake(coralEffector)) + .onFalse(new StopCoralMotor(coralEffector)); + + + axisTrigger(manipulatorController, Axis.kRightTrigger) + .whileTrue(new CoralIntakeManual(coralEffector)) + .onFalse(new StopCoralMotor(coralEffector)); + + new JoystickButton(manipulatorController, (Button.kA.value)).onTrue(new TapCoralIn(coralEffector)); + } + + public Command getAutonomousCommand() { return Commands.print("No autonomous command configured"); @@ -89,4 +131,8 @@ private double inputProcessing(double value) { private double ProcessedAxisValue(GenericHID hid, Axis axis){ return inputProcessing(getStickValue(hid, axis)); } + + private Trigger axisTrigger(GenericHID controller, Axis axis) { + return new Trigger( (BooleanSupplier)(() -> Math.abs(getStickValue(controller, axis)) > 0.2) ); + } } diff --git a/src/main/java/org/carlmontrobotics/commands/CoralIntake.java b/src/main/java/org/carlmontrobotics/commands/CoralIntake.java new file mode 100644 index 0000000..5409184 --- /dev/null +++ b/src/main/java/org/carlmontrobotics/commands/CoralIntake.java @@ -0,0 +1,105 @@ +package org.carlmontrobotics.commands; + +import static org.carlmontrobotics.Constants.CoralEffectorc.*; +import org.carlmontrobotics.subsystems.CoralEffector; + +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.Command; + +public class CoralIntake extends Command { + // public static double spin; + // public static boolean fast2 = false; + Timer timer = new Timer(); + // Timer timer2 = new Timer(); + // Timer coralInTimer = new Timer(); + public static double coralMotorPosition; + private CoralEffector coralEffector; + private boolean isSeen = false; + private boolean isTouching = false; + private boolean firstTime = true; + private boolean bruh = false; + public CoralIntake(CoralEffector coralEffector) { + // Use addRequirements() here to declare subsystem dependencies. + // addRequirements(this.CoralEffector = CoralEffector); + addRequirements(this.coralEffector = coralEffector); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + coralEffector.setMotorSpeed(INPUT_FAST_SPEED); + timer.stop(); + timer.reset(); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + if(firstTime) { + if(coralEffector.distanceSensorSeesCoral()) { + firstTime = false; + bruh = coralEffector.distanceSensorSeesCoral(); + } + + } + // if(coralEffector.getVel() < COAST_VELOCITY_AT_INPUT && isSeen) { + // isTouching=true; + // } else { + // isTouching = false; + //} + // if (CoralEffector.distanceSensorSees) { + // coralIn = true; + // if (CoralEffector.limitSwitchSees) { + // CoralEffector.coralMotor.set(CoralEffectorConstants.coralEffectorMotorSlowSpeed); + // spin = CoralEffectorConstants.coralEffectorMotorSlowSpeed; + // } else { + // if (timer.get() < 0.15) { + // CoralEffector.coralMotor.set(CoralEffectorConstants.coralEffectorMotorFastSpeed); + // spin = CoralEffectorConstants.coralEffectorMotorFastSpeed; + // } else { + // CoralEffector.coralMotor.set(CoralEffectorConstants.coralEffectorMotorFastSpeed2); + // spin = CoralEffectorConstants.coralEffectorMotorFastSpeed2; + // } + // } + // } else { + // CoralEffector.coralMotor.set(0); + // spin = 0; + // timer.restart(); + // } + // CoralEffector.coralMotor.set(0.1); + // spin = 10; + // SmartDashboard.putNumber("spin", spin); + //SmartDashboard.putNumber("timer", timer.get()); + // SmartDashboard.getBoolean("outtakeGet", coralIn); + + // if (coralEffector.coralIn){ + // coralEffector.setReferencePosition(coralMotorPosition + CORAL_EFFECTOR_DISTANCE_SENSOR_OFFSET); //rotations + // } + if (coralEffector.distanceSensorSeesCoral()){ + coralEffector.setMotorSpeed(INPUT_SLOW_SPEED/2); + coralMotorPosition = coralEffector.getEncoderPos(); //mark the position in rotations + coralEffector.coralIn=true; + timer.start(); + } else { + coralEffector.setMotorSpeed(INPUT_FAST_SPEED); + } + + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + coralEffector.setMotorSpeed(0); + bruh = false; + if(interrupted != true) { + firstTime = true; + } + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return !coralEffector.distanceSensorSeesCoral() && bruh; + } +} \ No newline at end of file diff --git a/src/main/java/org/carlmontrobotics/commands/CoralIntakeManual.java b/src/main/java/org/carlmontrobotics/commands/CoralIntakeManual.java new file mode 100644 index 0000000..794f697 --- /dev/null +++ b/src/main/java/org/carlmontrobotics/commands/CoralIntakeManual.java @@ -0,0 +1,41 @@ +package org.carlmontrobotics.commands; + +import static org.carlmontrobotics.Constants.CoralEffectorc.*; +import org.carlmontrobotics.subsystems.CoralEffector; + +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.Command; + +import org.carlmontrobotics.subsystems.CoralEffector; + +/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ +public class CoralIntakeManual extends Command { + /** Creates a new CoralIntakeManual. */ + private CoralEffector coralEffector; + Timer timer = new Timer(); + public CoralIntakeManual(CoralEffector coralEffector) { + // Use addRequirements() here to declare subsystem dependencies. + addRequirements(this.coralEffector = coralEffector); + } + + // 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() { + coralEffector.setMotorSpeed(INPUT_FAST_SPEED); + } + + // 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 timer.get() > MANUAL_INTAKE_TIME_OUT; + } +} diff --git a/src/main/java/org/carlmontrobotics/commands/CoralOuttake.java b/src/main/java/org/carlmontrobotics/commands/CoralOuttake.java new file mode 100644 index 0000000..a2452a9 --- /dev/null +++ b/src/main/java/org/carlmontrobotics/commands/CoralOuttake.java @@ -0,0 +1,55 @@ +// 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 org.carlmontrobotics.commands; + +import static org.carlmontrobotics.Constants.CoralEffectorc.*; +import org.carlmontrobotics.subsystems.CoralEffector; + +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj2.command.Command; + +public class CoralOuttake extends Command { + /** Creates a new SetCoralOut. */ + private CoralEffector coralEffector; + Timer timer; + public CoralOuttake(CoralEffector coralEffector) { + addRequirements(this.coralEffector = coralEffector); + // Use addRequirements() here to declare subsystem dependencies. + timer = new Timer(); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + timer.reset(); + timer.start(); +coralEffector.setMotorSpeed(-OUTPUT_SPEED); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { +/* if (coralEffector.coralDetected()) { + coralEffector.setMotorSpeed(CoralEffectorConstants.coralEffectorMotorOutputSpeed); + timer.reset(); + timer.start(); + } + else */ + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + coralEffector.setMotorSpeed(0); + coralEffector.coralIn = false; + coralEffector.setIn(false); + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return timer.get() > OUTTAKE_TIME_OUT || !coralEffector.distanceSensorSeesCoral(); + } +} diff --git a/src/main/java/org/carlmontrobotics/commands/StopCoralMotor.java b/src/main/java/org/carlmontrobotics/commands/StopCoralMotor.java new file mode 100644 index 0000000..37f26a4 --- /dev/null +++ b/src/main/java/org/carlmontrobotics/commands/StopCoralMotor.java @@ -0,0 +1,16 @@ +package org.carlmontrobotics.commands; + +import org.carlmontrobotics.subsystems.CoralEffector; + +import edu.wpi.first.wpilibj2.command.Command; + +public class StopCoralMotor extends Command { + CoralEffector coralEffector; + public StopCoralMotor(CoralEffector coralEffector) { + this.coralEffector=coralEffector; + } + @Override + public void initialize() { + coralEffector.setMotorSpeed(0); + } +} diff --git a/src/main/java/org/carlmontrobotics/commands/TapCoralIn.java b/src/main/java/org/carlmontrobotics/commands/TapCoralIn.java new file mode 100644 index 0000000..b9c006d --- /dev/null +++ b/src/main/java/org/carlmontrobotics/commands/TapCoralIn.java @@ -0,0 +1,55 @@ +// 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 org.carlmontrobotics.commands; + + +import org.carlmontrobotics.Constants.CoralEffectorc; +import org.carlmontrobotics.subsystems.CoralEffector; + +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj2.command.Command; + +public class TapCoralIn extends Command { + /** Creates a new SetCoralOut. */ + private CoralEffector coralEffector; + Timer timer; + public TapCoralIn(CoralEffector coralEffector) { + addRequirements(this.coralEffector = coralEffector); + // Use addRequirements() here to declare subsystem dependencies. + timer = new Timer(); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + timer.reset(); + timer.start(); + coralEffector.setMotorSpeed(CoralEffectorc.INPUT_SLOW_SPEED); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { +/* if (coralEffector.coralDetected()) { + coralEffector.setMotorSpeed(CoralEffectorConstants.coralEffectorMotorOutputSpeed); + timer.reset(); + timer.start(); + } + else */ + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + coralEffector.setMotorSpeed(0); + //coralEffector.setCoralIn(false); + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return timer.get() > .2; //|| coralEffector.coralIn == true; + } +} diff --git a/src/main/java/org/carlmontrobotics/subsystems/CoralEffector.java b/src/main/java/org/carlmontrobotics/subsystems/CoralEffector.java new file mode 100644 index 0000000..3498ae2 --- /dev/null +++ b/src/main/java/org/carlmontrobotics/subsystems/CoralEffector.java @@ -0,0 +1,113 @@ +package org.carlmontrobotics.subsystems; +import org.carlmontrobotics.lib199.MotorConfig; +import org.carlmontrobotics.lib199.MotorControllerFactory; + +import com.playingwithfusion.TimeOfFlight; +import com.revrobotics.RelativeEncoder; +import com.revrobotics.servohub.ServoHub.ResetMode; +import com.revrobotics.spark.SparkFlex; +import com.revrobotics.spark.SparkBase.ControlType; +import com.revrobotics.spark.SparkBase.PersistMode; +import com.revrobotics.spark.SparkLowLevel.MotorType; +import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; +import com.revrobotics.spark.config.SparkFlexConfig; +import com.revrobotics.spark.config.SparkMaxConfig; + +import edu.wpi.first.units.measure.Velocity; +import edu.wpi.first.wpilibj.DigitalInput; +import edu.wpi.first.wpilibj.GenericHID; +import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import static org.carlmontrobotics.Constants.*; + +import static org.carlmontrobotics.Constants.CoralEffectorc.*; + +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.SparkFlex; +import com.revrobotics.spark.SparkLowLevel.MotorType; +import com.revrobotics.spark.SparkClosedLoopController; +import com.revrobotics.spark.SparkBase; + +public class CoralEffector extends SubsystemBase { + + public SparkFlex coralMotor = new SparkFlex(CORAL_MOTOR_PORT, MotorType.kBrushless); + // public DigitalInput coralLimitSwitch = new DigitalInput(CORAL_LIMIT_SWITCH_PORT); + //FIXME ADD THE LIMIT SWITCH!! + public TimeOfFlight distanceSensor = new TimeOfFlight(CORAL_DISTANCE_SENSOR_PORT); + + private boolean isIn = false; + public final RelativeEncoder coralEncoder = coralMotor.getEncoder(); + + private double coralOutput; + public boolean coralIn; + private double targetPos=0; + + SparkFlexConfig config = new SparkFlexConfig(); + public CoralEffector(){ + config + .inverted(true) + .idleMode(IdleMode.kBrake); + config.closedLoop + .feedbackSensor(FeedbackSensor.kPrimaryEncoder) + .pid(KP, KI, KD); + + coralMotor.configure(config, SparkBase.ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters); + } + + public double getEncoderPos() { + return coralEncoder.getPosition(); + } + public void setMotorSpeed(double speed) { + coralMotor.set(speed); + } + // public void setReferencePosition(double reference) { + // targetPos = reference; + // coralMotor.getClosedLoopController().setReference(reference, SparkBase.ControlType.kPosition); + // } + public boolean motorAtGoal(){ + return Math.abs(coralEncoder.getPosition()-targetPos) <= CORAL_INTAKE_ERR; + } + public double getVel() { + return coralEncoder.getVelocity(); + } + public boolean distanceSensorSeesCoral(){ + return distanceSensor.getRange() < CORAL_DISTANCE_SENSOR_DISTANCE-50; + } + + // public boolean coralIsIn() { + // return coralIn; + // } + // public void setCoralIn(boolean coralIsInside) { + // coralIn = coralIsInside; + // } + + // public boolean limitSwitchSeesCoral() { + // return !coralLimitSwitch.get(); + // } + public boolean getIn() { + return isIn; + } + public void setIn(boolean in) { + isIn = in; + } + @Override + public void periodic() { + //coralMotor.getClosedLoopController().setReference(1, ControlType.kVelocity); + // limitSwitchSees = !coralLimitSwitch.get(); + // CoralGoalRPM = coralEncoder.getVelocity(); + coralOutput = coralMotor.getAppliedOutput(); + + SmartDashboard.putBoolean("Distance sensor", distanceSensorSeesCoral()); + SmartDashboard.putNumber("distance", distanceSensor.getRange()); + SmartDashboard.putBoolean("coral in", coralIn); + // SmartDashboard.putBoolean("limit switch", limitSwitchSees); + // SmartDashboard.putNumber("Coral goal RPM", CoralGoalRPM); + SmartDashboard.putNumber("Coral Speed", coralEncoder.getVelocity()); + SmartDashboard.putNumber("coral output", coralOutput); + SmartDashboard.getNumber("P", KP); +//coralMotor.set(INPUT_FAST_SPEED); + } +} \ No newline at end of file diff --git a/vendordeps/PathplannerLib-2025.2.1.json b/vendordeps/PathplannerLib-2025.2.5.json similarity index 87% rename from vendordeps/PathplannerLib-2025.2.1.json rename to vendordeps/PathplannerLib-2025.2.5.json index 71e25f3..b2a7265 100644 --- a/vendordeps/PathplannerLib-2025.2.1.json +++ b/vendordeps/PathplannerLib-2025.2.5.json @@ -1,7 +1,7 @@ { - "fileName": "PathplannerLib-2025.2.1.json", + "fileName": "PathplannerLib-2025.2.5.json", "name": "PathplannerLib", - "version": "2025.2.1", + "version": "2025.2.5", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2025", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2025.2.1" + "version": "2025.2.5" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2025.2.1", + "version": "2025.2.5", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, diff --git a/vendordeps/Phoenix6-25.1.0.json b/vendordeps/Phoenix6-25.3.1.json similarity index 80% rename from vendordeps/Phoenix6-25.1.0.json rename to vendordeps/Phoenix6-25.3.1.json index 473f6a8..a216d97 100644 --- a/vendordeps/Phoenix6-25.1.0.json +++ b/vendordeps/Phoenix6-25.3.1.json @@ -1,7 +1,7 @@ { - "fileName": "Phoenix6-25.1.0.json", + "fileName": "Phoenix6-25.3.1.json", "name": "CTRE-Phoenix (v6)", - "version": "25.1.0", + "version": "25.3.1", "frcYear": "2025", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ @@ -19,14 +19,14 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "25.1.0" + "version": "25.3.1" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "api-cpp", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -40,7 +40,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -54,7 +54,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "api-cpp-sim", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -68,7 +68,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -82,7 +82,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -96,7 +96,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -110,7 +110,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -124,7 +124,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -138,7 +138,21 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.1.0", + "version": "25.3.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -152,7 +166,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -166,7 +180,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.1.0", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -180,7 +194,21 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.1.0", + "version": "25.3.1", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "25.3.1", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -196,7 +224,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -212,7 +240,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -228,7 +256,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -244,7 +272,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -260,7 +288,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -276,7 +304,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -292,7 +320,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -308,7 +336,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -324,7 +352,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -337,10 +365,26 @@ ], "simMode": "swsim" }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "25.3.1", + "libName": "CTRE_SimProTalonFXS", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -356,7 +400,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, @@ -372,7 +416,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANrange", - "version": "25.1.0", + "version": "25.3.1", "libName": "CTRE_SimProCANrange", "headerClassifier": "headers", "sharedLibrary": true, @@ -384,6 +428,22 @@ "osxuniversal" ], "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "25.3.1", + "libName": "CTRE_SimProCANdi", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" } ] } \ No newline at end of file diff --git a/vendordeps/REVLib-2025.0.0.json b/vendordeps/REVLib.json similarity index 86% rename from vendordeps/REVLib-2025.0.0.json rename to vendordeps/REVLib.json index cde6011..ac62be8 100644 --- a/vendordeps/REVLib-2025.0.0.json +++ b/vendordeps/REVLib.json @@ -1,7 +1,7 @@ { - "fileName": "REVLib-2025.0.0.json", + "fileName": "REVLib.json", "name": "REVLib", - "version": "2025.0.0", + "version": "2025.0.3", "frcYear": "2025", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ @@ -12,19 +12,18 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2025.0.0" + "version": "2025.0.3" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2025.0.0", + "version": "2025.0.3", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ "windowsx86-64", - "windowsx86", "linuxarm64", "linuxx86-64", "linuxathena", @@ -37,14 +36,13 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2025.0.0", + "version": "2025.0.3", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", - "windowsx86", "linuxarm64", "linuxx86-64", "linuxathena", @@ -55,14 +53,13 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2025.0.0", + "version": "2025.0.3", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", - "windowsx86", "linuxarm64", "linuxx86-64", "linuxathena", diff --git a/vendordeps/Studica-2025.0.0.json b/vendordeps/Studica-2025.0.1.json similarity index 89% rename from vendordeps/Studica-2025.0.0.json rename to vendordeps/Studica-2025.0.1.json index ddb0e44..5010be0 100644 --- a/vendordeps/Studica-2025.0.0.json +++ b/vendordeps/Studica-2025.0.1.json @@ -1,13 +1,13 @@ { - "fileName": "Studica-2025.0.0.json", + "fileName": "Studica-2025.0.1.json", "name": "Studica", - "version": "2025.0.0", + "version": "2025.0.1", "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", "frcYear": "2025", "mavenUrls": [ "https://dev.studica.com/maven/release/2025/" ], - "jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.0.0.json", + "jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.0.1.json", "cppDependencies": [ { "artifactId": "Studica-cpp", @@ -24,7 +24,7 @@ "libName": "Studica", "sharedLibrary": false, "skipInvalidPlatforms": true, - "version": "2025.0.0" + "version": "2025.0.1" }, { "artifactId": "Studica-driver", @@ -41,14 +41,14 @@ "libName": "StudicaDriver", "sharedLibrary": false, "skipInvalidPlatforms": true, - "version": "2025.0.0" + "version": "2025.0.1" } ], "javaDependencies": [ { "artifactId": "Studica-java", "groupId": "com.studica.frc", - "version": "2025.0.0" + "version": "2025.0.1" } ], "jniDependencies": [ @@ -65,7 +65,7 @@ "osxuniversal", "windowsx86-64" ], - "version": "2025.0.0" + "version": "2025.0.1" } ] } \ No newline at end of file diff --git a/vendordeps/PlayingWithFusion-2025.01.04.json b/vendordeps/playingwithfusion2025.json similarity index 82% rename from vendordeps/PlayingWithFusion-2025.01.04.json rename to vendordeps/playingwithfusion2025.json index 580c121..61a5641 100644 --- a/vendordeps/PlayingWithFusion-2025.01.04.json +++ b/vendordeps/playingwithfusion2025.json @@ -1,7 +1,7 @@ { - "fileName": "PlayingWithFusion-2025.01.04.json", + "fileName": "playingwithfusion2025.json", "name": "PlayingWithFusion", - "version": "2025.01.04", + "version": "2025.01.23", "uuid": "14b8ad04-24df-11ea-978f-2e728ce88125", "frcYear": "2025", "jsonUrl": "https://www.playingwithfusion.com/frc/playingwithfusion2025.json", @@ -12,21 +12,23 @@ { "groupId": "com.playingwithfusion.frc", "artifactId": "PlayingWithFusion-java", - "version": "2025.01.04" + "version": "2025.01.23" } ], "jniDependencies": [ { "groupId": "com.playingwithfusion.frc", "artifactId": "PlayingWithFusion-driver", - "version": "2025.01.04", + "version": "2025.01.23", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ "windowsx86-64", + "windowsx86", "linuxarm64", "linuxx86-64", "linuxathena", + "linuxarm32", "osxuniversal" ] } @@ -35,32 +37,36 @@ { "groupId": "com.playingwithfusion.frc", "artifactId": "PlayingWithFusion-cpp", - "version": "2025.01.04", + "version": "2025.01.23", "headerClassifier": "headers", "sharedLibrary": false, "libName": "PlayingWithFusion", "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", + "windowsx86", "linuxarm64", "linuxx86-64", "linuxathena", + "linuxarm32", "osxuniversal" ] }, { "groupId": "com.playingwithfusion.frc", "artifactId": "PlayingWithFusion-driver", - "version": "2025.01.04", + "version": "2025.01.23", "headerClassifier": "headers", "sharedLibrary": true, "libName": "PlayingWithFusionDriver", "skipInvalidPlatforms": true, "binaryPlatforms": [ "windowsx86-64", + "windowsx86", "linuxarm64", "linuxx86-64", "linuxathena", + "linuxarm32", "osxuniversal" ] }