diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/frc/robot/BuildConstants.java index 268643d..bcc9f9f 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/frc/robot/BuildConstants.java @@ -3,25 +3,15 @@ /** Automatically generated file containing build version information. */ public final class BuildConstants { public static final String MAVEN_GROUP = ""; - public static final String MAVEN_NAME = "AdvantageKit_TalonFXSwerveTemplate"; + public static final String MAVEN_NAME = "2025TemplateRobotCode"; public static final String VERSION = "unspecified"; -<<<<<<< Updated upstream - public static final int GIT_REVISION = 14; - public static final String GIT_SHA = "71903e992f09d70d8dc29903114fa0ed607e07e7"; - public static final String GIT_DATE = "2024-11-10 16:32:20 EST"; - public static final String GIT_BRANCH = "subsystems-import"; - public static final String BUILD_DATE = "2024-11-10 17:28:21 EST"; - public static final long BUILD_UNIX_TIME = 1731277701353L; + public static final int GIT_REVISION = 25; + public static final String GIT_SHA = "684dd24387e9b57a008d05ee3e8e3cca5aee1f77"; + public static final String GIT_DATE = "2024-12-07 10:27:36 EST"; + public static final String GIT_BRANCH = "AK-files"; + public static final String BUILD_DATE = "2024-12-07 12:21:42 EST"; + public static final long BUILD_UNIX_TIME = 1733592102547L; public static final int DIRTY = 1; -======= - public static final int GIT_REVISION = -1; - public static final String GIT_SHA = "UNKNOWN"; - public static final String GIT_DATE = "UNKNOWN"; - public static final String GIT_BRANCH = "UNKNOWN"; - public static final String BUILD_DATE = "2024-12-06 16:30:32 EST"; - public static final long BUILD_UNIX_TIME = 1733520632774L; - public static final int DIRTY = 129; ->>>>>>> Stashed changes private BuildConstants() {} } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 58d7742..264a576 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -16,6 +16,7 @@ import edu.wpi.first.wpilibj.Threads; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; +import frc.robot.constants.SimConstants; import org.littletonrobotics.junction.LogFileUtil; import org.littletonrobotics.junction.LoggedRobot; import org.littletonrobotics.junction.Logger; @@ -53,7 +54,7 @@ public Robot() { } // Set up data receivers & replay source - switch (Constants.currentMode) { + switch (SimConstants.currentMode) { case REAL: // Running on a real robot, log to a USB stick ("/U/logs") Logger.addDataReceiver(new WPILOGWriter()); diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 9b0c72c..08020ec 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -16,12 +16,8 @@ import static frc.robot.constants.VisionConstants.camera0Name; import static frc.robot.constants.VisionConstants.camera1Name; -import org.littletonrobotics.junction.networktables.LoggedDashboardChooser; -import org.littletonrobotics.junction.networktables.LoggedDashboardNumber; - import com.pathplanner.lib.auto.AutoBuilder; import com.pathplanner.lib.auto.NamedCommands; - import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.GenericHID; @@ -31,7 +27,8 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.robot.commands.DriveCommands; -import frc.robot.constants.PhysicalConstants; +import frc.robot.constants.SimConstants; +import frc.robot.constants.TunerConstants; import frc.robot.subsystems.drive.Drive; import frc.robot.subsystems.drive.GyroIO; import frc.robot.subsystems.drive.GyroIOPigeon2; @@ -41,10 +38,11 @@ import frc.robot.subsystems.flywheel.Flywheel; import frc.robot.subsystems.flywheel.FlywheelIO; import frc.robot.subsystems.flywheel.FlywheelIOSim; -import frc.robot.subsystems.flywheel.FlywheelIOSparkMax; +import frc.robot.subsystems.flywheel.FlywheelIOTalonFX; import frc.robot.subsystems.vision.Vision; import frc.robot.subsystems.vision.VisionIO; import frc.robot.subsystems.vision.VisionIOLimelight; +import org.littletonrobotics.junction.networktables.LoggedDashboardChooser; /** * This class is where the bulk of the robot should be declared. Since Command-based is a @@ -63,23 +61,21 @@ public class RobotContainer { // Dashboard inputs private final LoggedDashboardChooser autoChooser; - private final LoggedDashboardNumber flywheelSpeedInput = - new LoggedDashboardNumber("Flywheel Speed", 1500.0); /** The container for the robot. Contains subsystems, OI devices, and commands. */ public RobotContainer() { - switch (PhysicalConstants.currentMode) { + switch (SimConstants.currentMode) { case REAL: // Real robot, instantiate hardware IO implementations drive = new Drive( - new GyroIOPigeon2(false), - new ModuleIOTalonFX(0), - new ModuleIOTalonFX(1), - new ModuleIOTalonFX(2), - new ModuleIOTalonFX(3)); + new GyroIOPigeon2(), + new ModuleIOTalonFX(TunerConstants.FrontLeft), + new ModuleIOTalonFX(TunerConstants.FrontRight), + new ModuleIOTalonFX(TunerConstants.BackLeft), + new ModuleIOTalonFX(TunerConstants.BackRight)); - flywheel = new Flywheel(new FlywheelIOSparkMax()); + flywheel = new Flywheel(new FlywheelIOTalonFX()); vision = new Vision( drive::addVisionMeasurement, @@ -100,12 +96,12 @@ public RobotContainer() { drive = new Drive( new GyroIO() {}, - new ModuleIOSim(), - new ModuleIOSim(), - new ModuleIOSim(), - new ModuleIOSim()); + new ModuleIOSim(TunerConstants.FrontLeft), + new ModuleIOSim(TunerConstants.FrontRight), + new ModuleIOSim(TunerConstants.BackLeft), + new ModuleIOSim(TunerConstants.BackRight)); vision = new Vision(drive::addVisionMeasurement, new VisionIO() {}, new VisionIO() {}); - + flywheel = new Flywheel(new FlywheelIOSim()); break; @@ -127,8 +123,7 @@ public RobotContainer() { // Set up auto routines NamedCommands.registerCommand( "Run Flywheel", - Commands.startEnd( - () -> flywheel.runVelocity(flywheelSpeedInput.get()), flywheel::stop, flywheel) + Commands.startEnd(() -> flywheel.runVelocity(500), flywheel::stop, flywheel) .withTimeout(5.0)); autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser()); @@ -181,11 +176,6 @@ private void configureButtonBindings() { new Pose2d(drive.getPose().getTranslation(), new Rotation2d())), drive) .ignoringDisable(true)); - controller - .a() - .whileTrue( - Commands.startEnd( - () -> flywheel.runVelocity(flywheelSpeedInput.get()), flywheel::stop, flywheel)); } /** diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/constants/SimConstants.java similarity index 94% rename from src/main/java/frc/robot/Constants.java rename to src/main/java/frc/robot/constants/SimConstants.java index 4c29008..a28b24b 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/constants/SimConstants.java @@ -11,7 +11,7 @@ // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. -package frc.robot; +package frc.robot.constants; import edu.wpi.first.wpilibj.RobotBase; @@ -20,7 +20,7 @@ * on a roboRIO. Change the value of "simMode" to switch between "sim" (physics sim) and "replay" * (log replay from a file). */ -public final class Constants { +public final class SimConstants { public static final Mode simMode = Mode.SIM; public static final Mode currentMode = RobotBase.isReal() ? Mode.REAL : simMode; diff --git a/src/main/java/frc/robot/constants/PhysicalConstants.java b/src/main/java/frc/robot/constants/SubsystemConstants.java similarity index 64% rename from src/main/java/frc/robot/constants/PhysicalConstants.java rename to src/main/java/frc/robot/constants/SubsystemConstants.java index 5490d7b..15ce637 100644 --- a/src/main/java/frc/robot/constants/PhysicalConstants.java +++ b/src/main/java/frc/robot/constants/SubsystemConstants.java @@ -11,34 +11,14 @@ // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the // GNU General Public License for more details. +// does not include swerve constants + package frc.robot.constants; -import edu.wpi.first.math.util.Units; +public final class SubsystemConstants { -public final class PhysicalConstants { - public static final Mode currentMode = Mode.REAL; - public static final boolean tuningMode = true; public static final String CANBUS = "CAN Bus 2"; - public static final double LOOP_PERIOD_SECS = 0.02; - - public static final String LL_ALIGN = "limelight-align"; - public static final double INTAKE_LL_ANGLE = -20; - public static final double INTAKE_LL_HEIGHT_METERS = 0.5; - - public static class SwerveConstants { - public static final double MAX_LINEAR_SPEED = 5.56; - public static final double TRACK_WIDTH_X_METERS = Units.inchesToMeters(26.0); - public static final double TRACK_WIDTH_Y_METERS = Units.inchesToMeters(26.0); - public static final double DRIVE_BASE_RADIUS = - Math.hypot(TRACK_WIDTH_X_METERS / 2.0, TRACK_WIDTH_Y_METERS / 2.0); - public static final double MAX_ANGULAR_SPEED = 0.45 * MAX_LINEAR_SPEED / DRIVE_BASE_RADIUS; - public static final double OPEN_LOOP_RAMP_SEC = 0.05; - } - - public static class ModuleConstants { - public static final double DRIVE_GEAR_RATIO = 6.12; - public static final double TURN_GEAR_RATIO = 150.0 / 7.0; - } + public static final double LOOP_PERIOD_SECONDS = 0.02; public static class IntakeConstants { public static final int CURRENT_LIMIT = 40; @@ -104,12 +84,4 @@ public static enum Mode { SIM, REPLAY } - - public static Mode getMode() { - return switch (currentMode) { - case REAL -> Mode.REAL; - case SIM -> Mode.SIM; - case REPLAY -> Mode.REPLAY; - }; - } } diff --git a/src/main/java/frc/robot/subsystems/arms/Pivot.java b/src/main/java/frc/robot/subsystems/arms/Pivot.java index 1cd7196..8743a93 100644 --- a/src/main/java/frc/robot/subsystems/arms/Pivot.java +++ b/src/main/java/frc/robot/subsystems/arms/Pivot.java @@ -4,12 +4,18 @@ package frc.robot.subsystems.arms; +import static edu.wpi.first.units.Units.Degrees; +import static edu.wpi.first.units.Units.DegreesPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.ArmFeedforward; import edu.wpi.first.math.trajectory.TrapezoidProfile; +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.constants.PhysicalConstants; - +import frc.robot.constants.SimConstants; +import frc.robot.constants.SubsystemConstants; import org.littletonrobotics.junction.Logger; public class Pivot extends SubsystemBase { @@ -36,7 +42,7 @@ public class Pivot extends SubsystemBase { /** Creates a new Pivot. */ public Pivot(PivotIO pivot) { this.pivot = pivot; - switch (PhysicalConstants.getMode()) { + switch (SimConstants.currentMode) { case REAL: kG = 0.29; kV = 1; @@ -96,7 +102,11 @@ public void setPositionDegs(double positionDegs, double velocityDegsPerSec) { positionDegs = MathUtil.clamp(positionDegs, 33, 120); pivot.setPositionSetpointDegs( positionDegs, - pivotFFModel.calculate(Math.toRadians(positionDegs), Math.toRadians(velocityDegsPerSec))); + pivotFFModel + .calculate( + Angle.ofBaseUnits(positionDegs, Degrees), + AngularVelocity.ofBaseUnits(velocityDegsPerSec, DegreesPerSecond)) + .in(Volts)); } public void pivotStop() { @@ -118,7 +128,9 @@ public void periodic() { pivotCurrentStateDegrees = pivotProfile.calculate( - PhysicalConstants.LOOP_PERIOD_SECS, pivotCurrentStateDegrees, pivotGoalStateDegrees); + SubsystemConstants.LOOP_PERIOD_SECONDS, + pivotCurrentStateDegrees, + pivotGoalStateDegrees); setPositionDegs(pivotCurrentStateDegrees.position, pivotCurrentStateDegrees.velocity); diff --git a/src/main/java/frc/robot/subsystems/arms/PivotIOSim.java b/src/main/java/frc/robot/subsystems/arms/PivotIOSim.java index df96121..eab17d4 100644 --- a/src/main/java/frc/robot/subsystems/arms/PivotIOSim.java +++ b/src/main/java/frc/robot/subsystems/arms/PivotIOSim.java @@ -7,17 +7,15 @@ import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; -import frc.robot.constants.physicalConstants; +import frc.robot.constants.SubsystemConstants; /** Add your docs here. */ public class PivotIOSim implements PivotIO { // private final DCMotor pivotGearbox = DCMotor.getKrakenX60Foc(2); - + // public RobotContainer robotContainer = new RobotContainer(); - // SIM VARIABLES private int gearBoxMotorCount = 2; @@ -73,7 +71,7 @@ public void updateInputs(PivotIOInputs inputs) { inputs.velocityDegsPerSec = Math.toDegrees(velocityRadsPerSec); inputs.currentAmps = currentAmps; - sim.update(physicalConstants.LOOP_PERIOD_SECS); + sim.update(SubsystemConstants.LOOP_PERIOD_SECONDS); } @Override diff --git a/src/main/java/frc/robot/subsystems/arms/PivotIOTalonFX.java b/src/main/java/frc/robot/subsystems/arms/PivotIOTalonFX.java index 7857bc1..0e272df 100644 --- a/src/main/java/frc/robot/subsystems/arms/PivotIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/arms/PivotIOTalonFX.java @@ -12,16 +12,11 @@ import com.ctre.phoenix6.signals.FeedbackSensorSourceValue; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; - -<<<<<<< Updated upstream -import frc.robot.constants.PhysicalConstants; -======= import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Voltage; -import frc.robot.physicalConstants; ->>>>>>> Stashed changes +import frc.robot.constants.SubsystemConstants; import frc.robot.util.Conversions; import org.littletonrobotics.junction.Logger; @@ -43,15 +38,15 @@ public class PivotIOTalonFX implements PivotIO { public PivotIOTalonFX(int leadID, int followID, int gyroID) { TalonFXConfiguration config = new TalonFXConfiguration(); - config.CurrentLimits.StatorCurrentLimit = PhysicalConstants.PivotConstants.CURRENT_LIMIT; + config.CurrentLimits.StatorCurrentLimit = SubsystemConstants.PivotConstants.CURRENT_LIMIT; config.CurrentLimits.StatorCurrentLimitEnable = - PhysicalConstants.PivotConstants.CURRENT_LIMIT_ENABLED; + SubsystemConstants.PivotConstants.CURRENT_LIMIT_ENABLED; config.MotorOutput.NeutralMode = NeutralModeValue.Coast; config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; config.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.RotorSensor; - leader = new TalonFX(leadID, PhysicalConstants.CANBUS); - follower = new TalonFX(followID, PhysicalConstants.CANBUS); - pigeon = new Pigeon2(gyroID, PhysicalConstants.CANBUS); + leader = new TalonFX(leadID, SubsystemConstants.CANBUS); + follower = new TalonFX(followID, SubsystemConstants.CANBUS); + pigeon = new Pigeon2(gyroID, SubsystemConstants.CANBUS); pigeon.reset(); leader.getConfigurator().apply(config); @@ -63,10 +58,10 @@ public PivotIOTalonFX(int leadID, int followID, int gyroID) { startAngleDegs = pitch.getValueAsDouble(); leader.setPosition( - Conversions.degreesToFalcon(startAngleDegs, PhysicalConstants.PivotConstants.REDUCTION)); + Conversions.degreesToFalcon(startAngleDegs, SubsystemConstants.PivotConstants.REDUCTION)); follower.setPosition( - Conversions.degreesToFalcon(startAngleDegs, PhysicalConstants.PivotConstants.REDUCTION)); + Conversions.degreesToFalcon(startAngleDegs, SubsystemConstants.PivotConstants.REDUCTION)); leaderPositionDegs = leader.getPosition(); velocityDegsPerSec = leader.getVelocity(); @@ -75,7 +70,7 @@ public PivotIOTalonFX(int leadID, int followID, int gyroID) { // leader.get - positionSetpointDegs = PhysicalConstants.PivotConstants.STOW_SETPOINT_DEG; + positionSetpointDegs = SubsystemConstants.PivotConstants.STOW_SETPOINT_DEG; Logger.recordOutput("start angle", startAngleDegs); @@ -94,23 +89,17 @@ public void updateInputs(PivotIOInputs inputs) { BaseStatusSignal.refreshAll( leaderPositionDegs, velocityDegsPerSec, appliedVolts, currentAmps, pitch); inputs.gyroConnected = BaseStatusSignal.refreshAll(pitch).equals(StatusCode.OK); - inputs.pitch = pitch.getValueAsDouble() + PhysicalConstants.PivotConstants.PIVOT_ZERO_ANGLE; + inputs.pitch = pitch.getValueAsDouble() + SubsystemConstants.PivotConstants.PIVOT_ZERO_ANGLE; inputs.positionDegs = Conversions.falconToDegrees( - (leaderPositionDegs.getValueAsDouble()), PhysicalConstants.PivotConstants.REDUCTION) - + PhysicalConstants.PivotConstants.PIVOT_ZERO_ANGLE; + (leaderPositionDegs.getValueAsDouble()), + SubsystemConstants.PivotConstants.REDUCTION) + + SubsystemConstants.PivotConstants.PIVOT_ZERO_ANGLE; // inputs.velocityDegsPerSec = // Conversions.falconToDegrees( // (followPositionDegs.getValueAsDouble()), Constants.PivotConstants.REDUCTION); - inputs.velocityDegsPerSec = -<<<<<<< Updated upstream - Conversions.falconToDegrees( - velocityDegsPerSec.getValueAsDouble() * 2048, - PhysicalConstants.PivotConstants.REDUCTION); -======= - velocityDegsPerSec.getValueAsDouble(); ->>>>>>> Stashed changes + inputs.velocityDegsPerSec = velocityDegsPerSec.getValueAsDouble(); inputs.appliedVolts = appliedVolts.getValueAsDouble(); inputs.currentAmps = currentAmps.getValueAsDouble(); inputs.positionSetpointDegs = positionSetpointDegs; @@ -135,14 +124,7 @@ public void setPositionSetpointDegs(double positionDegs, double ffVolts) { leader.setControl( new PositionVoltage( Conversions.degreesToFalcon( - positionDegs - 59, PhysicalConstants.PivotConstants.REDUCTION), - 0, - false, - ffVolts, - 0, - false, - false, - false)); + positionDegs - 59, SubsystemConstants.PivotConstants.REDUCTION))); } @Override diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 8a7e931..abf11b9 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -46,14 +46,10 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -<<<<<<< Updated upstream -import frc.robot.constants.PhysicalConstants; -import frc.robot.subsystems.vision.VisionIO; -======= -import frc.robot.Constants; -import frc.robot.Constants.Mode; -import frc.robot.generated.TunerConstants; ->>>>>>> Stashed changes +import frc.robot.constants.SimConstants; +import frc.robot.constants.SimConstants.Mode; +import frc.robot.constants.SubsystemConstants; +import frc.robot.constants.TunerConstants; import frc.robot.util.LocalADStarAK; import java.util.concurrent.locks.Lock; import java.util.concurrent.locks.ReentrantLock; @@ -61,20 +57,6 @@ import org.littletonrobotics.junction.Logger; public class Drive extends SubsystemBase { -<<<<<<< Updated upstream - private static final double MAX_LINEAR_SPEED = - PhysicalConstants.SwerveConstants.MAX_LINEAR_SPEED * 0.85; - private static final double TRACK_WIDTH_X = - PhysicalConstants.SwerveConstants.TRACK_WIDTH_X_METERS; - private static final double TRACK_WIDTH_Y = - PhysicalConstants.SwerveConstants.TRACK_WIDTH_Y_METERS; - private static final double DRIVE_BASE_RADIUS = - PhysicalConstants.SwerveConstants.DRIVE_BASE_RADIUS; - private static final double MAX_ANGULAR_SPEED = - PhysicalConstants.SwerveConstants.MAX_ANGULAR_SPEED; - private static double multiplier = 1.0; - private static boolean toggle = false; -======= // TunerConstants doesn't include these constants, so they are declared locally static final double ODOMETRY_FREQUENCY = new CANBus(TunerConstants.DrivetrainConstants.CANBusName).isNetworkFD() ? 250.0 : 100.0; @@ -86,7 +68,6 @@ public class Drive extends SubsystemBase { Math.max( Math.hypot(TunerConstants.BackLeft.LocationX, TunerConstants.BackLeft.LocationY), Math.hypot(TunerConstants.BackRight.LocationX, TunerConstants.BackRight.LocationY))); ->>>>>>> Stashed changes // PathPlanner config constants private static final double ROBOT_MASS_KG = 74.088; @@ -150,22 +131,10 @@ public Drive( this::setPose, this::getChassisSpeeds, this::runVelocity, -<<<<<<< Updated upstream - new HolonomicPathFollowerConfig( - new PIDConstants(5), - new PIDConstants(1.5), - PhysicalConstants.SwerveConstants.MAX_LINEAR_SPEED, - DRIVE_BASE_RADIUS, - new ReplanningConfig()), - () -> - DriverStation.getAlliance().isPresent() - && DriverStation.getAlliance().get() == Alliance.Red, -======= new PPHolonomicDriveController( new PIDConstants(5.0, 0.0, 0.0), new PIDConstants(5.0, 0.0, 0.0)), PP_CONFIG, () -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red, ->>>>>>> Stashed changes this); Pathfinding.setPathfinder(new LocalADStarAK()); PathPlannerLogging.setLogActivePathCallback( @@ -246,7 +215,7 @@ public void periodic() { } // Update gyro alert - gyroDisconnectedAlert.set(!gyroInputs.connected && Constants.currentMode != Mode.SIM); + gyroDisconnectedAlert.set(!gyroInputs.connected && SimConstants.currentMode != Mode.SIM); } /** @@ -256,7 +225,7 @@ public void periodic() { */ public void runVelocity(ChassisSpeeds speeds) { // Calculate module setpoints - speeds.discretize(0.02); + speeds.discretize(SubsystemConstants.LOOP_PERIOD_SECONDS); SwerveModuleState[] setpointStates = kinematics.toSwerveModuleStates(speeds); SwerveDriveKinematics.desaturateWheelSpeeds(setpointStates, TunerConstants.kSpeedAt12Volts); @@ -397,5 +366,4 @@ public static Translation2d[] getModuleTranslations() { new Translation2d(TunerConstants.BackRight.LocationX, TunerConstants.BackRight.LocationY) }; } - } diff --git a/src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java b/src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java index 1bbb223..2a7f209 100644 --- a/src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java +++ b/src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java @@ -23,7 +23,6 @@ import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import frc.robot.constants.TunerConstants; - import java.util.Queue; /** IO implementation for Pigeon 2. */ diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java index 0a9cb83..dfb544e 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOSim.java @@ -22,6 +22,7 @@ import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.simulation.DCMotorSim; +import frc.robot.constants.SubsystemConstants; /** * Physics sim implementation of module IO. The sim models are configured using a set of module @@ -86,8 +87,8 @@ public void updateInputs(ModuleIOInputs inputs) { // Update simulation state driveSim.setInputVoltage(MathUtil.clamp(driveAppliedVolts, -12.0, 12.0)); turnSim.setInputVoltage(MathUtil.clamp(turnAppliedVolts, -12.0, 12.0)); - driveSim.update(0.02); - turnSim.update(0.02); + driveSim.update(SubsystemConstants.LOOP_PERIOD_SECONDS); + turnSim.update(SubsystemConstants.LOOP_PERIOD_SECONDS); // Update drive inputs inputs.driveConnected = true; diff --git a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java index 655e2fb..67046df 100644 --- a/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java @@ -41,7 +41,6 @@ import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Voltage; import frc.robot.constants.TunerConstants; - import java.util.Queue; /** diff --git a/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java b/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java index 082bb6d..d83517d 100644 --- a/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java +++ b/src/main/java/frc/robot/subsystems/drive/PhoenixOdometryThread.java @@ -19,7 +19,6 @@ import edu.wpi.first.units.measure.Angle; import edu.wpi.first.wpilibj.RobotController; import frc.robot.constants.TunerConstants; - import java.util.ArrayList; import java.util.List; import java.util.Queue; diff --git a/src/main/java/frc/robot/subsystems/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/elevator/Elevator.java index 247c7a0..c85dd18 100644 --- a/src/main/java/frc/robot/subsystems/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/elevator/Elevator.java @@ -1,13 +1,15 @@ package frc.robot.subsystems.elevator; +import static edu.wpi.first.units.Units.InchesPerSecond; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.controller.ElevatorFeedforward; import edu.wpi.first.math.trajectory.TrapezoidProfile; +import edu.wpi.first.units.measure.LinearVelocity; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.physicalConstants; - -import static edu.wpi.first.units.Units.MetersPerSecond; - +import frc.robot.constants.SimConstants; +import frc.robot.constants.SubsystemConstants; import org.littletonrobotics.junction.Logger; import org.littletonrobotics.junction.networktables.LoggedNetworkNumber; @@ -25,7 +27,6 @@ public class Elevator extends SubsystemBase { private static final LoggedNetworkNumber kV = new LoggedNetworkNumber("Elevator/kV"); private static final LoggedNetworkNumber kA = new LoggedNetworkNumber("Elevator/kA"); - private static final LoggedNetworkNumber barkG = new LoggedNetworkNumber("Bar/kG"); private TrapezoidProfile extenderProfile; @@ -34,10 +35,6 @@ public class Elevator extends SubsystemBase { private TrapezoidProfile.State extenderGoal = new TrapezoidProfile.State(); private TrapezoidProfile.State extenderCurrent = new TrapezoidProfile.State(); - private static double maxVelocityDegPerSec; - private static double maxAccelerationDegPerSecSquared; - - private double goal; // private double barGoalPos; private final ElevatorFeedforward elevatorFFModel; @@ -45,9 +42,8 @@ public class Elevator extends SubsystemBase { public Elevator(ElevatorIO elevator) { this.elevator = elevator; - switch (PhysicalConstants.getMode()) { + switch (SimConstants.currentMode) { case REAL: - kS.setDefault(0); kG.setDefault(0.25); kV.setDefault(0); @@ -56,7 +52,6 @@ public Elevator(ElevatorIO elevator) { kP.setDefault(0.44); kI.setDefault(0); - barkG.setDefault(0); break; case REPLAY: @@ -68,7 +63,6 @@ public Elevator(ElevatorIO elevator) { kP.setDefault(15); kI.setDefault(0); - barkG.setDefault(0); break; case SIM: @@ -80,7 +74,6 @@ public Elevator(ElevatorIO elevator) { kP.setDefault(1); kI.setDefault(0); - barkG.setDefault(0); break; default: @@ -92,7 +85,6 @@ public Elevator(ElevatorIO elevator) { kP.setDefault(15); kI.setDefault(0); - barkG.setDefault(0); break; } @@ -101,23 +93,13 @@ public Elevator(ElevatorIO elevator) { extenderProfile = new TrapezoidProfile(extenderConstraints); extenderCurrent = extenderProfile.calculate(0, extenderCurrent, extenderGoal); - maxVelocityDegPerSec = 1200; - maxAccelerationDegPerSecSquared = 1550; - - - this.elevator.configurePID(kP.get(), 0, 0); elevatorFFModel = new ElevatorFeedforward(kS.get(), kG.get(), kV.get(), kA.get()); } public boolean atGoal() { -<<<<<<< Updated upstream - return (Math.abs(eInputs.elevatorPosition - goal) - <= PhysicalConstants.ElevatorConstants.THRESHOLD); -======= return (Math.abs(eInputs.elevatorPositionInch - goal) - <= physicalConstants.ElevatorConstants.THRESHOLD); ->>>>>>> Stashed changes + <= SubsystemConstants.ElevatorConstants.THRESHOLD); } public double getElevatorPosition() { @@ -129,7 +111,7 @@ private double getElevatorError() { } public boolean elevatorAtSetpoint() { - return (Math.abs(getElevatorError()) <= PhysicalConstants.ElevatorConstants.THRESHOLD); + return (Math.abs(getElevatorError()) <= SubsystemConstants.ElevatorConstants.THRESHOLD); } // public void setbarCurrent(double current) { @@ -143,7 +125,9 @@ public void setExtenderGoal(double setpoint) { } public void setPositionExtend(double position, double velocity) { - elevator.setPositionSetpoint(position, elevatorFFModel.calculate(MetersPerSecond.of(velocity))); + elevator.setPositionSetpoint( + position, + elevatorFFModel.calculate(LinearVelocity.ofBaseUnits(velocity, InchesPerSecond)).in(Volts)); } public void elevatorStop() { @@ -164,7 +148,7 @@ public void setConstraints( } public boolean isExtended() { - return extenderGoal.position == PhysicalConstants.ElevatorConstants.EXTEND_SETPOINT_INCH; + return extenderGoal.position == SubsystemConstants.ElevatorConstants.EXTEND_SETPOINT_INCH; } @Override @@ -175,26 +159,19 @@ public void periodic() { extenderCurrent = extenderProfile.calculate( - PhysicalConstants.LOOP_PERIOD_SECS, extenderCurrent, extenderGoal); - -<<<<<<< Updated upstream - barCurrent = barProfile.calculate(PhysicalConstants.LOOP_PERIOD_SECS, barCurrent, barGoal); -======= - ->>>>>>> Stashed changes + SubsystemConstants.LOOP_PERIOD_SECONDS, extenderCurrent, extenderGoal); setPositionExtend(extenderCurrent.position, extenderCurrent.velocity); Logger.processInputs("Elevator", eInputs); - - // if (kP.hasChanged(hashCode()) || kI.hasChanged(hashCode())) { + // if (kP.hasChanged(hashCode()) || kI.hasChanged(hashCode())) { // elevator.configurePID(kP.get(), kI.get(), 0); - // } - // if (barkP.hasChanged(hashCode()) - // || barkV.hasChanged(hashCode()) - // || barkG.hasChanged(hashCode())) {} - // } + // } + // if (barkP.hasChanged(hashCode()) + // || barkV.hasChanged(hashCode()) + // || barkG.hasChanged(hashCode())) {} + // } - } -} \ No newline at end of file + } +} diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java index 8124a8c..2117a74 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java @@ -2,8 +2,6 @@ import org.littletonrobotics.junction.AutoLog; -import edu.wpi.first.units.measure.Voltage; - public interface ElevatorIO { @AutoLog public static class ElevatorIOInputs { @@ -18,7 +16,7 @@ public default void updateInputs(ElevatorIOInputs inputs) {} public default void runCharacterization(double volts) {} - public default void setPositionSetpoint(double position, Voltage ffVolts) {} + public default void setPositionSetpoint(double position, double ffVolts) {} public default void stop() {} diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorIOSim.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorIOSim.java index 272be71..72e30a7 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorIOSim.java @@ -4,36 +4,16 @@ package frc.robot.subsystems.elevator; -import static edu.wpi.first.units.Units.Amps; -import static edu.wpi.first.units.Units.Inches; -import static edu.wpi.first.units.Units.InchesPerSecond; -import static edu.wpi.first.units.Units.Meters; -import static edu.wpi.first.units.Units.MetersPerSecond; -import static edu.wpi.first.units.Units.Volts; - import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.units.measure.Voltage; -import edu.wpi.first.units.measure.Current; -import edu.wpi.first.units.measure.Distance; -import edu.wpi.first.units.measure.LinearVelocity; - - +import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.simulation.ElevatorSim; -import frc.robot.constants.physicalConstants; +import frc.robot.constants.SubsystemConstants; /** Add your docs here. */ public class ElevatorIOSim implements ElevatorIO { -<<<<<<< Updated upstream - private final DCMotor simGearbox = DCMotor.getKrakenX60Foc(2); - private ElevatorSim sim = new ElevatorSim(simGearbox, 1, 1, 0.01, 0.0, 3, true, 0.0); - private PIDController pid = new PIDController(0, 0, 0); - - private Distance position = Inches.of(0); - private LinearVelocity velocityInchPerSec = InchesPerSecond.of(0); -======= // SIM VARIABLES (CHANGE) private int gearBoxMotorCount = 2; private int gearing = 1; @@ -44,7 +24,7 @@ public class ElevatorIOSim implements ElevatorIO { private boolean simulateGravity = true; private double initialPositionMeters = 0.0; - private final DCMotor simGearbox = DCMotor.getFalcon500(gearBoxMotorCount); + private final DCMotor simGearbox = DCMotor.getKrakenX60Foc(gearBoxMotorCount); private ElevatorSim sim = new ElevatorSim( simGearbox, @@ -57,55 +37,35 @@ public class ElevatorIOSim implements ElevatorIO { initialPositionMeters); private PIDController pid = new PIDController(0, 0, 0); - private Distance position = Inches.of(0); - private LinearVelocity velocity = InchesPerSecond.of(0); ->>>>>>> Stashed changes - private Voltage appliedVolts = Volts.of(0.0); - private Current currentAmps = Amps.of(0.0); - private Distance positionSetpointInches = Inches.of(0); + private double positionInch = 0; + private double velocityInchesPerSecond = 0; + private double appliedVolts = 0; + private double currentAmps = 0; + private double positionSetpointInches = 0; + @Override + public void updateInputs(ElevatorIOInputs inputs) { + positionSetpointInches = pid.getSetpoint(); + appliedVolts += + MathUtil.clamp( + pid.calculate(Units.metersToInches(sim.getPositionMeters()), positionSetpointInches), + -12.0, + 12); - + sim.setInputVoltage(appliedVolts); - @Override - public void updateInputs(ElevatorIOInputs inputs) { - positionSetpointInches = Inches.of(pid.getSetpoint()); - -<<<<<<< Updated upstream -======= - ->>>>>>> Stashed changes - appliedVolts.plus( - Volts.of(MathUtil.clamp( - pid.calculate(Meters.of(sim.getPositionMeters()).in(Inches), positionSetpointInches.in(Inches)), -12.0, 12))); - - sim.setInputVoltage(appliedVolts.in(Volts)); - -<<<<<<< Updated upstream - position = Inches.of(Meters.of(sim.getPositionMeters()).in(Inches)); - position = Meters.of(sim.getPositionMeters()); - - velocityInchPerSec = InchesPerSecond.of(MetersPerSecond.of(sim.getVelocityMetersPerSecond()).in(MetersPerSecond)); - currentAmps = Amps.of(sim.getCurrentDrawAmps()); - - inputs.positionSetpointInch = position.plus(Meters.of(2)); - inputs.appliedVolts = appliedVolts.in(Volts); - inputs.elevatorPosition = position; - inputs.elevatorVelocity = velocityInchPerSec; -======= - position = Meters.of(sim.getPositionMeters()); - velocity = MetersPerSecond.of(sim.getVelocityMetersPerSecond()); - currentAmps = Amps.of(sim.getCurrentDrawAmps()); - - inputs.positionSetpointInch = positionSetpointInches.in(Inches); - inputs.appliedVolts = appliedVolts.in(Volts); - inputs.elevatorPositionInch = position.in(Inches); - inputs.elevatorVelocityInchesPerSecond = velocity.in(InchesPerSecond); ->>>>>>> Stashed changes - inputs.currentAmps = currentAmps.in(Amps); - - sim.update(physicalConstants.LOOP_PERIOD_SECS); + positionInch = Units.metersToInches(sim.getPositionMeters()); + velocityInchesPerSecond = Units.metersToInches(sim.getVelocityMetersPerSecond()); + currentAmps = sim.getCurrentDrawAmps(); + + inputs.positionSetpointInch = positionSetpointInches; + inputs.appliedVolts = appliedVolts; + inputs.elevatorPositionInch = positionInch; + inputs.elevatorVelocityInchesPerSecond = velocityInchesPerSecond; + inputs.currentAmps = currentAmps; + + sim.update(SubsystemConstants.LOOP_PERIOD_SECONDS); } @Override @@ -114,15 +74,15 @@ public void runCharacterization(double volts) { } @Override - public void setPositionSetpoint(double position, Voltage ffVolts) { + public void setPositionSetpoint(double position, double ffVolts) { appliedVolts = ffVolts; pid.setSetpoint(position); } @Override public void stop() { - appliedVolts = Volts.of(0); - pid.setSetpoint(sim.getPositionMeters() * 39.37); + appliedVolts = 0; + pid.setSetpoint(Units.metersToInches(sim.getPositionMeters())); } @Override diff --git a/src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java index 12781a7..478058e 100644 --- a/src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java @@ -9,9 +9,11 @@ import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.FeedbackSensorSourceValue; import com.ctre.phoenix6.signals.NeutralModeValue; - +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Voltage; -import frc.robot.constants.PhysicalConstants; +import frc.robot.constants.SubsystemConstants; import frc.robot.util.Conversions; public class ElevatorIOTalonFX implements ElevatorIO { @@ -19,25 +21,25 @@ public class ElevatorIOTalonFX implements ElevatorIO { private final TalonFX follower; private double positionSetpoint; - private final StatusSignal elevatorPosition; - private final StatusSignal elevatorVelocity; - private final StatusSignal appliedVolts; - private final StatusSignal currentAmps; + private final StatusSignal elevatorPosition; + private final StatusSignal elevatorVelocity; + private final StatusSignal appliedVolts; + private final StatusSignal currentAmps; public ElevatorIOTalonFX(int lead, int follow) { TalonFXConfiguration config = new TalonFXConfiguration(); - config.CurrentLimits.StatorCurrentLimit = PhysicalConstants.ElevatorConstants.CURRENT_LIMIT; + config.CurrentLimits.StatorCurrentLimit = SubsystemConstants.ElevatorConstants.CURRENT_LIMIT; config.CurrentLimits.StatorCurrentLimitEnable = - PhysicalConstants.ElevatorConstants.CURRENT_LIMIT_ENABLED; + SubsystemConstants.ElevatorConstants.CURRENT_LIMIT_ENABLED; config.MotorOutput.NeutralMode = NeutralModeValue.Brake; config.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.RotorSensor; - leader = new TalonFX(lead, PhysicalConstants.CANBUS); - follower = new TalonFX(follow, PhysicalConstants.CANBUS); + leader = new TalonFX(lead, SubsystemConstants.CANBUS); + follower = new TalonFX(follow, SubsystemConstants.CANBUS); leader.getConfigurator().apply(config); - positionSetpoint = PhysicalConstants.ElevatorConstants.RETRACT_SETPOINT_INCH; + positionSetpoint = SubsystemConstants.ElevatorConstants.RETRACT_SETPOINT_INCH; follower.setControl(new Follower(lead, true)); @@ -53,19 +55,19 @@ public ElevatorIOTalonFX(int lead, int follow) { @Override public void updateInputs(ElevatorIOInputs inputs) { BaseStatusSignal.refreshAll(elevatorPosition, elevatorVelocity, appliedVolts, currentAmps); - inputs.elevatorPosition = + inputs.elevatorPositionInch = Conversions.motorRotToInches( elevatorPosition.getValueAsDouble(), 5.97, - PhysicalConstants.ElevatorConstants.REDUCTION); - inputs.elevatorVelocity = + SubsystemConstants.ElevatorConstants.REDUCTION); + inputs.elevatorVelocityInchesPerSecond = Conversions.motorRotToInches( elevatorVelocity.getValueAsDouble() * 60., 5.97, - PhysicalConstants.ElevatorConstants.REDUCTION); + SubsystemConstants.ElevatorConstants.REDUCTION); inputs.appliedVolts = appliedVolts.getValueAsDouble(); inputs.currentAmps = currentAmps.getValueAsDouble(); - inputs.positionSetpoint = positionSetpoint; + inputs.positionSetpointInch = positionSetpoint; } @Override @@ -74,19 +76,12 @@ public void runCharacterization(double volts) { } @Override - public void setPositionSetpoint(double position, Voltage ffVolts) { + public void setPositionSetpoint(double position, double ffVolts) { this.positionSetpoint = position; leader.setControl( new PositionVoltage( Conversions.inchesToMotorRot( - position, 5.97, PhysicalConstants.ElevatorConstants.REDUCTION), - 0, - false, - ffVolts, - 0, - false, - false, - false)); + position, 5.97, SubsystemConstants.ElevatorConstants.REDUCTION))); } @Override diff --git a/src/main/java/frc/robot/subsystems/flywheel/Flywheel.java b/src/main/java/frc/robot/subsystems/flywheel/Flywheel.java index b4512ef..bc4c20a 100644 --- a/src/main/java/frc/robot/subsystems/flywheel/Flywheel.java +++ b/src/main/java/frc/robot/subsystems/flywheel/Flywheel.java @@ -13,15 +13,16 @@ package frc.robot.subsystems.flywheel; +import static edu.wpi.first.units.Units.RadiansPerSecond; import static edu.wpi.first.units.Units.Volts; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.util.Units; +import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -import frc.robot.constants.PhysicalConstants; - +import frc.robot.constants.SimConstants; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -37,7 +38,7 @@ public Flywheel(FlywheelIO io) { // Switch constants based on mode (the physics simulator is treated as a // separate robot with different tuning) - switch (PhysicalConstants.currentMode) { + switch (SimConstants.currentMode) { case REAL: case REPLAY: ffModel = new SimpleMotorFeedforward(0.1, 0.05); @@ -77,7 +78,11 @@ public void runVolts(double volts) { /** Run closed loop at the specified velocity. */ public void runVelocity(double velocityRPM) { var velocityRadPerSec = Units.rotationsPerMinuteToRadiansPerSecond(velocityRPM); - io.setVelocity(velocityRadPerSec, ffModel.calculate(velocityRadPerSec)); + io.setVelocity( + velocityRadPerSec, + ffModel + .calculate(AngularVelocity.ofBaseUnits(velocityRadPerSec, RadiansPerSecond)) + .in(Volts)); // Log flywheel setpoint Logger.recordOutput("Flywheel/SetpointRPM", velocityRPM); diff --git a/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOSim.java b/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOSim.java index 9431daf..c45628d 100644 --- a/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOSim.java +++ b/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOSim.java @@ -16,15 +16,21 @@ import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.wpilibj.simulation.FlywheelSim; +import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.wpilibj.simulation.DCMotorSim; +import frc.robot.constants.SubsystemConstants; public class FlywheelIOSim implements FlywheelIO { private int gearBoxMotorCount = 1; private double gearing = 1.5; private double momentOfInertia = 0.004; + private DCMotor motor = DCMotor.getKrakenX60Foc(gearBoxMotorCount); + private double[] stds = {1, 2, 3}; + + private DCMotorSim sim = + new DCMotorSim( + LinearSystemId.createDCMotorSystem(motor, gearBoxMotorCount, gearing), motor, 0.0); - private FlywheelSim sim = - new FlywheelSim(DCMotor.getNEO(gearBoxMotorCount), gearing, momentOfInertia); private PIDController pid = new PIDController(0.0, 0.0, 0.0); private boolean closedLoop = false; @@ -45,7 +51,7 @@ public void updateInputs(FlywheelIOInputs inputs) { sim.setInputVoltage(appliedVolts); } - sim.update(0.02); + sim.update(SubsystemConstants.LOOP_PERIOD_SECONDS); inputs.positionRad = 0.0; inputs.velocityRadPerSec = sim.getAngularVelocityRadPerSec(); diff --git a/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOSparkMax.java b/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOSparkMax.java deleted file mode 100644 index 787f369..0000000 --- a/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOSparkMax.java +++ /dev/null @@ -1,89 +0,0 @@ -// Copyright 2021-2024 FRC 6328 -// http://github.com/Mechanical-Advantage -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// version 3 as published by the Free Software Foundation or -// available in the root directory of this project. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. - -package frc.robot.subsystems.flywheel; - -import com.revrobotics.CANSparkBase.ControlType; -import com.revrobotics.CANSparkLowLevel.MotorType; -import com.revrobotics.CANSparkMax; -import com.revrobotics.RelativeEncoder; -import com.revrobotics.SparkPIDController; -import com.revrobotics.SparkPIDController.ArbFFUnits; -import edu.wpi.first.math.util.Units; - -/** - * NOTE: To use the Spark Flex / NEO Vortex, replace all instances of "CANSparkMax" with - * "CANSparkFlex". - */ -public class FlywheelIOSparkMax implements FlywheelIO { - private static final double GEAR_RATIO = 1.5; - - private final CANSparkMax leader = new CANSparkMax(0, MotorType.kBrushless); - private final CANSparkMax follower = new CANSparkMax(1, MotorType.kBrushless); - private final RelativeEncoder encoder = leader.getEncoder(); - private final SparkPIDController pid = leader.getPIDController(); - - public FlywheelIOSparkMax() { - leader.restoreFactoryDefaults(); - follower.restoreFactoryDefaults(); - - leader.setCANTimeout(250); - follower.setCANTimeout(250); - - leader.setInverted(false); - follower.follow(leader, false); - - leader.enableVoltageCompensation(12.0); - leader.setSmartCurrentLimit(30); - - leader.burnFlash(); - follower.burnFlash(); - } - - @Override - public void updateInputs(FlywheelIOInputs inputs) { - inputs.positionRad = Units.rotationsToRadians(encoder.getPosition() / GEAR_RATIO); - inputs.velocityRadPerSec = - Units.rotationsPerMinuteToRadiansPerSecond(encoder.getVelocity() / GEAR_RATIO); - inputs.appliedVolts = leader.getAppliedOutput() * leader.getBusVoltage(); - inputs.currentAmps = new double[] {leader.getOutputCurrent(), follower.getOutputCurrent()}; - } - - @Override - public void setVoltage(double volts) { - leader.setVoltage(volts); - } - - @Override - public void setVelocity(double velocityRadPerSec, double ffVolts) { - pid.setReference( - Units.radiansPerSecondToRotationsPerMinute(velocityRadPerSec) * GEAR_RATIO, - ControlType.kVelocity, - 0, - ffVolts, - ArbFFUnits.kVoltage); - } - - @Override - public void stop() { - leader.stopMotor(); - } - - @Override - public void configurePID(double kP, double kI, double kD) { - pid.setP(kP, 0); - pid.setI(kI, 0); - pid.setD(kD, 0); - pid.setFF(0, 0); - } -} diff --git a/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOTalonFX.java b/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOTalonFX.java index b235db4..96dd486 100644 --- a/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/flywheel/FlywheelIOTalonFX.java @@ -26,7 +26,6 @@ import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; -import edu.wpi.first.units.measure.Distance; import edu.wpi.first.units.measure.Voltage; public class FlywheelIOTalonFX implements FlywheelIO { @@ -75,9 +74,7 @@ public void setVoltage(double volts) { @Override public void setVelocity(double velocityRadPerSec, double ffVolts) { - leader.setControl( - new VelocityVoltage( - Units.radiansToRotations(velocityRadPerSec))); + leader.setControl(new VelocityVoltage(Units.radiansToRotations(velocityRadPerSec))); } @Override diff --git a/src/main/java/frc/robot/subsystems/indexers/Indexer.java b/src/main/java/frc/robot/subsystems/indexers/Indexer.java index fbe9fdb..9b2f222 100644 --- a/src/main/java/frc/robot/subsystems/indexers/Indexer.java +++ b/src/main/java/frc/robot/subsystems/indexers/Indexer.java @@ -4,16 +4,22 @@ package frc.robot.subsystems.indexers; -import edu.wpi.first.math.controller.ArmFeedforward; +import static edu.wpi.first.units.Units.InchesPerSecond; +import static edu.wpi.first.units.Units.Volts; + +import edu.wpi.first.math.controller.ElevatorFeedforward; import edu.wpi.first.math.trajectory.TrapezoidProfile; +import edu.wpi.first.units.measure.LinearVelocity; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.constants.PhysicalConstants; +import frc.robot.constants.SimConstants; +import frc.robot.constants.SubsystemConstants; +import org.littletonrobotics.junction.Logger; public class Indexer extends SubsystemBase { /** Creates a new Indexer. */ private final IndexerIO indexer; - private final IndexerIOInputsAutoLogged Iinputs = new IndexerIOInputsAutoLogged(); + private final IndexerIOInputsAutoLogged iInputs = new IndexerIOInputsAutoLogged(); private static double kP; private static double kG; @@ -28,10 +34,12 @@ public class Indexer extends SubsystemBase { private TrapezoidProfile.State indexerGoalStateRotations = new TrapezoidProfile.State(); private TrapezoidProfile.State indexerCurrentStateRotations = new TrapezoidProfile.State(); + private ElevatorFeedforward ff; + public Indexer(IndexerIO indexer) { this.indexer = indexer; - switch (PhysicalConstants.getMode()) { + switch (SimConstants.currentMode) { case REAL: kG = 0.29; kV = 1; @@ -57,23 +65,40 @@ public Indexer(IndexerIO indexer) { maxVelocityRotPerSec = 4; maxAccelerationRotPerSecSquared = 4; - indexerConstraints = new TrapezoidProfile.Constraints(maxVelocityRotPerSec, maxAccelerationRotPerSecSquared); + indexerConstraints = + new TrapezoidProfile.Constraints(maxVelocityRotPerSec, maxAccelerationRotPerSecSquared); indexerProfile = new TrapezoidProfile(indexerConstraints); - - indexerCurrentStateRotations = indexerProfile.calculate(0, indexerCurrentStateRotations, indexerGoalStateRotations); - + + indexerCurrentStateRotations = + indexerProfile.calculate(0, indexerCurrentStateRotations, indexerGoalStateRotations); + indexer.configurePID(kP, 0, 0); + ff = new ElevatorFeedforward(0, kG, kV); } @Override public void periodic() { // This method will be called once per scheduler run - indexer.updateInputs(Iinputs); + indexer.updateInputs(iInputs); + + indexerCurrentStateRotations = + indexerProfile.calculate( + SubsystemConstants.LOOP_PERIOD_SECONDS, + indexerCurrentStateRotations, + indexerGoalStateRotations); + + indexer.setPositionSetpoint( + indexerCurrentStateRotations.position * 360, + ff.calculate( + LinearVelocity.ofBaseUnits(indexerCurrentStateRotations.velocity, InchesPerSecond)) + .in(Volts)); + + Logger.processInputs("Indexer", iInputs); } public void index(double linearDistanceInches) { - indexer.setPosition(positionRots, ffvolts); + double rollerDiameterInches = 1; + indexerGoalStateRotations.position += linearDistanceInches / (rollerDiameterInches * Math.PI); } - } diff --git a/src/main/java/frc/robot/subsystems/indexers/IndexerIO.java b/src/main/java/frc/robot/subsystems/indexers/IndexerIO.java index 7844029..31fe101 100644 --- a/src/main/java/frc/robot/subsystems/indexers/IndexerIO.java +++ b/src/main/java/frc/robot/subsystems/indexers/IndexerIO.java @@ -5,20 +5,20 @@ public interface IndexerIO { @AutoLog public static class IndexerIOInputs { - - public double positionRads = 0.0; - public double velocityRadsPerSec = 0.0; - public double appliedVolts = 0.0; - public double currentAmps = 0.0; + double indexerPositionInch = 0; + double indexerVelocityInchesPerSecond = 0; + double currentAmps = 0; + double appliedVolts = 0; + double positionSetpointInch = 0; } default void updateInputs(IndexerIOInputs inputs) {} - default void setVoltage(double volts) {} + default void runCharacterization(double volts) {} default void stop() {} - default void setPosition(double positionDegs, double ffvolts) {} + default void setPositionSetpoint(double positionDegs, double ffvolts) {} default void configurePID(double kP, double kI, double kD) {} } diff --git a/src/main/java/frc/robot/subsystems/indexers/IndexerIOSim.java b/src/main/java/frc/robot/subsystems/indexers/IndexerIOSim.java index fae7b69..0baec85 100644 --- a/src/main/java/frc/robot/subsystems/indexers/IndexerIOSim.java +++ b/src/main/java/frc/robot/subsystems/indexers/IndexerIOSim.java @@ -3,67 +3,86 @@ import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.math.system.plant.LinearSystemId; -import edu.wpi.first.wpilibj.simulation.DCMotorSim; -import frc.robot.constants.PhysicalConstants; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.simulation.ElevatorSim; +import frc.robot.constants.SubsystemConstants; +/** Add your docs here. */ public class IndexerIOSim implements IndexerIO { - private double indexerGearing = 0; - private double indexerMOI = 0; - private int numberOFIndexerMotors = 0; + // SIM VARIABLES (CHANGE) + private int gearBoxMotorCount = 2; + private int gearing = 1; + private double carriageMassKg = 1; + private double drumRadiusMeters = 0.01; + private double minHeightMeters = 0; + private double maxHeightMeters = Double.POSITIVE_INFINITY; + private boolean simulateGravity = true; + private double initialPositionMeters = 0.0; - private final DCMotor indexer = DCMotor.getKrakenX60(numberOFIndexerMotors); - private final DCMotorSim sim = new DCMotorSim(LinearSystemId.createDCMotorSystem(indexer, indexerMOI, indexerGearing), indexer); - private PIDController pid = new PIDController(0.0, 0.0, 0.0); + private final DCMotor simGearbox = DCMotor.getKrakenX60Foc(gearBoxMotorCount); + private ElevatorSim sim = + new ElevatorSim( + simGearbox, + gearing, + carriageMassKg, + drumRadiusMeters, + minHeightMeters, + maxHeightMeters, + simulateGravity, + initialPositionMeters); + private PIDController pid = new PIDController(0, 0, 0); - private double clampedValueLowVolts = -12.0; - private double clampedValueHighVolts = 12.0; + private double positionInch = 0; + private double velocityInchesPerSecond = 0; + private double appliedVolts = 0; + private double currentAmps = 0; + private double positionSetpointInches = 0; - private boolean closedLoop = true; + @Override + public void updateInputs(IndexerIOInputs inputs) { + positionSetpointInches = pid.getSetpoint(); - private double appliedVolts = 0.0; + appliedVolts += + MathUtil.clamp( + pid.calculate(Units.metersToInches(sim.getPositionMeters()), positionSetpointInches), + -12.0, + 12); - @Override - public void configurePID(double kP, double kI, double kD) { - pid.setPID(kP, kI, kD); + sim.setInputVoltage(appliedVolts); + + positionInch = Units.metersToInches(sim.getPositionMeters()); + velocityInchesPerSecond = Units.metersToInches(sim.getVelocityMetersPerSecond()); + currentAmps = sim.getCurrentDrawAmps(); + + inputs.positionSetpointInch = positionSetpointInches; + inputs.appliedVolts = appliedVolts; + inputs.indexerPositionInch = positionInch; + inputs.indexerVelocityInchesPerSecond = velocityInchesPerSecond; + inputs.currentAmps = currentAmps; + + sim.update(SubsystemConstants.LOOP_PERIOD_SECONDS); } @Override - public void setPosition(double positionDegs, double ffVolts) { - // appliedVolts = ffVolts; - pid.setSetpoint(positionDegs); + public void runCharacterization(double volts) { + sim.setInputVoltage(volts); } @Override - public void setVoltage(double volts) { - appliedVolts = volts; - sim.setInputVoltage(volts); + public void setPositionSetpoint(double position, double ffVolts) { + appliedVolts = ffVolts; + pid.setSetpoint(position); } @Override public void stop() { appliedVolts = 0; - pid.setSetpoint(sim.getAngularPositionRad()); + pid.setSetpoint(Units.metersToInches(sim.getPositionMeters())); } @Override - public void updateInputs(IndexerIOInputs inputs) { - if (closedLoop) { - appliedVolts = - MathUtil.clamp( - pid.calculate(sim.getAngularPositionRad()), - clampedValueLowVolts, - clampedValueHighVolts); - - sim.setInputVoltage(appliedVolts); - } - - sim.update(PhysicalConstants.LOOP_PERIOD_SECS); - - inputs.positionRads = sim.getAngularPositionRad(); - inputs.velocityRadsPerSec = sim.getAngularVelocityRadPerSec(); - inputs.appliedVolts = appliedVolts; - inputs.currentAmps = sim.getCurrentDrawAmps(); + public void configurePID(double kP, double kI, double kD) { + pid.setPID(kP, kI, kD); } } diff --git a/src/main/java/frc/robot/subsystems/indexers/IndexerIOTalonFX.java b/src/main/java/frc/robot/subsystems/indexers/IndexerIOTalonFX.java index cd1bb15..2a4923a 100644 --- a/src/main/java/frc/robot/subsystems/indexers/IndexerIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/indexers/IndexerIOTalonFX.java @@ -46,22 +46,20 @@ public IndexerIOTalonFX(int motorID) { public void updateInputs(IndexerIOInputs inputs) { BaseStatusSignal.refreshAll(positionRads, velocityRadsPerSec, appliedVolts, currentAmps); - inputs.positionRads = positionRads.getValueAsDouble(); - inputs.velocityRadsPerSec = velocityRadsPerSec.getValueAsDouble(); + inputs.indexerPositionInch = positionRads.getValueAsDouble(); + inputs.indexerVelocityInchesPerSecond = velocityRadsPerSec.getValueAsDouble(); inputs.appliedVolts = appliedVolts.getValueAsDouble(); inputs.currentAmps = currentAmps.getValueAsDouble(); } @Override - public void setVoltage(double volts) { + public void runCharacterization(double volts) { talon.setControl(new VoltageOut(volts)); } @Override - public void setPosition(double positionDegs, double ffVolts) { - talon.setControl( - new PositionVoltage( - Units.degreesToRotations(positionDegs))); + public void setPositionSetpoint(double positionDegs, double ffVolts) { + talon.setControl(new PositionVoltage(Units.degreesToRotations(positionDegs))); } @Override diff --git a/src/main/java/frc/robot/subsystems/led/LED.java b/src/main/java/frc/robot/subsystems/led/LED.java index 4d40a7f..b5126b3 100644 --- a/src/main/java/frc/robot/subsystems/led/LED.java +++ b/src/main/java/frc/robot/subsystems/led/LED.java @@ -5,8 +5,7 @@ package frc.robot.subsystems.led; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.constants.PhysicalConstants.LED_STATE; - +import frc.robot.constants.SubsystemConstants.LED_STATE; import org.littletonrobotics.junction.Logger; /** Add your docs here. */ diff --git a/src/main/java/frc/robot/subsystems/led/LED_IO.java b/src/main/java/frc/robot/subsystems/led/LED_IO.java index c0b6605..6aebea4 100644 --- a/src/main/java/frc/robot/subsystems/led/LED_IO.java +++ b/src/main/java/frc/robot/subsystems/led/LED_IO.java @@ -4,10 +4,9 @@ package frc.robot.subsystems.led; +import frc.robot.constants.SubsystemConstants.LED_STATE; import org.littletonrobotics.junction.AutoLog; -import frc.robot.constants.PhysicalConstants.LED_STATE; - /** Add your docs here. */ public interface LED_IO { @AutoLog diff --git a/src/main/java/frc/robot/subsystems/led/LED_IOCANdle.java b/src/main/java/frc/robot/subsystems/led/LED_IOCANdle.java index 64a0576..a82cb38 100644 --- a/src/main/java/frc/robot/subsystems/led/LED_IOCANdle.java +++ b/src/main/java/frc/robot/subsystems/led/LED_IOCANdle.java @@ -13,8 +13,8 @@ import com.ctre.phoenix.led.StrobeAnimation; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; -import frc.robot.constants.PhysicalConstants; -import frc.robot.constants.PhysicalConstants.LED_STATE; +import frc.robot.constants.SubsystemConstants; +import frc.robot.constants.SubsystemConstants.LED_STATE; public class LED_IOCANdle implements LED_IO { LED_STATE ledState; @@ -43,7 +43,7 @@ public class LED_IOCANdle implements LED_IO { public LED_IOCANdle(int channel, String CANBUS) { // led = new Spark(channel); candle = new CANdle(channel, CANBUS); - ledState = PhysicalConstants.LED_STATE.BLUE; + ledState = SubsystemConstants.LED_STATE.BLUE; CANdleConfiguration configs = new CANdleConfiguration(); // CANdleControlFrame.CANdle_Control_1_General(0x4000); diff --git a/src/main/java/frc/robot/subsystems/led/LED_IOSim.java b/src/main/java/frc/robot/subsystems/led/LED_IOSim.java index 98a2699..d80c93b 100644 --- a/src/main/java/frc/robot/subsystems/led/LED_IOSim.java +++ b/src/main/java/frc/robot/subsystems/led/LED_IOSim.java @@ -2,14 +2,14 @@ import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; -import frc.robot.constants.PhysicalConstants; -import frc.robot.constants.PhysicalConstants.LED_STATE; +import frc.robot.constants.SubsystemConstants; +import frc.robot.constants.SubsystemConstants.LED_STATE; public class LED_IOSim implements LED_IO { LED_STATE ledState; public LED_IOSim() { - ledState = PhysicalConstants.LED_STATE.BLUE; + ledState = SubsystemConstants.LED_STATE.BLUE; setLEDState(ledState); } diff --git a/src/main/java/frc/robot/subsystems/vision/Vision.java b/src/main/java/frc/robot/subsystems/vision/Vision.java index 587abe3..5d56cd8 100644 --- a/src/main/java/frc/robot/subsystems/vision/Vision.java +++ b/src/main/java/frc/robot/subsystems/vision/Vision.java @@ -13,6 +13,8 @@ package frc.robot.subsystems.vision; +import static frc.robot.constants.VisionConstants.*; + import edu.wpi.first.math.Matrix; import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.geometry.Pose2d; @@ -24,9 +26,6 @@ import edu.wpi.first.wpilibj.Alert.AlertType; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.subsystems.vision.VisionIO.PoseObservationType; - -import static frc.robot.constants.VisionConstants.*; - import java.util.LinkedList; import java.util.List; import org.littletonrobotics.junction.Logger; diff --git a/src/main/java/frc/robot/util/Conversions.java b/src/main/java/frc/robot/util/Conversions.java index 2a123b3..c128078 100644 --- a/src/main/java/frc/robot/util/Conversions.java +++ b/src/main/java/frc/robot/util/Conversions.java @@ -176,4 +176,4 @@ public static double IPSSToMotorRPMS( double accelerationInchPerSecSec, double circumference, double gearRatio) { return accelerationInchPerSecSec / (circumference / (gearRatio)) * 60.0; } -} \ No newline at end of file +} diff --git a/vendordeps/Phoenix5-5.34.0-beta-3.json b/vendordeps/Phoenix5-5.34.0-beta-3.json new file mode 100644 index 0000000..d222a1c --- /dev/null +++ b/vendordeps/Phoenix5-5.34.0-beta-3.json @@ -0,0 +1,171 @@ +{ + "fileName": "Phoenix5-5.34.0-beta-3.json", + "name": "CTRE-Phoenix (v5)", + "version": "5.34.0-beta-3", + "frcYear": "2025", + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-beta-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-frc2025-beta-latest.json", + "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-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-frc2025-beta-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-frc2025-beta-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.34.0-beta-3" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.34.0-beta-3" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.34.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.34.0-beta-3", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.34.0-beta-3", + "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.34.0-beta-3", + "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.34.0-beta-3", + "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.34.0-beta-3", + "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.34.0-beta-3", + "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.34.0-beta-3", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index 70cdac9..440b132 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,74 +1,74 @@ { - "fileName": "REVLib.json", - "name": "REVLib", - "version": "2025.0.0-beta-3", - "frcYear": "2025", - "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", - "mavenUrls": [ - "https://maven.revrobotics.com/" - ], - "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json", - "javaDependencies": [ - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-java", - "version": "2025.0.0-beta-3" - } - ], - "jniDependencies": [ - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-driver", - "version": "2025.0.0-beta-3", - "skipInvalidPlatforms": true, - "isJar": false, - "validPlatforms": [ - "windowsx86-64", - "windowsx86", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - } - ], - "cppDependencies": [ - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-cpp", - "version": "2025.0.0-beta-3", - "libName": "REVLib", - "headerClassifier": "headers", - "sharedLibrary": false, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "windowsx86", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - }, - { - "groupId": "com.revrobotics.frc", - "artifactId": "REVLib-driver", - "version": "2025.0.0-beta-3", - "libName": "REVLibDriver", - "headerClassifier": "headers", - "sharedLibrary": false, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "windowsx86", - "linuxarm64", - "linuxx86-64", - "linuxathena", - "linuxarm32", - "osxuniversal" - ] - } - ] -} \ No newline at end of file + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2025.0.0-beta-3", + "frcYear": "2025", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2025.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2025.0.0-beta-3" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2025.0.0-beta-3", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2025.0.0-beta-3", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2025.0.0-beta-3", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +}