diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/frc/robot/BuildConstants.java index 09f0aadb..8cbe8222 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/frc/robot/BuildConstants.java @@ -3,15 +3,15 @@ /** Automatically generated file containing build version information. */ public final class BuildConstants { public static final String MAVEN_GROUP = ""; - public static final String MAVEN_NAME = "offseason-robot-code-2024"; + public static final String MAVEN_NAME = "offseason-robot-code-2024-1"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 464; - public static final String GIT_SHA = "e85bebc1ff41f2682e3d4ccbe67f1f5ce0f8a0f3"; - public static final String GIT_DATE = "2024-12-08 17:15:05 EST"; - public static final String GIT_BRANCH = "add-aquila-constants"; - public static final String BUILD_DATE = "2024-12-08 17:29:19 EST"; - public static final long BUILD_UNIX_TIME = 1733696959570L; - public static final int DIRTY = 0; + public static final int GIT_REVISION = 533; + public static final String GIT_SHA = "79a886e543767e4320fa8f9f31ac613afa9377c3"; + public static final String GIT_DATE = "2025-01-02 19:18:09 EST"; + public static final String GIT_BRANCH = "vision-sim"; + public static final String BUILD_DATE = "2025-01-03 21:17:04 EST"; + public static final long BUILD_UNIX_TIME = 1735957024697L; + public static final int DIRTY = 1; private BuildConstants() {} } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index f2cac57f..b3a2417a 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -24,21 +24,21 @@ public class Robot extends LoggedRobot { public Robot() { // Record metadata // Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME); - // Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE); - // Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA); - // Logger.recordMetadata("GitDate", BuildConstants.GIT_DATE); - // Logger.recordMetadata("GitBranch", BuildConstants.GIT_BRANCH); - // switch (BuildConstants.DIRTY) { - // case 0: - // Logger.recordMetadata("GitDirty", "All changes committed"); - // break; - // case 1: - // Logger.recordMetadata("GitDirty", "Uncomitted changes"); - // break; - // default: - // Logger.recordMetadata("GitDirty", "Unknown"); - // break; - // } + Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE); + Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA); + Logger.recordMetadata("GitDate", BuildConstants.GIT_DATE); + Logger.recordMetadata("GitBranch", BuildConstants.GIT_BRANCH); + switch (BuildConstants.DIRTY) { + case 0: + Logger.recordMetadata("GitDirty", "All changes committed"); + break; + case 1: + Logger.recordMetadata("GitDirty", "Uncomitted changes"); + break; + default: + Logger.recordMetadata("GitDirty", "Unknown"); + break; + } // Set up data receivers & replay source switch (Constants.CURRENT_MODE) { diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index f8742040..b3c60e7e 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -8,7 +8,6 @@ import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.Trigger; -import frc.robot.Constants.SimulationConstants; import frc.robot.commands.drive.DriveCommand; import frc.robot.extras.simulation.field.SimulatedField; import frc.robot.extras.simulation.mechanismSim.swerve.GyroSimulation; @@ -87,8 +86,8 @@ public RobotContainer() { DriveConstants.TRACK_WIDTH + .2, DriveConstants.WHEEL_BASE + .2, SwerveModuleSimulation.getModule( - DCMotor.getFalcon500(1), - DCMotor.getFalcon500(1), + DCMotor.getKrakenX60(1).withReduction(ModuleConstants.DRIVE_GEAR_RATIO), + DCMotor.getFalcon500(1).withReduction(11), 60, WHEEL_GRIP.TIRE_WHEEL, ModuleConstants.DRIVE_GEAR_RATIO), @@ -145,7 +144,7 @@ private void resetFieldAndOdometryForAuto(Pose2d robotStartingPoseAtBlueAlliance } // swerveDrive.periodic(); - swerveDrive.resetPosition(startingPose); + swerveDrive.setPose(startingPose); } public void teleopInit() { @@ -246,7 +245,7 @@ private void configureButtonBindings() { driverRightDirectionPad.onTrue( new InstantCommand( () -> - swerveDrive.resetPosition( + swerveDrive.setPose( new Pose2d( swerveDrive.getPose().getX(), swerveDrive.getPose().getY(), @@ -255,11 +254,10 @@ private void configureButtonBindings() { .x() .onTrue( new InstantCommand( - () -> - swerveDrive.resetPosition(swerveDriveSimulation.getSimulatedDriveTrainPose()))); + () -> swerveDrive.setPose(swerveDriveSimulation.getSimulatedDriveTrainPose()))); // // // Reset robot odometry based on vision pose measurement from april tags driverLeftDirectionPad.onTrue( - new InstantCommand(() -> swerveDrive.resetPosition(visionSubsystem.getLastSeenPose()))); + new InstantCommand(() -> swerveDrive.setPose(visionSubsystem.getLastSeenPose()))); // // driverLeftDpad.onTrue(new InstantCommand(() -> swerveDrive.resetOdometry(new // Pose2d(15.251774787902832, 5.573054313659668, Rotation2d.fromRadians(3.14159265))))); // // driverBButton.whileTrue(new ShootPass(swerveDrive, shooterSubsystem, pivotSubsystem, @@ -308,7 +306,7 @@ private void configureButtonBindings() { public Command getAutonomousCommand() { // Resets the pose factoring in the robot side // This is just a failsafe, pose should be reset at the beginning of auto - swerveDrive.resetPosition( + swerveDrive.setPose( new Pose2d( swerveDrive.getPose().getX(), swerveDrive.getPose().getY(), diff --git a/src/main/java/frc/robot/commands/drive/DriveCommandBase.java b/src/main/java/frc/robot/commands/drive/DriveCommandBase.java index 83f8aab0..73ae4529 100644 --- a/src/main/java/frc/robot/commands/drive/DriveCommandBase.java +++ b/src/main/java/frc/robot/commands/drive/DriveCommandBase.java @@ -4,6 +4,7 @@ import edu.wpi.first.wpilibj2.command.Command; import frc.robot.extras.interpolators.MultiLinearInterpolator; +import frc.robot.extras.util.TimeUtil; import frc.robot.subsystems.swerve.SwerveDrive; import frc.robot.subsystems.vision.Vision; import frc.robot.subsystems.vision.VisionConstants; @@ -70,7 +71,7 @@ public void calculatePoseFromLimelight(Limelight limelight) { swerveDrive.addPoseEstimatorVisionMeasurement( vision.getPoseFromAprilTags(limelight), - Logger.getTimestamp() - vision.getLatencySeconds(limelight)); + TimeUtil.getLogTimeSeconds() - vision.getLatencySeconds(limelight)); } Logger.recordOutput( diff --git a/src/main/java/frc/robot/extras/util/TimeUtil.java b/src/main/java/frc/robot/extras/util/TimeUtil.java index 754968af..3cad1701 100644 --- a/src/main/java/frc/robot/extras/util/TimeUtil.java +++ b/src/main/java/frc/robot/extras/util/TimeUtil.java @@ -1,5 +1,6 @@ package frc.robot.extras.util; +import edu.wpi.first.wpilibj.RobotController; import org.littletonrobotics.junction.Logger; public class TimeUtil { @@ -26,6 +27,6 @@ public static double getLogTimeSeconds() { } public static double getRealTimeSeconds() { - return Logger.getRealTimestamp() / 1_000_000.0; + return RobotController.getFPGATime() / 1_000_000.0; } } diff --git a/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java b/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java index 5efcdc95..81e12f54 100644 --- a/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java +++ b/src/main/java/frc/robot/subsystems/swerve/SwerveDrive.java @@ -39,7 +39,7 @@ public class SwerveDrive extends SubsystemBase { private Rotation2d rawGyroRotation; private final SwerveModulePosition[] lastModulePositions; - private final SwerveDrivePoseEstimator odometry; + private final SwerveDrivePoseEstimator poseEstimator; private final SwerveSetpointGenerator setpointGenerator = new SwerveSetpointGenerator( @@ -86,10 +86,10 @@ public SwerveDrive( new SwerveModulePosition(), new SwerveModulePosition() }; - this.odometry = + this.poseEstimator = new SwerveDrivePoseEstimator( DriveConstants.DRIVE_KINEMATICS, - getGyroRotation2d(), + rawGyroRotation, lastModulePositions, new Pose2d(), VecBuilder.fill( @@ -99,7 +99,7 @@ public SwerveDrive( VisionConstants.VISION_Y_POS_TRUST, VisionConstants.VISION_ANGLE_TRUST)); - this.odometryThread = OdometryThread.createInstance(DeviceCANBus.CANIVORE); + this.odometryThread = OdometryThread.createInstance(DeviceCANBus.RIO); this.odometryThreadInputs = new OdometryThreadInputsAutoLogged(); this.odometryThread.start(); @@ -123,7 +123,7 @@ public SwerveDrive( */ public void addPoseEstimatorVisionMeasurement( Pose2d visionMeasurement, double currentTimeStampSeconds) { - odometry.addVisionMeasurement(visionMeasurement, currentTimeStampSeconds); + poseEstimator.addVisionMeasurement(visionMeasurement, currentTimeStampSeconds); } /** @@ -136,7 +136,7 @@ public void addPoseEstimatorVisionMeasurement( */ public void setPoseEstimatorVisionConfidence( double xStandardDeviation, double yStandardDeviation, double thetaStandardDeviation) { - odometry.setVisionMeasurementStdDevs( + poseEstimator.setVisionMeasurementStdDevs( VecBuilder.fill(xStandardDeviation, yStandardDeviation, thetaStandardDeviation)); } @@ -160,7 +160,6 @@ public void runCharacterization(double volts) { } /** Returns the average drive velocity in rotations/sec. */ - // TODO: fix method public double getCharacterizationVelocity() { double velocity = 0.0; for (SwerveModule module : swerveModules) { @@ -256,7 +255,7 @@ public void zeroHeading() { */ @AutoLogOutput(key = "Odometry/Odometry") public Pose2d getPose() { - return odometry.getEstimatedPosition(); + return poseEstimator.getEstimatedPosition(); } /** Returns a Rotation2d for the heading of the robot */ @@ -319,7 +318,7 @@ public void addPoseEstimatorSwerveMeasurement() { // int timestampIndex rawGyroRotation = rawGyroRotation.plus(new Rotation2d(twist.dtheta)); } - odometry.updateWithTime( + poseEstimator.updateWithTime( // odometryThreadInputs.measurementTimeStamps[timestampIndex], Logger.getTimestamp(), rawGyroRotation, modulePositions); } @@ -373,7 +372,7 @@ private SwerveModulePosition[] getModulePositions() { * * @param pose pose to set */ - public void resetPosition(Pose2d pose) { - odometry.resetPosition(getGyroRotation2d(), getModulePositions(), pose); + public void setPose(Pose2d pose) { + poseEstimator.resetPosition(rawGyroRotation, getModulePositions(), pose); } } diff --git a/src/main/java/frc/robot/subsystems/swerve/setpointGen/SwerveSetpointGenerator.java b/src/main/java/frc/robot/subsystems/swerve/setpointGen/SwerveSetpointGenerator.java index 392f9e1c..80fc630a 100644 --- a/src/main/java/frc/robot/subsystems/swerve/setpointGen/SwerveSetpointGenerator.java +++ b/src/main/java/frc/robot/subsystems/swerve/setpointGen/SwerveSetpointGenerator.java @@ -130,11 +130,7 @@ public SwerveSetpoint generateSetpoint( vars.prevSpeeds.vxMetersPerSecond + vars.minS * vars.dx, vars.prevSpeeds.vyMetersPerSecond + vars.minS * vars.dy, vars.prevSpeeds.omegaRadiansPerSecond + vars.minS * vars.dtheta); - retSpeeds.discretize( - retSpeeds.vxMetersPerSecond, - retSpeeds.vyMetersPerSecond, - retSpeeds.omegaRadiansPerSecond, - dt); + retSpeeds = ChassisSpeeds.discretize(retSpeeds, dt); double chassisAccelX = (retSpeeds.vxMetersPerSecond - vars.prevSpeeds.vxMetersPerSecond) / dt; double chassisAccelY = (retSpeeds.vyMetersPerSecond - vars.prevSpeeds.vyMetersPerSecond) / dt; diff --git a/src/main/java/frc/robot/subsystems/vision/PhysicalVision.java b/src/main/java/frc/robot/subsystems/vision/PhysicalVision.java index 33e481df..4ceab058 100644 --- a/src/main/java/frc/robot/subsystems/vision/PhysicalVision.java +++ b/src/main/java/frc/robot/subsystems/vision/PhysicalVision.java @@ -61,6 +61,8 @@ public void updateInputs(VisionInputs inputs) { inputs.limelightCalculatedPose[limelight.getId()] = getPoseFromAprilTags(limelight); inputs.limelightTimestamp[limelight.getId()] = getTimeStampSeconds(limelight); inputs.limelightLastSeenPose = getLastSeenPose(); + inputs.limelightAprilTagDistance[limelight.getId()] = + getLimelightAprilTagDistance(limelight); latestInputs.set(inputs); limelightThreads.get(limelight).set(latestInputs.get()); diff --git a/src/main/java/frc/robot/subsystems/vision/SimulatedVision.java b/src/main/java/frc/robot/subsystems/vision/SimulatedVision.java index b937a3d6..f2c5bd29 100644 --- a/src/main/java/frc/robot/subsystems/vision/SimulatedVision.java +++ b/src/main/java/frc/robot/subsystems/vision/SimulatedVision.java @@ -46,8 +46,8 @@ public SimulatedVision(Supplier robotSimulationPose) { // Create simulated camera properties. These can be set to mimic your actual // camera. var cameraProperties = new SimCameraProperties(); - // cameraProperties.setCalibration(kResWidth, kResHeight, Rotation2d.fromDegrees(97.7)); - // cameraProperties.setCalibError(0.35, 0.10); + cameraProperties.setCalibration(kResWidth, kResHeight, Rotation2d.fromDegrees(97.7)); + cameraProperties.setCalibError(0.35, 0.10); cameraProperties.setFPS(15); cameraProperties.setAvgLatencyMs(20); cameraProperties.setLatencyStdDevMs(5); @@ -63,23 +63,23 @@ public SimulatedVision(Supplier robotSimulationPose) { frontRightCameraSim = new PhotonCameraSim(getSimulationCamera(Limelight.FRONT_RIGHT), cameraProperties); - visionSim.addCamera(shooterCameraSim, VisionConstants.SHOOTER_TRANSFORM); - visionSim.addCamera(frontLeftCameraSim, VisionConstants.FRONT_LEFT_TRANSFORM); - visionSim.addCamera(frontRightCameraSim, VisionConstants.FRONT_RIGHT_TRANSFORM); + visionSim.addCamera(shooterCameraSim, VisionConstants.SHOOTER_TRANSFORM.inverse()); + visionSim.addCamera(frontLeftCameraSim, VisionConstants.FRONT_LEFT_TRANSFORM.inverse()); + visionSim.addCamera(frontRightCameraSim, VisionConstants.FRONT_RIGHT_TRANSFORM.inverse()); // Enable the raw and processed streams. (http://localhost:1181 / 1182) - shooterCameraSim.enableRawStream(true); - shooterCameraSim.enableProcessedStream(true); - frontLeftCameraSim.enableRawStream(true); - frontLeftCameraSim.enableProcessedStream(true); - frontRightCameraSim.enableRawStream(true); - frontRightCameraSim.enableProcessedStream(true); - - // Enable drawing a wireframe visualization of the field to the camera streams. - // This is extremely resource-intensive and is disabled by default. - shooterCameraSim.enableDrawWireframe(true); - frontLeftCameraSim.enableDrawWireframe(true); - frontRightCameraSim.enableDrawWireframe(true); + // shooterCameraSim.enableRawStream(true); + // shooterCameraSim.enableProcessedStream(true); + // frontLeftCameraSim.enableRawStream(true); + // frontLeftCameraSim.enableProcessedStream(true); + // frontRightCameraSim.enableRawStream(true); + // frontRightCameraSim.enableProcessedStream(true); + + // // Enable drawing a wireframe visualization of the field to the camera streams. + // // This is extremely resource-intensive and is disabled by default. + // shooterCameraSim.enableDrawWireframe(true); + // frontLeftCameraSim.enableDrawWireframe(true); + // frontRightCameraSim.enableDrawWireframe(true); } @Override @@ -97,8 +97,9 @@ public void updateInputs(VisionInputs inputs) { getSimulationCamera(limelight).getAllUnreadResults(), getLimelightTable(limelight), limelight); - inputs.limelightTargets[limelight.getId()] = getNumberOfAprilTags(limelight); - inputs.limelightAprilTagDistance[limelight.getId()] = getLimelightAprilTagDistance(limelight); + // inputs.limelightTargets[limelight.getId()] = getNumberOfAprilTags(limelight); + // inputs.limelightAprilTagDistance[limelight.getId()] = + // getLimelightAprilTagDistance(limelight); } super.updateInputs(inputs); } @@ -145,7 +146,13 @@ private void writeToTable( .setDoubleArray(pose_data.stream().mapToDouble(Double::doubleValue).toArray()); tagCount[limelight.getId()] = result.getMultiTagResult().get().fiducialIDsUsed.size(); apriltagDist[limelight.getId()] = - result.getMultiTagResult().get().estimatedPose.best.getX(); + result + .getMultiTagResult() + .get() + .estimatedPose + .best + .getTranslation() + .getDistance(result.getBestTarget().bestCameraToTarget.getTranslation()); } table.getEntry("tv").setInteger(result.hasTargets() ? 1 : 0); diff --git a/vendordeps/Phoenix6-frc2025-beta-latest.json b/vendordeps/Phoenix6-25.0.0-beta-4.json similarity index 83% rename from vendordeps/Phoenix6-frc2025-beta-latest.json rename to vendordeps/Phoenix6-25.0.0-beta-4.json index cd9d153a..5a588aab 100644 --- a/vendordeps/Phoenix6-frc2025-beta-latest.json +++ b/vendordeps/Phoenix6-25.0.0-beta-4.json @@ -1,7 +1,7 @@ { - "fileName": "Phoenix6-frc2025-beta-latest.json", + "fileName": "Phoenix6-25.0.0-beta-4.json", "name": "CTRE-Phoenix (v6)", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "frcYear": "2025", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "mavenUrls": [ @@ -19,14 +19,14 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "25.0.0-beta-3" + "version": "25.0.0-beta-4" } ], "jniDependencies": [ { "groupId": "com.ctre.phoenix6", "artifactId": "api-cpp", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -40,7 +40,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -54,7 +54,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "api-cpp-sim", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -68,7 +68,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -82,7 +82,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -96,7 +96,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -110,7 +110,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -124,7 +124,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -138,7 +138,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -152,7 +152,21 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -166,7 +180,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -182,7 +196,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, @@ -198,7 +212,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -214,7 +228,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, @@ -230,7 +244,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -246,7 +260,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -262,7 +276,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -278,7 +292,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -294,7 +308,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -310,7 +324,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -326,7 +340,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -339,10 +353,26 @@ ], "simMode": "swsim" }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.0.0-beta-4", + "libName": "CTRE_SimProCANrange", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "25.0.0-beta-3", + "version": "25.0.0-beta-4", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, diff --git a/vendordeps/Studica-2025.1.1-beta-3.json b/vendordeps/Studica-2025.1.1-beta-4.json similarity index 86% rename from vendordeps/Studica-2025.1.1-beta-3.json rename to vendordeps/Studica-2025.1.1-beta-4.json index 92a57d64..facfc721 100644 --- a/vendordeps/Studica-2025.1.1-beta-3.json +++ b/vendordeps/Studica-2025.1.1-beta-4.json @@ -1,13 +1,13 @@ { - "fileName": "Studica-2025.1.1-beta-3.json", + "fileName": "Studica-2025.1.1-beta-4.json", "name": "Studica", - "version": "2025.1.1-beta-3", + "version": "2025.1.1-beta-4", "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", "frcYear": "2025", "mavenUrls": [ "https://dev.studica.com/maven/release/2025/" ], - "jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.1.1-beta-3.json", + "jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.1.1-beta-4.json", "cppDependencies": [ { "artifactId": "Studica-cpp", @@ -24,7 +24,7 @@ "libName": "Studica", "sharedLibrary": false, "skipInvalidPlatforms": true, - "version": "2025.1.1-beta-3" + "version": "2025.1.1-beta-4" }, { "artifactId": "Studica-driver", @@ -41,14 +41,14 @@ "libName": "StudicaDriver", "sharedLibrary": false, "skipInvalidPlatforms": true, - "version": "2025.1.1-beta-3" + "version": "2025.1.1-beta-4" } ], "javaDependencies": [ { "artifactId": "Studica-java", "groupId": "com.studica.frc", - "version": "2025.1.1-beta-3" + "version": "2025.1.1-beta-4" } ], "jniDependencies": [ @@ -65,7 +65,7 @@ "osxuniversal", "windowsx86-64" ], - "version": "2025.1.1-beta-3" + "version": "2025.1.1-beta-4" } ] } diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib-v2025.0.0-beta-8.json similarity index 88% rename from vendordeps/photonlib.json rename to vendordeps/photonlib-v2025.0.0-beta-8.json index 2e8e6b00..1163429e 100644 --- a/vendordeps/photonlib.json +++ b/vendordeps/photonlib-v2025.0.0-beta-8.json @@ -1,7 +1,7 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2025.0.0-beta-5", + "version": "v2025.0.0-beta-8", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", "frcYear": "2025", "mavenUrls": [ @@ -13,7 +13,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2025.0.0-beta-5", + "version": "v2025.0.0-beta-8", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -28,7 +28,7 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-cpp", - "version": "v2025.0.0-beta-5", + "version": "v2025.0.0-beta-8", "libName": "photonlib", "headerClassifier": "headers", "sharedLibrary": true, @@ -43,7 +43,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2025.0.0-beta-5", + "version": "v2025.0.0-beta-8", "libName": "photontargeting", "headerClassifier": "headers", "sharedLibrary": true, @@ -60,12 +60,12 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-java", - "version": "v2025.0.0-beta-5" + "version": "v2025.0.0-beta-8" }, { "groupId": "org.photonvision", "artifactId": "photontargeting-java", - "version": "v2025.0.0-beta-5" + "version": "v2025.0.0-beta-8" } ] }