From 58a6971704f425f2387eaef18e896971fe5afd60 Mon Sep 17 00:00:00 2001 From: Bradley Bickford Date: Mon, 12 Jan 2026 23:25:11 -0500 Subject: [PATCH] First tinkering iteration, missing some stuff --- build.gradle | 8 + src/main/java/frc/robot/Robot.java | 32 +- src/main/java/frc/robot/RobotContainer.java | 22 +- .../robot/constants/CompetitionConstants.java | 6 + .../robot/constants/DrivetrainConstants.java | 62 +++ .../robot/constants/KrakenMotorConstants.java | 5 + .../frc/robot/constants/ModuleConstants.java | 102 ++++ .../java/frc/robot/constants/OIConstants.java | 0 .../robot/interfaces/IAprilTagProvider.java | 40 ++ .../robot/interfaces/IVisualPoseProvider.java | 27 ++ .../java/frc/robot/subsystems/Drivetrain.java | 194 ++++++++ .../frc/robot/utilities/PhotonVision.java | 166 +++++++ .../frc/robot/utilities/SwerveModule.java | 123 +++++ vendordeps/AdvantageKit.json | 35 ++ vendordeps/PathplannerLib-2026.1.2.json | 38 ++ vendordeps/Phoenix5-5.36.0.json | 171 +++++++ vendordeps/Phoenix6-26.1.0.json | 449 ++++++++++++++++++ vendordeps/REVLib.json | 133 ++++++ vendordeps/Studica.json | 71 +++ vendordeps/photonlib.json | 71 +++ 20 files changed, 1752 insertions(+), 3 deletions(-) create mode 100644 src/main/java/frc/robot/constants/CompetitionConstants.java create mode 100644 src/main/java/frc/robot/constants/DrivetrainConstants.java create mode 100644 src/main/java/frc/robot/constants/KrakenMotorConstants.java create mode 100644 src/main/java/frc/robot/constants/ModuleConstants.java create mode 100644 src/main/java/frc/robot/constants/OIConstants.java create mode 100644 src/main/java/frc/robot/interfaces/IAprilTagProvider.java create mode 100644 src/main/java/frc/robot/interfaces/IVisualPoseProvider.java create mode 100644 src/main/java/frc/robot/subsystems/Drivetrain.java create mode 100644 src/main/java/frc/robot/utilities/PhotonVision.java create mode 100644 src/main/java/frc/robot/utilities/SwerveModule.java create mode 100644 vendordeps/AdvantageKit.json create mode 100644 vendordeps/PathplannerLib-2026.1.2.json create mode 100644 vendordeps/Phoenix5-5.36.0.json create mode 100644 vendordeps/Phoenix6-26.1.0.json create mode 100644 vendordeps/REVLib.json create mode 100644 vendordeps/Studica.json create mode 100644 vendordeps/photonlib.json diff --git a/build.gradle b/build.gradle index e9b0020..47f2286 100644 --- a/build.gradle +++ b/build.gradle @@ -50,6 +50,11 @@ wpi.java.debugJni = false // Set this to true to enable desktop support. def includeDesktopSupport = true +task(replayWatch, type: JavaExec) { + mainClass = "org.littletonrobotics.junction.ReplayWatch" + classpath = sourceSets.main.runtimeClasspath +} + // Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries. // Also defines JUnit 5. dependencies { @@ -73,6 +78,9 @@ dependencies { testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' testRuntimeOnly 'org.junit.platform:junit-platform-launcher' + + def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text) + annotationProcessor "org.littletonrobotics.akit:akit-autolog:$akitJson.version" } test { diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index cea1ffc..b5a3d16 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -4,16 +4,44 @@ package frc.robot; -import edu.wpi.first.wpilibj.TimedRobot; +import org.littletonrobotics.junction.LogFileUtil; +import org.littletonrobotics.junction.LoggedRobot; +import org.littletonrobotics.junction.Logger; +import org.littletonrobotics.junction.networktables.NT4Publisher; +import org.littletonrobotics.junction.wpilog.WPILOGReader; +import org.littletonrobotics.junction.wpilog.WPILOGWriter; + +import edu.wpi.first.wpilibj.PowerDistribution; +import edu.wpi.first.wpilibj.PowerDistribution.ModuleType; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; +import frc.robot.constants.CompetitionConstants; -public class Robot extends TimedRobot { +public class Robot extends LoggedRobot { private Command m_autonomousCommand; private final RobotContainer m_robotContainer; public Robot() { + Logger.recordMetadata("ProjectName", "2026_Robot_Code"); + + if(isReal()) { + if(CompetitionConstants.logToNetworkTables) { + Logger.addDataReceiver(new NT4Publisher()); + } + + Logger.addDataReceiver(new WPILOGWriter()); + + new PowerDistribution(1, ModuleType.kRev); + } else { + setUseTiming(false); + String logPath = LogFileUtil.findReplayLog(); + Logger.setReplaySource(new WPILOGReader(logPath)); + Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); + } + + Logger.start(); + m_robotContainer = new RobotContainer(); } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index de2c9d0..a6a2556 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -6,13 +6,33 @@ package frc.robot; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import frc.robot.constants.OIConstants; +import frc.robot.subsystems.Drivetrain; public class RobotContainer { + private Drivetrain drivetrain; + + private CommandXboxController driver; + public RobotContainer() { + drivetrain = new Drivetrain(); + + driver = new CommandXboxController(OIConstants.kDriverControllerPort); + configureBindings(); } - private void configureBindings() {} + private void configureBindings() { + drivetrain.setDefaultCommand( + drivetrain.drive( + driver::getLeftX, + driver::getLeftY, + driver::getRightX, + () -> true + ) + ); + } public Command getAutonomousCommand() { return Commands.print("No autonomous command configured"); diff --git a/src/main/java/frc/robot/constants/CompetitionConstants.java b/src/main/java/frc/robot/constants/CompetitionConstants.java new file mode 100644 index 0000000..6ff076a --- /dev/null +++ b/src/main/java/frc/robot/constants/CompetitionConstants.java @@ -0,0 +1,6 @@ +package frc.robot.constants; + +public class CompetitionConstants { + // THIS SHOULD BE FALSE DURING COMPETITION PLAY + public static final boolean logToNetworkTables = true; +} diff --git a/src/main/java/frc/robot/constants/DrivetrainConstants.java b/src/main/java/frc/robot/constants/DrivetrainConstants.java new file mode 100644 index 0000000..0d592db --- /dev/null +++ b/src/main/java/frc/robot/constants/DrivetrainConstants.java @@ -0,0 +1,62 @@ +package frc.robot.constants; + +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.kinematics.SwerveDriveKinematics; +import edu.wpi.first.math.util.Units; + +public class DrivetrainConstants { + // TODO Hold over from 2025, adjust? + public static final double kMaxSpeedMetersPerSecond = 4.125; + public static final double kMaxAngularSpeed = 2 * Math.PI; + + // TODO Replace zeros with real numbers + public static final double kTrackWidth = Units.inchesToMeters(0); + public static final double kWheelBase = Units.inchesToMeters(0); + + // TODO Replace zeros with real numbers + // These values should be determinable by writing the magnetic encoder output + // to the dashboard, and manually aligning all wheels such that the bevel gears + // on the side of the wheel all face left. Some known straight edge (like 1x1 or similar) + // should be used as the alignment medium. If done correctly, and the modules aren't disassembled, + // then these values should work throughout the season the first time they are set. + public static final double kFrontLeftMagEncoderOffset = 0; + public static final double kFrontRightMagEncoderOffset = 0; + public static final double kRearLeftMagEncoderOffset = 0; + public static final double kRearRightMagEncoderOffset = 0; + + // Kraken CAN IDs + // TODO Real CAN IDs + public static final int kFrontLeftDrivingCANID = 0; + public static final int kFrontRightDrivingCANID = 0; + public static final int kRearLeftDrivingCANID = 0; + public static final int kRearRightDrivingCANID = 0; + + // SparkMAX CAN IDs + // TODO Real CAN IDs + public static final int kFrontLeftTurningCANID = 0; + public static final int kFrontRightTurningCANID = 0; + public static final int kRearLeftTurningCANID = 0; + public static final int kRearRightTurningCANID = 0; + + // Analog Encoder Input Ports + // TODO Real Port IDs + public static final int kFrontLeftAnalogInPort = 0; + public static final int kFrontRightAnalogInPort = 0; + public static final int kRearLeftAnalogInPort = 0; + public static final int kRearRightAnalogInPort = 0; + + public static final boolean kGyroReversed = true; + + // TODO Hold over from 2025, adjust? + public static final double kHeadingP = .1; + public static final double kXTranslationP = .5; + public static final double kYTranslationP = .5; + + // YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A NEW CONFIGURATION ITEM + public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics( + new Translation2d(kWheelBase / 2, kTrackWidth / 2), + new Translation2d(kWheelBase / 2, -kTrackWidth / 2), + new Translation2d(-kWheelBase / 2, kTrackWidth / 2), + new Translation2d(-kWheelBase / 2, -kTrackWidth / 2) + ); +} diff --git a/src/main/java/frc/robot/constants/KrakenMotorConstants.java b/src/main/java/frc/robot/constants/KrakenMotorConstants.java new file mode 100644 index 0000000..7b5a29e --- /dev/null +++ b/src/main/java/frc/robot/constants/KrakenMotorConstants.java @@ -0,0 +1,5 @@ +package frc.robot.constants; + +public class KrakenMotorConstants { + public static final double kFreeSpeedRPM = 6000; +} diff --git a/src/main/java/frc/robot/constants/ModuleConstants.java b/src/main/java/frc/robot/constants/ModuleConstants.java new file mode 100644 index 0000000..c28b7ec --- /dev/null +++ b/src/main/java/frc/robot/constants/ModuleConstants.java @@ -0,0 +1,102 @@ +package frc.robot.constants; + +import com.ctre.phoenix6.configs.AudioConfigs; +import com.ctre.phoenix6.configs.CurrentLimitsConfigs; +import com.ctre.phoenix6.configs.FeedbackConfigs; +import com.ctre.phoenix6.configs.MotorOutputConfigs; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.signals.InvertedValue; +import com.ctre.phoenix6.signals.NeutralModeValue; +import com.revrobotics.spark.FeedbackSensor; +import com.revrobotics.spark.config.SparkMaxConfig; +import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; + +import edu.wpi.first.math.util.Units; + +public class ModuleConstants { + // DRIVING MOTOR CONFIG (Kraken) + // TODO Replace with something other than 0 + public static final double kDrivingMotorReduction = 0; + + public static final double kDrivingMotorFeedSpeedRPS = KrakenMotorConstants.kFreeSpeedRPM / 60; + public static final double kWheelDiameterMeters = Units.inchesToMeters(4); + public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI; + public static final double kDriveWheelFreeSpeedRPS = (kDrivingMotorFeedSpeedRPS * kWheelCircumferenceMeters) / + kDrivingMotorReduction; + public static final double kDrivingFactor = kWheelDiameterMeters * Math.PI / kDrivingMotorReduction; + public static final double kDrivingVelocityFeedForward = 1 / kDriveWheelFreeSpeedRPS; + + // TODO Hold over from 2025, adjust? + public static final double kDriveP = .04; + public static final double kDriveI = 0; + public static final double kDriveD = 0; + public static final double kDriveS = 0; + public static final double kDriveV = kDrivingVelocityFeedForward; + public static final double kDriveA = 0; + + // TODO Hold over from 2025, adjust? + public static final int kDriveMotorStatorCurrentLimit = 100; + public static final int kDriveMotorSupplyCurrentLimit = 65; + + // TODO Hold over from 2025, adjust? + public static final InvertedValue kDriveInversionState = InvertedValue.Clockwise_Positive; + public static final NeutralModeValue kDriveIdleMode = NeutralModeValue.Brake; + + // TURNING MOTOR CONFIG (NEO) + + // TODO Hold over from 2025, adjust? + public static final double kTurningMotorReduction = 0; + public static final double kTurningFactor = 2 * Math.PI / kTurningMotorReduction; + public static final double kTurnP = 1; + public static final double kTurnI = 0; + public static final double kTurnD = 0; + + public static final int kTurnMotorCurrentLimit = 20; + + public static final IdleMode kTurnIdleMode = IdleMode.kBrake; + + // YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A CONFIGURATION ITEM + + public static final SparkMaxConfig turningConfig = new SparkMaxConfig(); + + public static final FeedbackConfigs kDriveFeedConfig = new FeedbackConfigs(); + public static final CurrentLimitsConfigs kDriveCurrentLimitConfig = new CurrentLimitsConfigs(); + public static final MotorOutputConfigs kDriveMotorConfig = new MotorOutputConfigs(); + public static final AudioConfigs kAudioConfig = new AudioConfigs(); + public static final Slot0Configs kDriveSlot0Config = new Slot0Configs(); + + static { + kDriveFeedConfig.SensorToMechanismRatio = kDrivingMotorReduction; + + kDriveCurrentLimitConfig.StatorCurrentLimitEnable = true; + kDriveCurrentLimitConfig.SupplyCurrentLimitEnable = true; + kDriveCurrentLimitConfig.StatorCurrentLimit = kDriveMotorStatorCurrentLimit; + kDriveCurrentLimitConfig.SupplyCurrentLimit = kDriveMotorSupplyCurrentLimit; + + kDriveMotorConfig.Inverted = kDriveInversionState; + kDriveMotorConfig.NeutralMode = kDriveIdleMode; + + kAudioConfig.AllowMusicDurDisable = true; + + kDriveSlot0Config.kP = kDriveP; + kDriveSlot0Config.kI = kDriveI; + kDriveSlot0Config.kD = kDriveD; + kDriveSlot0Config.kS = kDriveS; + kDriveSlot0Config.kV = kDriveV; + kDriveSlot0Config.kA = kDriveA; + + turningConfig + .idleMode(kTurnIdleMode) + .smartCurrentLimit(kTurnMotorCurrentLimit); + turningConfig.encoder + .inverted(true) + .positionConversionFactor(kTurningFactor) + .velocityConversionFactor(kTurningFactor / 60.0); + turningConfig.closedLoop + .feedbackSensor(FeedbackSensor.kPrimaryEncoder) + .pid(kTurnP, kTurnI, kTurnD) + .outputRange(-1, 1) + .positionWrappingEnabled(true) + .positionWrappingInputRange(0, 2 * Math.PI); + } +} diff --git a/src/main/java/frc/robot/constants/OIConstants.java b/src/main/java/frc/robot/constants/OIConstants.java new file mode 100644 index 0000000..e69de29 diff --git a/src/main/java/frc/robot/interfaces/IAprilTagProvider.java b/src/main/java/frc/robot/interfaces/IAprilTagProvider.java new file mode 100644 index 0000000..632ea73 --- /dev/null +++ b/src/main/java/frc/robot/interfaces/IAprilTagProvider.java @@ -0,0 +1,40 @@ +package frc.robot.interfaces; + +import java.util.OptionalDouble; + +/** + * An interface which ensures a class can provide common AprilTag oriented + * information from various sources in a consistent way. + */ +public interface IAprilTagProvider { + /** + * A method to get the tags currently in the camera's field of view + * @return + */ + public int[] getVisibleTagIDs(); + + /** + * A method to get the distance from the camera to the AprilTag specified + * + * @param id The ID of the AprilTag to give a distance to + * @param targetHeightMeters The height of the AprilTag off the ground, in meters + * @return The distance, in meters, to the target, or OptionalDouble.empty() if the tag is not present in the camera's view + */ + public OptionalDouble getTagDistanceFromCameraByID(int id, double targetHeightMeters); + + /** + * A method to get the pitch from the center of the image of a particular AprilTag + * + * @param id The ID of the AprilTag to get the pitch of + * @return The pitch, in degrees, of the target, or OptionalDouble.empty() if the tag is not present in the camera's view + */ + public OptionalDouble getTagPitchByID(int id); + + /** + * A method to get the yaw from the center of the image of a particular AprilTag + * + * @param id The ID of the AprilTag to get the yaw of + * @return The yaw, in degrees, of the target, or OptionalDouble.empty() if the tag is not present in the camera's view + */ + public OptionalDouble getTagYawByID(int id); +} diff --git a/src/main/java/frc/robot/interfaces/IVisualPoseProvider.java b/src/main/java/frc/robot/interfaces/IVisualPoseProvider.java new file mode 100644 index 0000000..1f6cf62 --- /dev/null +++ b/src/main/java/frc/robot/interfaces/IVisualPoseProvider.java @@ -0,0 +1,27 @@ +package frc.robot.interfaces; + +import java.util.Optional; + +import edu.wpi.first.math.geometry.Pose2d; + +/** + * An interface which ensures a class' ability to provide visual pose information + * in a consistent way + */ +public interface IVisualPoseProvider { + /** + * A record that can contain the two elements necessary for a WPILIB + * pose estimator to use the information from a vision system as part of a full + * robot pose estimation + */ + public record VisualPose(Pose2d visualPose, double timestamp) {} + + /** + * Return a VisualPose or null if an empty Optional if none is available. + * Implementation should provide an empty response if it's unable to provide + * a reliable pose, or any pose at all. + * + * @return An Optional containing a VisualPose, or empty if no VisualPose can reliably be provided + */ + public Optional getVisualPose(); +} diff --git a/src/main/java/frc/robot/subsystems/Drivetrain.java b/src/main/java/frc/robot/subsystems/Drivetrain.java new file mode 100644 index 0000000..9df0d78 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Drivetrain.java @@ -0,0 +1,194 @@ +package frc.robot.subsystems; + +import java.util.function.BooleanSupplier; +import java.util.function.DoubleSupplier; + +import org.littletonrobotics.junction.Logger; + +import com.studica.frc.AHRS; +import com.studica.frc.AHRS.NavXComType; + +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.math.kinematics.SwerveDriveKinematics; +import edu.wpi.first.math.kinematics.SwerveModulePosition; +import edu.wpi.first.math.kinematics.SwerveModuleState; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.constants.DrivetrainConstants; +import frc.robot.constants.OIConstants; +import frc.robot.utilities.SwerveModule; + +public class Drivetrain extends SubsystemBase { + private SwerveModule frontLeft; + private SwerveModule frontRight; + private SwerveModule rearLeft; + private SwerveModule rearRight; + + private AHRS gyro; + + private SwerveDrivePoseEstimator estimator; + + public Drivetrain() { + frontLeft = new SwerveModule( + "FrontLeft", + DrivetrainConstants.kFrontLeftDrivingCANID, + DrivetrainConstants.kFrontLeftTurningCANID, + DrivetrainConstants.kFrontLeftAnalogInPort, + DrivetrainConstants.kFrontLeftMagEncoderOffset + ); + + frontRight = new SwerveModule( + "FrontRight", + DrivetrainConstants.kFrontRightDrivingCANID, + DrivetrainConstants.kFrontRightTurningCANID, + DrivetrainConstants.kFrontRightAnalogInPort, + DrivetrainConstants.kFrontRightMagEncoderOffset + ); + + rearLeft = new SwerveModule( + "RearLeft", + DrivetrainConstants.kRearLeftDrivingCANID, + DrivetrainConstants.kRearLeftTurningCANID, + DrivetrainConstants.kRearLeftAnalogInPort, + DrivetrainConstants.kRearLeftMagEncoderOffset + ); + + rearRight = new SwerveModule( + "RearRight", + DrivetrainConstants.kRearRightDrivingCANID, + DrivetrainConstants.kRearRightTurningCANID, + DrivetrainConstants.kRearRightAnalogInPort, + DrivetrainConstants.kRearRightMagEncoderOffset + ); + + gyro = new AHRS(NavXComType.kMXP_SPI); + + // TODO 2025 used non-standard deviations for encoder/gyro inputs and vision, will need to be tuned for 2026 in the future + estimator = new SwerveDrivePoseEstimator( + DrivetrainConstants.kDriveKinematics, + Rotation2d.fromDegrees(getGyroValue()), + new SwerveModulePosition[] { + frontLeft.getPosition(), + frontRight.getPosition(), + rearLeft.getPosition(), + rearRight.getPosition() + }, + new Pose2d() + ); + } + + @Override + public void periodic() { + estimator.update( + Rotation2d.fromDegrees(getGyroValue()), + new SwerveModulePosition[] { + frontLeft.getPosition(), + frontRight.getPosition(), + rearLeft.getPosition(), + rearRight.getPosition() + } + ); + + frontLeft.periodic(); + frontRight.periodic(); + rearLeft.periodic(); + rearRight.periodic(); + + Logger.recordOutput("Drivetrain/Pose", getPose()); + Logger.recordOutput("Drivetrain/Heading", getHeading()); + } + + public Command drive(DoubleSupplier xSpeed, DoubleSupplier ySpeed, DoubleSupplier rotation, BooleanSupplier fieldRelative) { + // TODO Inversions? Specific Alliance code? + return run(() -> { + drive( + MathUtil.applyDeadband(xSpeed.getAsDouble(), OIConstants.kDriveDeadband), + MathUtil.applyDeadband(ySpeed.getAsDouble(), OIConstants.kDriveDeadband), + MathUtil.applyDeadband(rotation.getAsDouble(), OIConstants.kDriveDeadband), + fieldRelative.getAsBoolean() + ); + }); + } + + public Command setX() { + return run(() -> { + frontLeft.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(45))); + frontRight.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(-45))); + rearLeft.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(-45))); + rearRight.setDesiredState(new SwerveModuleState(0, Rotation2d.fromDegrees(45))); + }); + } + + public void resetEncoders() { + frontLeft.resetEncoders(); + frontRight.resetEncoders(); + rearLeft.resetEncoders(); + rearRight.resetEncoders(); + } + + public void drive(double xSpeed, double ySpeed, double rotation, boolean fieldRelative) { + double p = Math.sqrt(Math.pow(xSpeed, 2) + Math.pow(ySpeed, 2)); + double xSpeedDelivered = 0; + double ySpeedDelivered = 0; + + if(p != 0){ + xSpeedDelivered = xSpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond; + ySpeedDelivered = ySpeed * (Math.pow(p, OIConstants.kJoystickExponential) / p) * DrivetrainConstants.kMaxSpeedMetersPerSecond; + }else{ + xSpeedDelivered = 0; + ySpeedDelivered = 0; + } + + double rotationDelivered = rotation * DrivetrainConstants.kMaxAngularSpeed; + + SwerveModuleState[] swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates( + fieldRelative ? + ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered, + estimator.getEstimatedPosition().getRotation()) : + new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered) + ); + + setModuleStates(swerveModuleStates); + } + + public void driveWithChassisSpeeds(ChassisSpeeds speeds) { + ChassisSpeeds discreteSpeeds = ChassisSpeeds.discretize(speeds, 0.2); + SwerveModuleState[] newStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(discreteSpeeds); + + setModuleStates(newStates); + } + + public void setModuleStates(SwerveModuleState[] desiredStates) { + SwerveDriveKinematics.desaturateWheelSpeeds( + desiredStates, DrivetrainConstants.kMaxSpeedMetersPerSecond); + frontLeft.setDesiredState(desiredStates[0]); + frontRight.setDesiredState(desiredStates[1]); + rearLeft.setDesiredState(desiredStates[2]); + rearRight.setDesiredState(desiredStates[3]); + } + + public ChassisSpeeds getCurrentChassisSpeeds() { + return DrivetrainConstants.kDriveKinematics.toChassisSpeeds( + frontLeft.getState(), + frontRight.getState(), + rearLeft.getState(), + rearRight.getState() + ); + } + + public Pose2d getPose() { + return estimator.getEstimatedPosition(); + } + + public double getGyroValue() { + return gyro.getAngle() * (DrivetrainConstants.kGyroReversed ? -1 : 1); + } + + public double getHeading() { + return estimator.getEstimatedPosition().getRotation().getDegrees(); + } +} diff --git a/src/main/java/frc/robot/utilities/PhotonVision.java b/src/main/java/frc/robot/utilities/PhotonVision.java new file mode 100644 index 0000000..0563c31 --- /dev/null +++ b/src/main/java/frc/robot/utilities/PhotonVision.java @@ -0,0 +1,166 @@ +package frc.robot.utilities; + +import java.io.IOException; +import java.util.List; +import java.util.Optional; +import java.util.OptionalDouble; + +import org.photonvision.EstimatedRobotPose; +import org.photonvision.PhotonCamera; +import org.photonvision.PhotonPoseEstimator; +import org.photonvision.PhotonPoseEstimator.PoseStrategy; +import org.photonvision.PhotonUtils; +import org.photonvision.targeting.PhotonPipelineResult; +import org.photonvision.targeting.PhotonTrackedTarget; + +import edu.wpi.first.apriltag.AprilTagFieldLayout; +import edu.wpi.first.apriltag.AprilTagFields; +import edu.wpi.first.math.geometry.Transform3d; +import edu.wpi.first.math.util.Units; +import frc.robot.interfaces.IAprilTagProvider; +import frc.robot.interfaces.IVisualPoseProvider; + +public class PhotonVision implements IAprilTagProvider,IVisualPoseProvider { + + private final PhotonCamera camera; + + private final PhotonPoseEstimator photonPoseEstimator; + + private final double cameraHeightMeters; + private final double cameraPitchRadians; + + private PhotonPipelineResult latestResult; + + public PhotonVision(String cameraName, Transform3d robotToCam, double cameraHeightMeters, double cameraPitchRadians) throws IOException { + camera = new PhotonCamera(cameraName); + + photonPoseEstimator = new PhotonPoseEstimator( + AprilTagFieldLayout.loadFromResource( + AprilTagFields.kDefaultField.m_resourceFile + ), + PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, + robotToCam + ); + + this.cameraHeightMeters = cameraHeightMeters; + this.cameraPitchRadians = cameraPitchRadians; + + this.latestResult = null; + } + + public void periodic() { + // TODO Do we care about missed results? Probably not, if we're taking long enough to miss results something else is wrong + List results = camera.getAllUnreadResults(); + + if(!results.isEmpty()) { + latestResult = results.get(results.size() - 1); + } + } + + @Override + public Optional getVisualPose() { + if(latestResult == null) { + return Optional.empty(); + } + + Optional pose = photonPoseEstimator.update(latestResult); + + if (pose.isEmpty()) { + return Optional.empty(); + } + + return Optional.of( + new VisualPose( + pose.get().estimatedPose.toPose2d(), + pose.get().timestampSeconds + ) + ); + } + + @Override + public OptionalDouble getTagDistanceFromCameraByID(int id, double targetHeightMeters) { + if (latestResult == null) { + return OptionalDouble.empty(); + } + + if (!latestResult.hasTargets()) { + return OptionalDouble.empty(); + } + + Optional desiredTarget = getTargetFromList(latestResult.getTargets(), id); + + if (desiredTarget.isEmpty()) { + return OptionalDouble.empty(); + } + + return OptionalDouble.of( + PhotonUtils.calculateDistanceToTargetMeters( + cameraHeightMeters, + targetHeightMeters, + cameraPitchRadians, + Units.degreesToRadians(desiredTarget.get().getPitch())) + ); + } + + @Override + public OptionalDouble getTagPitchByID(int id) { + if(latestResult == null) { + OptionalDouble.empty(); + } + + if (!latestResult.hasTargets()) { + return OptionalDouble.empty(); + } + + Optional desiredTarget = getTargetFromList(latestResult.getTargets(), id); + + if (desiredTarget.isEmpty()) { + return OptionalDouble.empty(); + } + + return OptionalDouble.of( + desiredTarget.get().getPitch() + ); + } + + @Override + public OptionalDouble getTagYawByID(int id) { + if(latestResult == null) { + OptionalDouble.empty(); + } + + if (!latestResult.hasTargets()) { + return OptionalDouble.empty(); + } + + Optional desiredTarget = getTargetFromList(latestResult.getTargets(), id); + + if (desiredTarget.isEmpty()) { + return OptionalDouble.empty(); + } + + return OptionalDouble.of( + desiredTarget.get().getYaw() + ); + } + + private Optional getTargetFromList(List targets, int id) { + for (PhotonTrackedTarget target : targets) { + if (target.getFiducialId() == id) { + return Optional.of(target); + } + } + + return Optional.empty(); + } + + @Override + public int[] getVisibleTagIDs() { + if(latestResult == null) { + return new int[] {}; + } + + return latestResult.getTargets().stream().mapToInt(PhotonTrackedTarget::getFiducialId).toArray(); + } + +} diff --git a/src/main/java/frc/robot/utilities/SwerveModule.java b/src/main/java/frc/robot/utilities/SwerveModule.java new file mode 100644 index 0000000..77d40be --- /dev/null +++ b/src/main/java/frc/robot/utilities/SwerveModule.java @@ -0,0 +1,123 @@ +package frc.robot.utiltiies; + +import org.littletonrobotics.junction.Logger; + +import com.ctre.phoenix6.controls.VelocityVoltage; +import com.ctre.phoenix6.hardware.TalonFX; +import com.revrobotics.PersistMode; +import com.revrobotics.RelativeEncoder; +import com.revrobotics.ResetMode; +import com.revrobotics.spark.SparkClosedLoopController; +import com.revrobotics.spark.SparkMax; +import com.revrobotics.spark.SparkBase.ControlType; +import com.revrobotics.spark.SparkLowLevel.MotorType; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.kinematics.SwerveModulePosition; +import edu.wpi.first.math.kinematics.SwerveModuleState; +import edu.wpi.first.wpilibj.AnalogEncoder; +import frc.robot.constants.ModuleConstants; + +/* + * This thread + * + * https://www.chiefdelphi.com/t/best-easiest-way-to-connect-wire-and-program-thrifty-absolute-magnetic-encoder-to-rev-spark-max-motor-controller/439040/30 + * + * implies that the best use of the thrifty absolute encoder is to use it as a reference for the Spark relative encoder and then + * used the closed loop control on the controller for turning + * + * IDK if that's really necessary, the read rate of the analog ports is 100HZ, I suppose the only benefit is the higher rate of + * the controller closed loop controller. + */ +public class SwerveModule { + private TalonFX drive; + private SparkMax turning; + + private RelativeEncoder turningRelativeEncoder; + + private AnalogEncoder turningAbsoluteEncoder; + + private SparkClosedLoopController turningClosedLoopController; + + private VelocityVoltage driveVelocityRequest; + + private String moduleName; + + public SwerveModule(String moduleName, int drivingCANID, int turningCANID, int analogEncoderID, double analogEncoderOffset) { + drive = new TalonFX(drivingCANID); + turning = new SparkMax(turningCANID, MotorType.kBrushless); + + turningRelativeEncoder = turning.getEncoder(); + + turningAbsoluteEncoder = new AnalogEncoder(analogEncoderID, 2 * Math.PI, analogEncoderOffset); + + turningClosedLoopController = turning.getClosedLoopController(); + + drive.getConfigurator().apply(ModuleConstants.kDriveCurrentLimitConfig); + drive.getConfigurator().apply(ModuleConstants.kDriveFeedConfig); + drive.getConfigurator().apply(ModuleConstants.kDriveMotorConfig); + drive.getConfigurator().apply(ModuleConstants.kAudioConfig); + drive.getConfigurator().apply(ModuleConstants.kDriveSlot0Config); + + turning.configure( + ModuleConstants.turningConfig, + ResetMode.kResetSafeParameters, + PersistMode.kPersistParameters + ); + + turningRelativeEncoder.setPosition(turningAbsoluteEncoder.get()); + drive.setPosition(0); + + this.moduleName = "Drivetrain/Modules/" + moduleName; + } + + public void periodic() { + Logger.recordOutput(moduleName + "/AbsoluteEncoder/Position", turningAbsoluteEncoder.get()); + Logger.recordOutput(moduleName + "/SwerveModuleState", getState()); + Logger.recordOutput(moduleName + "/SwerveModulePosition", getPosition()); + } + + public SwerveModuleState getState() { + return new SwerveModuleState( + drive.getVelocity().getValueAsDouble() * ModuleConstants.kWheelCircumferenceMeters, + new Rotation2d(turningRelativeEncoder.getPosition()) + ); + } + + public SwerveModulePosition getPosition() { + return new SwerveModulePosition( + drive.getPosition().getValueAsDouble() * ModuleConstants.kWheelCircumferenceMeters, + new Rotation2d(turningRelativeEncoder.getPosition()) + ); + } + + public void setDesiredState(SwerveModuleState desiredState) { + // TODO is this really necessary, the offset is managed by the Absolute Encoder + // and its "source of truth" behavior in relation to the relative encoder + // Probably doesn't *hurt* that it's here, but it may not be needed + desiredState.optimize(new Rotation2d(turningRelativeEncoder.getPosition())); + + drive.setControl( + driveVelocityRequest.withVelocity( + desiredState.speedMetersPerSecond / ModuleConstants.kWheelCircumferenceMeters + ).withFeedForward( + desiredState.speedMetersPerSecond / ModuleConstants.kWheelCircumferenceMeters + ) + ); + + turningClosedLoopController.setSetpoint( + desiredState.angle.getRadians(), + ControlType.kPosition + ); + } + + public void resetEncoders() { + drive.setPosition(0); + + zeroTurningEncoder(); + } + + public void zeroTurningEncoder() { + turningRelativeEncoder.setPosition(turningAbsoluteEncoder.get()); + } +} diff --git a/vendordeps/AdvantageKit.json b/vendordeps/AdvantageKit.json new file mode 100644 index 0000000..162ad66 --- /dev/null +++ b/vendordeps/AdvantageKit.json @@ -0,0 +1,35 @@ +{ + "fileName": "AdvantageKit.json", + "name": "AdvantageKit", + "version": "26.0.0", + "uuid": "d820cc26-74e3-11ec-90d6-0242ac120003", + "frcYear": "2026", + "mavenUrls": [ + "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/" + ], + "jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json", + "javaDependencies": [ + { + "groupId": "org.littletonrobotics.akit", + "artifactId": "akit-java", + "version": "26.0.0" + } + ], + "jniDependencies": [ + { + "groupId": "org.littletonrobotics.akit", + "artifactId": "akit-wpilibio", + "version": "26.0.0", + "skipInvalidPlatforms": false, + "isJar": false, + "validPlatforms": [ + "linuxathena", + "linuxx86-64", + "linuxarm64", + "osxuniversal", + "windowsx86-64" + ] + } + ], + "cppDependencies": [] +} \ No newline at end of file diff --git a/vendordeps/PathplannerLib-2026.1.2.json b/vendordeps/PathplannerLib-2026.1.2.json new file mode 100644 index 0000000..f72fa41 --- /dev/null +++ b/vendordeps/PathplannerLib-2026.1.2.json @@ -0,0 +1,38 @@ +{ + "fileName": "PathplannerLib-2026.1.2.json", + "name": "PathplannerLib", + "version": "2026.1.2", + "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", + "frcYear": "2026", + "mavenUrls": [ + "https://3015rangerrobotics.github.io/pathplannerlib/repo" + ], + "jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json", + "javaDependencies": [ + { + "groupId": "com.pathplanner.lib", + "artifactId": "PathplannerLib-java", + "version": "2026.1.2" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "com.pathplanner.lib", + "artifactId": "PathplannerLib-cpp", + "version": "2026.1.2", + "libName": "PathplannerLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal", + "linuxathena", + "linuxarm32", + "linuxarm64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/Phoenix5-5.36.0.json b/vendordeps/Phoenix5-5.36.0.json new file mode 100644 index 0000000..9a27e47 --- /dev/null +++ b/vendordeps/Phoenix5-5.36.0.json @@ -0,0 +1,171 @@ +{ + "fileName": "Phoenix5-5.36.0.json", + "name": "CTRE-Phoenix (v5)", + "version": "5.36.0", + "frcYear": "2026", + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2026-latest.json", + "requires": [ + { + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.", + "offlineFileName": "Phoenix6-frc2026-latest.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json" + } + ], + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.", + "offlineFileName": "Phoenix6-replay-frc2026-latest.json" + }, + { + "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", + "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.", + "offlineFileName": "Phoenix5-replay-frc2026-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.36.0" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.36.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.36.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.36.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.36.0", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.36.0", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.36.0", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.36.0", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.36.0", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.36.0", + "libName": "CTRE_PhoenixCCISim", + "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/Phoenix6-26.1.0.json b/vendordeps/Phoenix6-26.1.0.json new file mode 100644 index 0000000..dc5dc62 --- /dev/null +++ b/vendordeps/Phoenix6-26.1.0.json @@ -0,0 +1,449 @@ +{ + "fileName": "Phoenix6-26.1.0.json", + "name": "CTRE-Phoenix (v6)", + "version": "26.1.0", + "frcYear": "2026", + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-latest.json", + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", + "offlineFileName": "Phoenix6-replay-frc2026-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "26.1.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "api-cpp", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "api-cpp-sim", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "26.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "26.1.0", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "26.1.0", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "26.1.0", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "26.1.0", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "26.1.0", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "26.1.0", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "26.1.0", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "26.1.0", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "26.1.0", + "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": "26.1.0", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "26.1.0", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "26.1.0", + "libName": "CTRE_SimProCANrange", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "26.1.0", + "libName": "CTRE_SimProCANdi", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "26.1.0", + "libName": "CTRE_SimProCANdle", + "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.json b/vendordeps/REVLib.json new file mode 100644 index 0000000..4f96af8 --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,133 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2026.0.0", + "frcYear": "2026", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2026.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2026.0.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2026.0.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibBackendDriver", + "version": "2026.0.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibWpiBackendDriver", + "version": "2026.0.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2026.0.0", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2026.0.0", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibBackendDriver", + "version": "2026.0.0", + "libName": "BackendDriver", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "RevLibWpiBackendDriver", + "version": "2026.0.0", + "libName": "REVLibWpi", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/Studica.json b/vendordeps/Studica.json new file mode 100644 index 0000000..b51bf58 --- /dev/null +++ b/vendordeps/Studica.json @@ -0,0 +1,71 @@ +{ + "fileName": "Studica.json", + "name": "Studica", + "version": "2026.0.0", + "frcYear": "2026", + "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "mavenUrls": [ + "https://dev.studica.com/maven/release/2026/" + ], + "jsonUrl": "https://dev.studica.com/maven/release/2026/json/Studica-2026.0.0.json", + "javaDependencies": [ + { + "groupId": "com.studica.frc", + "artifactId": "Studica-java", + "version": "2026.0.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.studica.frc", + "artifactId": "Studica-driver", + "version": "2026.0.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.studica.frc", + "artifactId": "Studica-cpp", + "version": "2026.0.0", + "libName": "Studica", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.studica.frc", + "artifactId": "Studica-driver", + "version": "2026.0.0", + "libName": "StudicaDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/photonlib.json b/vendordeps/photonlib.json new file mode 100644 index 0000000..7b78472 --- /dev/null +++ b/vendordeps/photonlib.json @@ -0,0 +1,71 @@ +{ + "fileName": "photonlib.json", + "name": "photonlib", + "version": "v2026.0.1-beta", + "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", + "frcYear": "2026", + "mavenUrls": [ + "https://maven.photonvision.org/repository/internal", + "https://maven.photonvision.org/repository/snapshots" + ], + "jsonUrl": "https://maven.photonvision.org/repository/internal/org/photonvision/photonlib-json/1.0/photonlib-json-1.0.json", + "jniDependencies": [ + { + "groupId": "org.photonvision", + "artifactId": "photontargeting-cpp", + "version": "v2026.0.1-beta", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "linuxathena", + "linuxx86-64", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "org.photonvision", + "artifactId": "photonlib-cpp", + "version": "v2026.0.1-beta", + "libName": "photonlib", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxathena", + "linuxx86-64", + "osxuniversal" + ] + }, + { + "groupId": "org.photonvision", + "artifactId": "photontargeting-cpp", + "version": "v2026.0.1-beta", + "libName": "photontargeting", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxathena", + "linuxx86-64", + "osxuniversal" + ] + } + ], + "javaDependencies": [ + { + "groupId": "org.photonvision", + "artifactId": "photonlib-java", + "version": "v2026.0.1-beta" + }, + { + "groupId": "org.photonvision", + "artifactId": "photontargeting-java", + "version": "v2026.0.1-beta" + } + ] +} \ No newline at end of file