From e5deec0a17fb501b3aa600ce3fd8e0a0522549dc Mon Sep 17 00:00:00 2001 From: Jonathan Dao Date: Sun, 5 Jan 2025 18:04:36 -0800 Subject: [PATCH] Merge 2024 Drivetrain Code Merge of 2024 Drivetrain code with 2025 Phoenix 6 library changes. TODO: Verify all swerve constants --- src/main/java/frc/robot/RobotContainer.java | 69 +++- src/main/java/frc/robot/constants/CAN.java | 22 + src/main/java/frc/robot/constants/SWERVE.java | 76 ++++ src/main/java/frc/robot/constants/USB.java | 9 + .../frc/robot/generated/TunerConstants.java | 326 +++++++++++++++ .../subsystems/CommandSwerveDrivetrain.java | 355 ++++++++++++++++ src/main/java/frc/robot/utils/Telemetry.java | 115 ++++++ vendordeps/PathplannerLib.json | 38 ++ vendordeps/Phoenix6-frc2025-latest.json | 389 ++++++++++++++++++ 9 files changed, 1385 insertions(+), 14 deletions(-) create mode 100644 src/main/java/frc/robot/constants/CAN.java create mode 100644 src/main/java/frc/robot/constants/SWERVE.java create mode 100644 src/main/java/frc/robot/constants/USB.java create mode 100644 src/main/java/frc/robot/generated/TunerConstants.java create mode 100644 src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java create mode 100644 src/main/java/frc/robot/utils/Telemetry.java create mode 100644 vendordeps/PathplannerLib.json create mode 100644 vendordeps/Phoenix6-frc2025-latest.json diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 0cff9b6..3105fcd 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -4,13 +4,19 @@ package frc.robot; +import static edu.wpi.first.units.Units.*; + +import com.ctre.phoenix6.swerve.SwerveRequest; +import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.WaitCommand; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.Trigger; -import frc.robot.Constants.OperatorConstants; -import frc.robot.commands.Autos; -import frc.robot.commands.ExampleCommand; -import frc.robot.subsystems.ExampleSubsystem; +import frc.robot.constants.SWERVE; +import frc.robot.constants.USB; +import frc.robot.generated.TunerConstants; +import frc.robot.subsystems.CommandSwerveDrivetrain; +import frc.robot.utils.Telemetry; /** * This class is where the bulk of the robot should be declared. Since Command-based is a @@ -20,18 +26,53 @@ */ public class RobotContainer { // The robot's subsystems and commands are defined here... - private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem(); + private final CommandSwerveDrivetrain m_swerveDrive = TunerConstants.createDrivetrain(); + private final Telemetry m_telemetry = new Telemetry(); // Replace with CommandPS4Controller or CommandJoystick if needed + private final Joystick leftJoystick = new Joystick(USB.leftJoystick); + private final Joystick rightJoystick = new Joystick(USB.rightJoystick); private final CommandXboxController m_driverController = - new CommandXboxController(OperatorConstants.kDriverControllerPort); + new CommandXboxController(USB.xBoxController); + + private double MaxSpeed = + TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed + private double MaxAngularRate = + RotationsPerSecond.of(SWERVE.kMaxRotationRadiansPerSecond) + .in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity + + /* Setting up bindings for necessary control of the swerve drive platform */ + private final SwerveRequest.FieldCentric drive = + new SwerveRequest.FieldCentric() + .withDeadband(MaxSpeed * 0.1) + .withRotationalDeadband(MaxAngularRate * 0.1); // Add a 10% deadband /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { + m_swerveDrive.registerTelemetry(m_telemetry::telemeterize); + // Configure the trigger bindings + initializeSubSystems(); configureBindings(); } + private void initializeSubSystems() { + m_swerveDrive.setDefaultCommand( + // Drivetrain will execute this command periodically + m_swerveDrive.applyRequest( + () -> + drive + .withVelocityX( + leftJoystick.getRawAxis(1) + * MaxSpeed) // Drive forward with negative Y (forward) + .withVelocityY( + leftJoystick.getRawAxis(0) * MaxSpeed) // Drive left with negative X (left) + .withRotationalRate( + rightJoystick.getRawAxis(0) + * MaxAngularRate) // Drive counterclockwise with negative X (left) + )); + } + /** * Use this method to define your trigger->command mappings. Triggers can be created via the * {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary @@ -42,13 +83,13 @@ public RobotContainer() { * joysticks}. */ private void configureBindings() { - // Schedule `ExampleCommand` when `exampleCondition` changes to `true` - new Trigger(m_exampleSubsystem::exampleCondition) - .onTrue(new ExampleCommand(m_exampleSubsystem)); - - // Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed, - // cancelling on release. - m_driverController.b().whileTrue(m_exampleSubsystem.exampleMethodCommand()); + // // Schedule `ExampleCommand` when `exampleCondition` changes to `true` + // new Trigger(m_exampleSubsystem::exampleCondition) + // .onTrue(new ExampleCommand(m_exampleSubsystem)); + // + // // Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed, + // // cancelling on release. + // m_driverController.b().whileTrue(m_exampleSubsystem.exampleMethodCommand()); } /** @@ -58,6 +99,6 @@ private void configureBindings() { */ public Command getAutonomousCommand() { // An example command will be run in autonomous - return Autos.exampleAuto(m_exampleSubsystem); + return new WaitCommand(0); } } diff --git a/src/main/java/frc/robot/constants/CAN.java b/src/main/java/frc/robot/constants/CAN.java new file mode 100644 index 0000000..128dd81 --- /dev/null +++ b/src/main/java/frc/robot/constants/CAN.java @@ -0,0 +1,22 @@ +package frc.robot.constants; + +public class CAN { + public static final String rioCanbus = "rio"; + public static String driveBaseCanbus = "drivebase"; + + public static final int pigeon = 9; + + public static final int frontLeftCanCoder = 10; + public static final int frontRightCanCoder = 11; + public static final int backLeftCanCoder = 12; + public static final int backRightCanCoder = 13; + + public static final int frontLeftDriveMotor = 20; + public static final int frontLeftTurnMotor = 21; + public static final int frontRightDriveMotor = 22; + public static final int frontRightTurnMotor = 23; + public static final int backLeftDriveMotor = 24; + public static final int backLeftTurnMotor = 25; + public static final int backRightDriveMotor = 26; + public static final int backRightTurnMotor = 27; +} diff --git a/src/main/java/frc/robot/constants/SWERVE.java b/src/main/java/frc/robot/constants/SWERVE.java new file mode 100644 index 0000000..3cebad4 --- /dev/null +++ b/src/main/java/frc/robot/constants/SWERVE.java @@ -0,0 +1,76 @@ +package frc.robot.constants; + +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.util.Units; + +public class SWERVE { + public static double kTrackWidth = Units.inchesToMeters(21); + public static final double kWheelBase = Units.inchesToMeters(19); + public static final double kDriveBaseRadius = + Math.sqrt(Math.pow(kTrackWidth / 2.0, 2) + Math.pow(kWheelBase / 2.0, 2)); + + // TODO: Reimplement/add to team library + // public static final Map kModuleTranslations = + // Map.of( + // MODULE_POSITION.FRONT_LEFT, + // new Translation2d(kWheelBase / 2.0, kTrackWidth / 2.0), + // MODULE_POSITION.FRONT_RIGHT, + // new Translation2d(kWheelBase / 2.0, -kTrackWidth / 2.0), + // MODULE_POSITION.BACK_LEFT, + // new Translation2d(-kWheelBase / 2.0, kTrackWidth / 2.0), + // MODULE_POSITION.BACK_RIGHT, + // new Translation2d(-kWheelBase / 2.0, -kTrackWidth / 2.0)); + // + // public static final SwerveDriveKinematics kSwerveKinematics = + // new SwerveDriveKinematics( + // ModuleMap.orderedValues(kModuleTranslations, new Translation2d[0])); + public static final Translation2d kFrontLeftPosition = + new Translation2d(kWheelBase / 2.0, kTrackWidth / 2.0); + public static final Translation2d kFrontRightPosition = + new Translation2d(kWheelBase / 2.0, -kTrackWidth / 2.0); + public static final Translation2d kBackLeftPosition = + new Translation2d(-kWheelBase / 2.0, kTrackWidth / 2.0); + public static final Translation2d kBackRightPosition = + new Translation2d(-kWheelBase / 2.0, -kTrackWidth / 2.0); + + public static final double kMaxSpeedMetersPerSecond = Units.feetToMeters(18); + public static final double kMaxRotationRadiansPerSecond = Math.PI * 2.0; + + // TODO: Verify values + public static final double kDriveMotorGearRatio = 6.12; + public static final double kTurnMotorGearRatio = 150.0 / 7.0; + public static final double kCoupleRatio = 3.5714285714285716; // TODO: Verify + public static final double kWheelRadiusInches = 1.95; + public static final double kWheelDiameterMeters = 2.0 * Units.inchesToMeters(kWheelRadiusInches); + + public static final boolean[] kTurnInversions = {true, false, false, false}; + public static final boolean[] kDriveInversions = {false, false, false, true}; + + // In rotations + public static double kFrontLeftEncoderOffset = 0.219970703125; + public static double kFrontRightEncoderOffset = 0.265380859375; + public static double kBackLeftEncoderOffset = -0.046875; + public static double kBackRightEncoderOffset = 0.328125; + + public static double kTurnKP = 100; + public static double kTurnKI = 0; + public static double kTurnKD = 0.5; + public static double kTurnKS = 0.1; + public static double kTurnKV = 1.91; + public static double kTurnKA = 0; + + public static double kDriveKP = 0.1; + public static double kDriveKI = 0; + public static double kDriveKD = 0; + public static double kDriveKS = 0; + public static double kDriveKV = 0.124; + public static double kDriveKA = 0; + + public static final double kTurnSatorCurrentLimit = 60; + + public static final double kSlipCurrent = 120.0; + public static final double kDriveInertia = 0.01; + public static final double kTurnInertia = 0.01; + public static final double kDriveFrictionVoltage = 0.2; + public static final double kTurnFrictionVoltage = 0.2; +} diff --git a/src/main/java/frc/robot/constants/USB.java b/src/main/java/frc/robot/constants/USB.java new file mode 100644 index 0000000..1d8d7c7 --- /dev/null +++ b/src/main/java/frc/robot/constants/USB.java @@ -0,0 +1,9 @@ +package frc.robot.constants; + +public final class USB { + public static final int leftJoystick = 0; + public static final int rightJoystick = 1; + public static final int xBoxController = 2; + + public static final int testController = 3; +} diff --git a/src/main/java/frc/robot/generated/TunerConstants.java b/src/main/java/frc/robot/generated/TunerConstants.java new file mode 100644 index 0000000..ade87fc --- /dev/null +++ b/src/main/java/frc/robot/generated/TunerConstants.java @@ -0,0 +1,326 @@ +package frc.robot.generated; + +import static edu.wpi.first.units.Units.*; + +import com.ctre.phoenix6.CANBus; +import com.ctre.phoenix6.configs.*; +import com.ctre.phoenix6.hardware.*; +import com.ctre.phoenix6.signals.*; +import com.ctre.phoenix6.swerve.*; +import com.ctre.phoenix6.swerve.SwerveModuleConstants.*; +import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.math.numbers.N3; +import edu.wpi.first.units.measure.*; +import frc.robot.constants.CAN; +import frc.robot.constants.SWERVE; +import frc.robot.subsystems.CommandSwerveDrivetrain; + +// Generated by the Tuner X Swerve Project Generator +// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html +public class TunerConstants { + // Both sets of gains need to be tuned to your individual robot. + + // The steer motor uses any SwerveModule.SteerRequestType control request with the + // output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput + private static final Slot0Configs steerGains = + new Slot0Configs() + .withKP(SWERVE.kTurnKP) + .withKI(SWERVE.kTurnKI) + .withKD(SWERVE.kTurnKD) + .withKS(SWERVE.kTurnKS) + .withKV(SWERVE.kTurnKV) + .withKA(SWERVE.kTurnKA) + .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign); + // When using closed-loop control, the drive motor uses the control + // output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput + private static final Slot0Configs driveGains = + new Slot0Configs() + .withKP(SWERVE.kDriveKP) + .withKI(SWERVE.kDriveKI) + .withKD(SWERVE.kDriveKD) + .withKS(SWERVE.kDriveKS) + .withKV(SWERVE.kDriveKV) + .withKA(SWERVE.kDriveKA); + + // The closed-loop output type to use for the steer motors; + // This affects the PID/FF gains for the steer motors + private static final ClosedLoopOutputType kSteerClosedLoopOutput = ClosedLoopOutputType.Voltage; + // The closed-loop output type to use for the drive motors; + // This affects the PID/FF gains for the drive motors + private static final ClosedLoopOutputType kDriveClosedLoopOutput = ClosedLoopOutputType.Voltage; + + // The type of motor used for the drive motor + private static final DriveMotorArrangement kDriveMotorType = + DriveMotorArrangement.TalonFX_Integrated; + // The type of motor used for the drive motor + private static final SteerMotorArrangement kSteerMotorType = + SteerMotorArrangement.TalonFX_Integrated; + + // The remote sensor feedback type to use for the steer motors; + // When not Pro-licensed, FusedCANcoder/SyncCANcoder automatically fall back to RemoteCANcoder + private static final SteerFeedbackType kSteerFeedbackType = SteerFeedbackType.FusedCANcoder; + + // The stator current at which the wheels start to slip; + // This needs to be tuned to your individual robot + private static final Current kSlipCurrent = Amps.of(SWERVE.kSlipCurrent); + + // Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null. + // Some configs will be overwritten; check the `with*InitialConfigs()` API documentation. + private static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration(); + private static final TalonFXConfiguration steerInitialConfigs = + new TalonFXConfiguration() + .withCurrentLimits( + new CurrentLimitsConfigs() + // Swerve azimuth does not require much torque output, so we can set a relatively + // low + // stator current limit to help avoid brownouts without impacting performance. + .withStatorCurrentLimit(Amps.of(SWERVE.kTurnSatorCurrentLimit)) + .withStatorCurrentLimitEnable(true)); + private static final CANcoderConfiguration encoderInitialConfigs = new CANcoderConfiguration(); + // Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs + private static final Pigeon2Configuration pigeonConfigs = null; + + // CAN bus that the devices are located on; + // All swerve devices must share the same CAN bus + public static final CANBus kCANBus = new CANBus(CAN.driveBaseCanbus, "./logs/example.hoot"); + + // Theoretical free speed (m/s) at 12 V applied output; + // This needs to be tuned to your individual robot + public static final LinearVelocity kSpeedAt12Volts = + MetersPerSecond.of(SWERVE.kMaxSpeedMetersPerSecond); + + // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns; + // This may need to be tuned to your individual robot + private static final double kCoupleRatio = SWERVE.kCoupleRatio; + + private static final double kDriveGearRatio = SWERVE.kDriveMotorGearRatio; + private static final double kSteerGearRatio = SWERVE.kTurnMotorGearRatio; + private static final Distance kWheelRadius = Inches.of(SWERVE.kWheelRadiusInches); + + private static final int kPigeonId = CAN.pigeon; + + // These are only used for simulation + private static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(SWERVE.kTurnInertia); + private static final MomentOfInertia kDriveInertia = + KilogramSquareMeters.of(SWERVE.kDriveInertia); + // Simulated voltage necessary to overcome friction + private static final Voltage kSteerFrictionVoltage = Volts.of(SWERVE.kTurnFrictionVoltage); + private static final Voltage kDriveFrictionVoltage = Volts.of(SWERVE.kDriveFrictionVoltage); + + public static final SwerveDrivetrainConstants DrivetrainConstants = + new SwerveDrivetrainConstants() + .withCANBusName(kCANBus.getName()) + .withPigeon2Id(kPigeonId) + .withPigeon2Configs(pigeonConfigs); + + private static final SwerveModuleConstantsFactory< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + ConstantCreator = + new SwerveModuleConstantsFactory< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>() + .withDriveMotorGearRatio(kDriveGearRatio) + .withSteerMotorGearRatio(kSteerGearRatio) + .withCouplingGearRatio(kCoupleRatio) + .withWheelRadius(kWheelRadius) + .withSteerMotorGains(steerGains) + .withDriveMotorGains(driveGains) + .withSteerMotorClosedLoopOutput(kSteerClosedLoopOutput) + .withDriveMotorClosedLoopOutput(kDriveClosedLoopOutput) + .withSlipCurrent(kSlipCurrent) + .withSpeedAt12Volts(kSpeedAt12Volts) + .withDriveMotorType(kDriveMotorType) + .withSteerMotorType(kSteerMotorType) + .withFeedbackSource(kSteerFeedbackType) + .withDriveMotorInitialConfigs(driveInitialConfigs) + .withSteerMotorInitialConfigs(steerInitialConfigs) + .withEncoderInitialConfigs(encoderInitialConfigs) + .withSteerInertia(kSteerInertia) + .withDriveInertia(kDriveInertia) + .withSteerFrictionVoltage(kSteerFrictionVoltage) + .withDriveFrictionVoltage(kDriveFrictionVoltage); + + // Front Left + private static final int kFrontLeftDriveMotorId = CAN.frontLeftDriveMotor; + private static final int kFrontLeftSteerMotorId = CAN.frontLeftTurnMotor; + private static final int kFrontLeftEncoderId = CAN.frontLeftCanCoder; + private static final Angle kFrontLeftEncoderOffset = Rotations.of(SWERVE.kFrontLeftEncoderOffset); + private static final boolean kFrontLeftSteerMotorInverted = SWERVE.kTurnInversions[0]; + private static final boolean kFrontLeftDriveMotorInverted = SWERVE.kDriveInversions[0]; + private static final boolean kFrontLeftEncoderInverted = false; + + private static final Distance kFrontLeftXPos = Inches.of(SWERVE.kFrontLeftPosition.getX()); + private static final Distance kFrontLeftYPos = Inches.of(SWERVE.kFrontLeftPosition.getY()); + + // Front Right + private static final int kFrontRightDriveMotorId = CAN.frontRightDriveMotor; + private static final int kFrontRightSteerMotorId = CAN.frontRightTurnMotor; + private static final int kFrontRightEncoderId = CAN.frontRightCanCoder; + private static final Angle kFrontRightEncoderOffset = + Rotations.of(SWERVE.kFrontRightEncoderOffset); + private static final boolean kFrontRightSteerMotorInverted = SWERVE.kTurnInversions[1]; + private static final boolean kFrontRightDriveMotorInverted = SWERVE.kDriveInversions[1]; + private static final boolean kFrontRightEncoderInverted = false; + + private static final Distance kFrontRightXPos = Inches.of(SWERVE.kFrontRightPosition.getX()); + private static final Distance kFrontRightYPos = Inches.of(SWERVE.kFrontRightPosition.getY()); + + // Back Left + private static final int kBackLeftDriveMotorId = CAN.backLeftDriveMotor; + private static final int kBackLeftSteerMotorId = CAN.backLeftTurnMotor; + private static final int kBackLeftEncoderId = CAN.backLeftCanCoder; + private static final Angle kBackLeftEncoderOffset = Rotations.of(SWERVE.kBackLeftEncoderOffset); + private static final boolean kBackLeftSteerMotorInverted = SWERVE.kTurnInversions[2]; + private static final boolean kBackLeftDriveMotorInverted = SWERVE.kDriveInversions[2]; + private static final boolean kBackLeftEncoderInverted = false; + + private static final Distance kBackLeftXPos = Inches.of(SWERVE.kBackLeftPosition.getX()); + private static final Distance kBackLeftYPos = Inches.of(SWERVE.kBackLeftPosition.getY()); + + // Back Right + private static final int kBackRightDriveMotorId = CAN.backRightDriveMotor; + private static final int kBackRightSteerMotorId = CAN.backRightTurnMotor; + private static final int kBackRightEncoderId = CAN.backRightCanCoder; + private static final Angle kBackRightEncoderOffset = Rotations.of(SWERVE.kBackRightEncoderOffset); + private static final boolean kBackRightSteerMotorInverted = SWERVE.kTurnInversions[3]; + private static final boolean kBackRightDriveMotorInverted = SWERVE.kDriveInversions[3]; + private static final boolean kBackRightEncoderInverted = false; + + private static final Distance kBackRightXPos = Inches.of(SWERVE.kBackRightPosition.getX()); + private static final Distance kBackRightYPos = Inches.of(SWERVE.kBackRightPosition.getY()); + + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + FrontLeft = + ConstantCreator.createModuleConstants( + kFrontLeftSteerMotorId, + kFrontLeftDriveMotorId, + kFrontLeftEncoderId, + kFrontLeftEncoderOffset, + kFrontLeftXPos, + kFrontLeftYPos, + kFrontLeftDriveMotorInverted, + kFrontLeftSteerMotorInverted, + kFrontLeftEncoderInverted); + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + FrontRight = + ConstantCreator.createModuleConstants( + kFrontRightSteerMotorId, + kFrontRightDriveMotorId, + kFrontRightEncoderId, + kFrontRightEncoderOffset, + kFrontRightXPos, + kFrontRightYPos, + kFrontRightDriveMotorInverted, + kFrontRightSteerMotorInverted, + kFrontRightEncoderInverted); + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + BackLeft = + ConstantCreator.createModuleConstants( + kBackLeftSteerMotorId, + kBackLeftDriveMotorId, + kBackLeftEncoderId, + kBackLeftEncoderOffset, + kBackLeftXPos, + kBackLeftYPos, + kBackLeftDriveMotorInverted, + kBackLeftSteerMotorInverted, + kBackLeftEncoderInverted); + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + BackRight = + ConstantCreator.createModuleConstants( + kBackRightSteerMotorId, + kBackRightDriveMotorId, + kBackRightEncoderId, + kBackRightEncoderOffset, + kBackRightXPos, + kBackRightYPos, + kBackRightDriveMotorInverted, + kBackRightSteerMotorInverted, + kBackRightEncoderInverted); + + /** + * Creates a CommandSwerveDrivetrain instance. This should only be called once in your robot + * program,. + */ + public static CommandSwerveDrivetrain createDrivetrain() { + return new CommandSwerveDrivetrain( + DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight); + } + + /** Swerve Drive class utilizing CTR Electronics' Phoenix 6 API with the selected device types. */ + public static class TunerSwerveDrivetrain extends SwerveDrivetrain { + /** + * Constructs a CTRE SwerveDrivetrain using the specified constants. + * + *

This constructs the underlying hardware devices, so users should not construct the devices + * themselves. If they need the devices, they can access them through getters in the classes. + * + * @param drivetrainConstants Drivetrain-wide constants for the swerve drive + * @param modules Constants for each specific module + */ + public TunerSwerveDrivetrain( + SwerveDrivetrainConstants drivetrainConstants, SwerveModuleConstants... modules) { + super(TalonFX::new, TalonFX::new, CANcoder::new, drivetrainConstants, modules); + } + + /** + * Constructs a CTRE SwerveDrivetrain using the specified constants. + * + *

This constructs the underlying hardware devices, so users should not construct the devices + * themselves. If they need the devices, they can access them through getters in the classes. + * + * @param drivetrainConstants Drivetrain-wide constants for the swerve drive + * @param odometryUpdateFrequency The frequency to run the odometry loop. If unspecified or set + * to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0. + * @param modules Constants for each specific module + */ + public TunerSwerveDrivetrain( + SwerveDrivetrainConstants drivetrainConstants, + double odometryUpdateFrequency, + SwerveModuleConstants... modules) { + super( + TalonFX::new, + TalonFX::new, + CANcoder::new, + drivetrainConstants, + odometryUpdateFrequency, + modules); + } + + /** + * Constructs a CTRE SwerveDrivetrain using the specified constants. + * + *

This constructs the underlying hardware devices, so users should not construct the devices + * themselves. If they need the devices, they can access them through getters in the classes. + * + * @param drivetrainConstants Drivetrain-wide constants for the swerve drive + * @param odometryUpdateFrequency The frequency to run the odometry loop. If unspecified or set + * to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0. + * @param odometryStandardDeviation The standard deviation for odometry calculation in the form + * [x, y, theta]ᵀ, with units in meters and radians + * @param visionStandardDeviation The standard deviation for vision calculation in the form [x, + * y, theta]ᵀ, with units in meters and radians + * @param modules Constants for each specific module + */ + public TunerSwerveDrivetrain( + SwerveDrivetrainConstants drivetrainConstants, + double odometryUpdateFrequency, + Matrix odometryStandardDeviation, + Matrix visionStandardDeviation, + SwerveModuleConstants... modules) { + super( + TalonFX::new, + TalonFX::new, + CANcoder::new, + drivetrainConstants, + odometryUpdateFrequency, + odometryStandardDeviation, + visionStandardDeviation, + modules); + } + } +} diff --git a/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java new file mode 100644 index 0000000..e52292d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java @@ -0,0 +1,355 @@ +package frc.robot.subsystems; + +import static edu.wpi.first.units.Units.*; + +import com.ctre.phoenix6.SignalLogger; +import com.ctre.phoenix6.Utils; +import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants; +import com.ctre.phoenix6.swerve.SwerveModuleConstants; +import com.ctre.phoenix6.swerve.SwerveRequest; +import com.pathplanner.lib.auto.AutoBuilder; +import com.pathplanner.lib.config.PIDConstants; +import com.pathplanner.lib.config.RobotConfig; +import com.pathplanner.lib.controllers.PPHolonomicDriveController; +import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Twist2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.math.numbers.N3; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.DriverStation.Alliance; +import edu.wpi.first.wpilibj.Notifier; +import edu.wpi.first.wpilibj.RobotController; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Subsystem; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; +import frc.robot.generated.TunerConstants.TunerSwerveDrivetrain; +import java.util.function.Supplier; + +/** + * Class that extends the Phoenix 6 SwerveDrivetrain class and implements Subsystem so it can easily + * be used in command-based projects. + */ +public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Subsystem { + private static final double kSimLoopPeriod = 0.005; // 5 ms + private Notifier m_simNotifier = null; + private double m_lastSimTime; + + /* Blue alliance sees forward as 0 degrees (toward red alliance wall) */ + private static final Rotation2d kBlueAlliancePerspectiveRotation = Rotation2d.kZero; + /* Red alliance sees forward as 180 degrees (toward blue alliance wall) */ + private static final Rotation2d kRedAlliancePerspectiveRotation = Rotation2d.k180deg; + /* Keep track if we've ever applied the operator perspective before or not */ + private boolean m_hasAppliedOperatorPerspective = false; + + // driving in open loop + private Pose2d m_futurePose = new Pose2d(); + private Twist2d m_twistFromPose = new Twist2d(); + private ChassisSpeeds m_newChassisSpeeds = new ChassisSpeeds(); + + /** Swerve request to apply during robot-centric path following */ + private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = + new SwerveRequest.ApplyRobotSpeeds(); + + /* Swerve requests to apply during SysId characterization */ + private final SwerveRequest.SysIdSwerveTranslation m_translationCharacterization = + new SwerveRequest.SysIdSwerveTranslation(); + private final SwerveRequest.SysIdSwerveSteerGains m_steerCharacterization = + new SwerveRequest.SysIdSwerveSteerGains(); + private final SwerveRequest.SysIdSwerveRotation m_rotationCharacterization = + new SwerveRequest.SysIdSwerveRotation(); + + /* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */ + private final SysIdRoutine m_sysIdRoutineTranslation = + new SysIdRoutine( + new SysIdRoutine.Config( + null, // Use default ramp rate (1 V/s) + Volts.of(4), // Reduce dynamic step voltage to 4 V to prevent brownout + null, // Use default timeout (10 s) + // Log state with SignalLogger class + state -> SignalLogger.writeString("SysIdTranslation_State", state.toString())), + new SysIdRoutine.Mechanism( + output -> setControl(m_translationCharacterization.withVolts(output)), null, this)); + + /* SysId routine for characterizing steer. This is used to find PID gains for the steer motors. */ + private final SysIdRoutine m_sysIdRoutineSteer = + new SysIdRoutine( + new SysIdRoutine.Config( + null, // Use default ramp rate (1 V/s) + Volts.of(7), // Use dynamic voltage of 7 V + null, // Use default timeout (10 s) + // Log state with SignalLogger class + state -> SignalLogger.writeString("SysIdSteer_State", state.toString())), + new SysIdRoutine.Mechanism( + volts -> setControl(m_steerCharacterization.withVolts(volts)), null, this)); + + /* + * SysId routine for characterizing rotation. + * This is used to find PID gains for the FieldCentricFacingAngle HeadingController. + * See the documentation of SwerveRequest.SysIdSwerveRotation for info on importing the log to SysId. + */ + private final SysIdRoutine m_sysIdRoutineRotation = + new SysIdRoutine( + new SysIdRoutine.Config( + /* This is in radians per second², but SysId only supports "volts per second" */ + Volts.of(Math.PI / 6).per(Second), + /* This is in radians per second, but SysId only supports "volts" */ + Volts.of(Math.PI), + null, // Use default timeout (10 s) + // Log state with SignalLogger class + state -> SignalLogger.writeString("SysIdRotation_State", state.toString())), + new SysIdRoutine.Mechanism( + output -> { + /* output is actually radians per second, but SysId only supports "volts" */ + setControl(m_rotationCharacterization.withRotationalRate(output.in(Volts))); + /* also log the requested output for SysId */ + SignalLogger.writeDouble("Rotational_Rate", output.in(Volts)); + }, + null, + this)); + + /* The SysId routine to test */ + private SysIdRoutine m_sysIdRoutineToApply = m_sysIdRoutineTranslation; + + /** + * Constructs a CTRE SwerveDrivetrain using the specified constants. + * + *

This constructs the underlying hardware devices, so users should not construct the devices + * themselves. If they need the devices, they can access them through getters in the classes. + * + * @param drivetrainConstants Drivetrain-wide constants for the swerve drive + * @param modules Constants for each specific module + */ + public CommandSwerveDrivetrain( + SwerveDrivetrainConstants drivetrainConstants, SwerveModuleConstants... modules) { + super(drivetrainConstants, modules); + if (Utils.isSimulation()) { + startSimThread(); + } + configureAutoBuilder(); + } + + /** + * Constructs a CTRE SwerveDrivetrain using the specified constants. + * + *

This constructs the underlying hardware devices, so users should not construct the devices + * themselves. If they need the devices, they can access them through getters in the classes. + * + * @param drivetrainConstants Drivetrain-wide constants for the swerve drive + * @param odometryUpdateFrequency The frequency to run the odometry loop. If unspecified or set to + * 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0. + * @param modules Constants for each specific module + */ + public CommandSwerveDrivetrain( + SwerveDrivetrainConstants drivetrainConstants, + double odometryUpdateFrequency, + SwerveModuleConstants... modules) { + super(drivetrainConstants, odometryUpdateFrequency, modules); + if (Utils.isSimulation()) { + startSimThread(); + } + configureAutoBuilder(); + } + + /** + * Constructs a CTRE SwerveDrivetrain using the specified constants. + * + *

This constructs the underlying hardware devices, so users should not construct the devices + * themselves. If they need the devices, they can access them through getters in the classes. + * + * @param drivetrainConstants Drivetrain-wide constants for the swerve drive + * @param odometryUpdateFrequency The frequency to run the odometry loop. If unspecified or set to + * 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0. + * @param odometryStandardDeviation The standard deviation for odometry calculation in the form + * [x, y, theta]ᵀ, with units in meters and radians + * @param visionStandardDeviation The standard deviation for vision calculation in the form [x, y, + * theta]ᵀ, with units in meters and radians + * @param modules Constants for each specific module + */ + public CommandSwerveDrivetrain( + SwerveDrivetrainConstants drivetrainConstants, + double odometryUpdateFrequency, + Matrix odometryStandardDeviation, + Matrix visionStandardDeviation, + SwerveModuleConstants... modules) { + super( + drivetrainConstants, + odometryUpdateFrequency, + odometryStandardDeviation, + visionStandardDeviation, + modules); + if (Utils.isSimulation()) { + startSimThread(); + } + configureAutoBuilder(); + } + + // TODO: Re-implement + // public Command applyChassisSpeeds(Supplier chassisSpeeds) { + // return applyChassisSpeeds(chassisSpeeds, 0.02, 1.0, false); + // } + + /** + * Second-Order Kinematics ... + */ + // TODO: Re-implement + // public Command applyChassisSpeeds( + // Supplier chassisSpeeds, + // double loopPeriod, + // double driftRate, + // boolean isRobotCentric) { + // return applyRequest( + // () -> { + // m_futurePose = + // new Pose2d( + // chassisSpeeds.get().vxMetersPerSecond * loopPeriod, + // chassisSpeeds.get().vyMetersPerSecond * loopPeriod, + // Rotation2d.fromRadians( + // chassisSpeeds.get().omegaRadiansPerSecond * loopPeriod * + // driftRate)); + // + // m_twistFromPose = new Pose2d().log(m_futurePose); + // + // var rotationSpeed = chassisSpeeds.get().omegaRadiansPerSecond; + // if (m_trackingState != VISION.TRACKING_STATE.NONE) { + // if (m_trackingState == VISION.TRACKING_STATE.NOTE) { + // if (m_vision != null) { + // if (m_vision.hasGamePieceTarget()) { + // rotationSpeed = calculateRotationToTarget(); + // } + // } + // } else if (m_trackingState == VISION.TRACKING_STATE.SPEAKER) { + // rotationSpeed = calculateRotationToTarget(); + // } + // } + // + // m_newChassisSpeeds = + // new ChassisSpeeds( + // m_twistFromPose.dx / loopPeriod, m_twistFromPose.dy / loopPeriod, + // rotationSpeed); + // + // if (isRobotCentric) { + // return m_driveReqeustRobotCentric + // .withVelocityX(m_newChassisSpeeds.vxMetersPerSecond) + // .withVelocityY(m_newChassisSpeeds.vyMetersPerSecond) + // .withRotationalRate(m_newChassisSpeeds.omegaRadiansPerSecond); + // } else { + // if (Controls.isRedAlliance()) { + // return m_driveReqeustFieldCentric + // .withVelocityX(-m_newChassisSpeeds.vxMetersPerSecond) + // .withVelocityY(-m_newChassisSpeeds.vyMetersPerSecond) + // .withRotationalRate(m_newChassisSpeeds.omegaRadiansPerSecond); + // } else { + // return m_driveReqeustFieldCentric + // .withVelocityX(m_newChassisSpeeds.vxMetersPerSecond) + // .withVelocityY(m_newChassisSpeeds.vyMetersPerSecond) + // .withRotationalRate(m_newChassisSpeeds.omegaRadiansPerSecond); + // } + // } + // }); + // } + + private void configureAutoBuilder() { + try { + var config = RobotConfig.fromGUISettings(); + AutoBuilder.configure( + () -> getState().Pose, // Supplier of current robot pose + this::resetPose, // Consumer for seeding pose against auto + () -> getState().Speeds, // Supplier of current robot speeds + // Consumer of ChassisSpeeds and feedforwards to drive the robot + (speeds, feedforwards) -> + setControl( + m_pathApplyRobotSpeeds + .withSpeeds(speeds) + .withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesXNewtons()) + .withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesYNewtons())), + new PPHolonomicDriveController( + // PID constants for translation + new PIDConstants(10, 0, 0), + // PID constants for rotation + new PIDConstants(7, 0, 0)), + config, + // Assume the path needs to be flipped for Red vs Blue, this is normally the case + () -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red, + this // Subsystem for requirements + ); + } catch (Exception ex) { + DriverStation.reportError( + "Failed to load PathPlanner config and configure AutoBuilder", ex.getStackTrace()); + } + } + + /** + * Returns a command that applies the specified control request to this swerve drivetrain. + * + * @param requestSupplier Function returning the request to apply + * @return Command to run + */ + public Command applyRequest(Supplier requestSupplier) { + return run(() -> this.setControl(requestSupplier.get())); + } + + /** + * Runs the SysId Quasistatic test in the given direction for the routine specified by {@link + * #m_sysIdRoutineToApply}. + * + * @param direction Direction of the SysId Quasistatic test + * @return Command to run + */ + public Command sysIdQuasistatic(SysIdRoutine.Direction direction) { + return m_sysIdRoutineToApply.quasistatic(direction); + } + + /** + * Runs the SysId Dynamic test in the given direction for the routine specified by {@link + * #m_sysIdRoutineToApply}. + * + * @param direction Direction of the SysId Dynamic test + * @return Command to run + */ + public Command sysIdDynamic(SysIdRoutine.Direction direction) { + return m_sysIdRoutineToApply.dynamic(direction); + } + + @Override + public void periodic() { + /* + * Periodically try to apply the operator perspective. + * If we haven't applied the operator perspective before, then we should apply it regardless of DS state. + * This allows us to correct the perspective in case the robot code restarts mid-match. + * Otherwise, only check and apply the operator perspective if the DS is disabled. + * This ensures driving behavior doesn't change until an explicit disable event occurs during testing. + */ + if (!m_hasAppliedOperatorPerspective || DriverStation.isDisabled()) { + DriverStation.getAlliance() + .ifPresent( + allianceColor -> { + setOperatorPerspectiveForward( + allianceColor == Alliance.Red + ? kRedAlliancePerspectiveRotation + : kBlueAlliancePerspectiveRotation); + m_hasAppliedOperatorPerspective = true; + }); + } + } + + private void startSimThread() { + m_lastSimTime = Utils.getCurrentTimeSeconds(); + + /* Run simulation at a faster rate so PID gains behave more reasonably */ + m_simNotifier = + new Notifier( + () -> { + final double currentTime = Utils.getCurrentTimeSeconds(); + double deltaTime = currentTime - m_lastSimTime; + m_lastSimTime = currentTime; + + /* use the measured time delta, get battery voltage from WPILib */ + updateSimState(deltaTime, RobotController.getBatteryVoltage()); + }); + m_simNotifier.startPeriodic(kSimLoopPeriod); + } +} diff --git a/src/main/java/frc/robot/utils/Telemetry.java b/src/main/java/frc/robot/utils/Telemetry.java new file mode 100644 index 0000000..7be8870 --- /dev/null +++ b/src/main/java/frc/robot/utils/Telemetry.java @@ -0,0 +1,115 @@ +package frc.robot.utils; + +import com.ctre.phoenix6.SignalLogger; +import com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveDriveState; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Transform2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.math.kinematics.SwerveModulePosition; +import edu.wpi.first.math.kinematics.SwerveModuleState; +import edu.wpi.first.networktables.*; +import frc.robot.constants.SWERVE; + +public class Telemetry { + private final double m_maxSpeed = SWERVE.kMaxSpeedMetersPerSecond; + + // TODO: Re-implement + // private FieldSim m_fieldSim; + // private final SwerveModuleVisualizer[] m_moduleVisualizer = { + // new SwerveModuleVisualizer(ModuleMap.MODULE_POSITION.FRONT_LEFT.name(), m_maxSpeed), + // new SwerveModuleVisualizer(ModuleMap.MODULE_POSITION.FRONT_RIGHT.name(), + // m_maxSpeed), + // new SwerveModuleVisualizer(ModuleMap.MODULE_POSITION.BACK_LEFT.name(), m_maxSpeed), + // new SwerveModuleVisualizer(ModuleMap.MODULE_POSITION.BACK_RIGHT.name(), m_maxSpeed) + // }; + + private final Pose2d[] m_swerveModulePoses = { + new Pose2d(), new Pose2d(), new Pose2d(), new Pose2d(), + }; + private final Transform2d[] m_moduleTransforms = new Transform2d[4]; + private final double[] m_moduleAngles = new double[4]; + + /* What to publish over networktables for telemetry */ + private final NetworkTableInstance inst = NetworkTableInstance.getDefault(); + + /* Robot swerve drive state */ + private final NetworkTable driveStateTable = inst.getTable("DriveState"); + private final StructPublisher drivePose = + driveStateTable.getStructTopic("Pose", Pose2d.struct).publish(); + private final StructPublisher driveSpeeds = + driveStateTable.getStructTopic("Speeds", ChassisSpeeds.struct).publish(); + private final StructArrayPublisher driveModuleStates = + driveStateTable.getStructArrayTopic("ModuleStates", SwerveModuleState.struct).publish(); + private final StructArrayPublisher driveModuleTargets = + driveStateTable.getStructArrayTopic("ModuleTargets", SwerveModuleState.struct).publish(); + private final StructArrayPublisher driveModulePositions = + driveStateTable.getStructArrayTopic("ModulePositions", SwerveModulePosition.struct).publish(); + private final DoublePublisher driveTimestamp = + driveStateTable.getDoubleTopic("Timestamp").publish(); + private final DoublePublisher driveOdometryFrequency = + driveStateTable.getDoubleTopic("OdometryFrequency").publish(); + + /* Robot pose for field positioning */ + private final NetworkTable table = inst.getTable("Pose"); + private final DoubleArrayPublisher fieldPub = table.getDoubleArrayTopic("robotPose").publish(); + private final StringPublisher fieldTypePub = table.getStringTopic(".type").publish(); + + private final double[] m_poseArray = new double[3]; + private final double[] m_moduleStatesArray = new double[8]; + private final double[] m_moduleTargetsArray = new double[8]; + + /** Construct a telemetry object */ + public Telemetry() {} + + // public void registerFieldSim(FieldSim fieldSim) { + // m_fieldSim = fieldSim; + // } + + /* Accept the swerve drive state and telemeterize it to SmartDashboard */ + public void telemeterize(SwerveDriveState state) { + /* Telemeterize the swerve drive state */ + drivePose.set(state.Pose); + driveSpeeds.set(state.Speeds); + driveModuleStates.set(state.ModuleStates); + driveModuleTargets.set(state.ModuleTargets); + driveModulePositions.set(state.ModulePositions); + driveTimestamp.set(state.Timestamp); + driveOdometryFrequency.set(1.0 / state.OdometryPeriod); + + /* Also write to log file */ + m_poseArray[0] = state.Pose.getX(); + m_poseArray[1] = state.Pose.getY(); + m_poseArray[2] = state.Pose.getRotation().getDegrees(); + for (int i = 0; i < 4; ++i) { + m_moduleStatesArray[i * 2 + 0] = state.ModuleStates[i].angle.getRadians(); + m_moduleStatesArray[i * 2 + 1] = state.ModuleStates[i].speedMetersPerSecond; + m_moduleTargetsArray[i * 2 + 0] = state.ModuleTargets[i].angle.getRadians(); + m_moduleTargetsArray[i * 2 + 1] = state.ModuleTargets[i].speedMetersPerSecond; + } + + SignalLogger.writeDoubleArray("DriveState/Pose", m_poseArray); + SignalLogger.writeDoubleArray("DriveState/ModuleStates", m_moduleStatesArray); + SignalLogger.writeDoubleArray("DriveState/ModuleTargets", m_moduleTargetsArray); + SignalLogger.writeDouble("DriveState/OdometryPeriod", state.OdometryPeriod, "seconds"); + + /* Telemeterize the pose to a Field2d */ + fieldTypePub.set("Field2d"); + fieldPub.set(m_poseArray); + + // TODO: Re-impelement + // if (m_fieldSim != null) { + // for (ModuleMap.MODULE_POSITION i : ModuleMap.MODULE_POSITION.values()) { + // m_moduleVisualizer[i.ordinal()].update(state.ModuleStates[i.ordinal()]); + // m_moduleTransforms[i.ordinal()] = + // new Transform2d( + // SWERVE.DRIVE.kModuleTranslations.get(i), + // state.ModuleStates[i.ordinal()].angle); + // m_swerveModulePoses[i.ordinal()] = + // pose.transformBy(m_moduleTransforms[i.ordinal()]); + // } + // + // m_fieldSim.updateRobotPose(pose); + // m_fieldSim.updateSwervePoses(m_swerveModulePoses); + // } + } +} diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib.json new file mode 100644 index 0000000..396f92d --- /dev/null +++ b/vendordeps/PathplannerLib.json @@ -0,0 +1,38 @@ +{ + "fileName": "PathplannerLib.json", + "name": "PathplannerLib", + "version": "2025.1.1", + "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", + "frcYear": "2025", + "mavenUrls": [ + "https://3015rangerrobotics.github.io/pathplannerlib/repo" + ], + "jsonUrl": "https://3015rangerrobotics.github.io/pathplannerlib/PathplannerLib.json", + "javaDependencies": [ + { + "groupId": "com.pathplanner.lib", + "artifactId": "PathplannerLib-java", + "version": "2025.1.1" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "com.pathplanner.lib", + "artifactId": "PathplannerLib-cpp", + "version": "2025.1.1", + "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/Phoenix6-frc2025-latest.json b/vendordeps/Phoenix6-frc2025-latest.json new file mode 100644 index 0000000..7f4bd2e --- /dev/null +++ b/vendordeps/Phoenix6-frc2025-latest.json @@ -0,0 +1,389 @@ +{ + "fileName": "Phoenix6-frc2025-latest.json", + "name": "CTRE-Phoenix (v6)", + "version": "25.1.0", + "frcYear": "2025", + "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-frc2025-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-frc2025-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "25.1.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "api-cpp", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "25.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": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "25.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": "25.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": "25.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": "25.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": "25.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": "25.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": "25.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": "simCANCoder", + "version": "25.1.0", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.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": "simProCANcoder", + "version": "25.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": "25.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": "25.1.0", + "libName": "CTRE_SimProCANrange", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file