19 Commits

Author SHA1 Message Date
a96d96fecb Merge branch 'main' into kraken_swerve 2025-01-20 20:12:40 -05:00
edb95da65c Merge branch 'main' of https://git.coldlightalchemist.com/Team_2648/2025_Robot_Code 2025-01-20 20:02:53 -05:00
b90056f9ce Adding basic PathPlanner setup 2025-01-20 20:02:51 -05:00
ce7246114f Added lots of comments, also added a few simple methods as backup 2025-01-21 00:58:38 +00:00
198d105741 Adding AHRS from Studica to the drivetrain so the NavX is assumed to be used, also cleaned up some unused imports 2025-01-20 19:33:33 -05:00
8cbd9bb095 Kraken swerve based on Tyler's original work 2025-01-18 16:04:54 -05:00
4d9aa82520 Adding ArmSysID and some more configuration stuff 2025-01-18 15:00:53 -05:00
c1dddcace5 Resolving some issues related to the use of the CANcoder, and added some missing constants and instantiations for PIDControllers related to the Arm 2025-01-18 12:57:02 -05:00
ecf4916b93 Upgrading to 2025.2.1 2025-01-18 11:12:48 -05:00
91cd13f87a did small amounts of stuff. can't remember 2025-01-18 15:47:18 +00:00
5325920b42 Adjusting moveManipulator so it's not so...rough 2025-01-16 17:59:12 -05:00
d1d577f52f fixed a terrible formatting error 2025-01-16 19:52:38 +00:00
11a191440c added a smooth manipulator translation method 2025-01-16 19:46:20 +00:00
f4cfd2874b began adding elevator and arm methods 2025-01-16 15:26:54 +00:00
f391d1540b One more fix to resolve Noah's merge conflict for him 2025-01-15 02:24:19 +00:00
5f111cd4ee Still resolving merge conflict 2025-01-15 02:21:48 +00:00
adb17f9cea Merge branch 'main' of https://git.coldlightalchemist.com/Team_2648/2025_Robot_Code 2025-01-15 02:21:24 +00:00
afba8731b3 added a few manual controls for arm and elevator 2025-01-15 02:04:25 +00:00
865ba29152 minor subsystem changes 2025-01-13 13:42:48 +00:00
24 changed files with 1144 additions and 443 deletions

View File

@@ -1,6 +1,6 @@
plugins { plugins {
id "java" id "java"
id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1" id "edu.wpi.first.GradleRIO" version "2025.2.1"
} }
java { java {
@@ -33,6 +33,8 @@ deploy {
frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) {
files = project.fileTree('src/main/deploy') files = project.fileTree('src/main/deploy')
directory = '/home/lvuser/deploy' directory = '/home/lvuser/deploy'
deleteOldFiles = false // Change to true to delete files on roboRIO that no
// longer exist in deploy directory of this project
} }
} }
} }

View File

@@ -1,6 +1,6 @@
distributionBase=GRADLE_USER_HOME distributionBase=GRADLE_USER_HOME
distributionPath=permwrapper/dists distributionPath=permwrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-8.10.2-bin.zip distributionUrl=https\://services.gradle.org/distributions/gradle-8.11-bin.zip
networkTimeout=10000 networkTimeout=10000
validateDistributionUrl=true validateDistributionUrl=true
zipStoreBase=GRADLE_USER_HOME zipStoreBase=GRADLE_USER_HOME

View File

@@ -20,8 +20,8 @@ pluginManagement {
} }
def frcHomeMaven = new File(frcHome, 'maven') def frcHomeMaven = new File(frcHome, 'maven')
maven { maven {
name 'frcHome' name = 'frcHome'
url frcHomeMaven url = frcHomeMaven
} }
} }
} }

View File

@@ -4,6 +4,8 @@
package frc.robot; package frc.robot;
import frc.robot.constants.ArmConstants;
import frc.robot.constants.ElevatorConstants;
import frc.robot.constants.OIConstants; import frc.robot.constants.OIConstants;
import frc.robot.subsystems.Arm; import frc.robot.subsystems.Arm;
import frc.robot.subsystems.ClimberPivot; import frc.robot.subsystems.ClimberPivot;
@@ -12,8 +14,16 @@ import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.Elevator; import frc.robot.subsystems.Elevator;
import frc.robot.subsystems.Indexer; import frc.robot.subsystems.Indexer;
import frc.robot.subsystems.Manipulator; import frc.robot.subsystems.Manipulator;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.PrintCommand; import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
public class RobotContainer { public class RobotContainer {
@@ -34,6 +44,8 @@ public class RobotContainer {
private CommandXboxController driver; private CommandXboxController driver;
private CommandXboxController operator; private CommandXboxController operator;
private SendableChooser<Command> autoChooser;
public RobotContainer() { public RobotContainer() {
arm = new Arm(); arm = new Arm();
@@ -52,7 +64,13 @@ public class RobotContainer {
driver = new CommandXboxController(OIConstants.kDriverControllerPort); driver = new CommandXboxController(OIConstants.kDriverControllerPort);
operator = new CommandXboxController(OIConstants.kOperatorControllerPort); operator = new CommandXboxController(OIConstants.kOperatorControllerPort);
autoChooser = AutoBuilder.buildAutoChooser();
configureButtonBindings(); configureButtonBindings();
configureNamedCommands();
configureShuffleboard();
} }
private void configureButtonBindings() { private void configureButtonBindings() {
@@ -61,7 +79,7 @@ public class RobotContainer {
); );
climberPivot.setDefaultCommand( climberPivot.setDefaultCommand(
climberPivot.goToAngle(0) climberPivot.goToAngle(0, 1)
); );
climberRollers.setDefaultCommand( climberRollers.setDefaultCommand(
@@ -78,7 +96,7 @@ public class RobotContainer {
); );
elevator.setDefaultCommand( elevator.setDefaultCommand(
elevator.goToSetpoint(0, 1) elevator.runAssistedElevator(operator::getLeftY)
); );
indexer.setDefaultCommand( indexer.setDefaultCommand(
@@ -100,23 +118,140 @@ public class RobotContainer {
//Operator inputs //Operator inputs
operator.povUp().onTrue( operator.povUp().onTrue(
elevator.goToSetpoint(0, 0) moveManipulator(
ElevatorConstants.kElevatorL4Position,
ArmConstants.kArmL4Position
)
); );
operator.povRight().onTrue( operator.povRight().onTrue(
elevator.goToSetpoint(0, 0) moveManipulator(
ElevatorConstants.kElevatorL3Position,
ArmConstants.kArmL3Position
)
); );
operator.povLeft().onTrue( operator.povLeft().onTrue(
elevator.goToSetpoint(0, 0) moveManipulator(
ElevatorConstants.kElevatorL2Position,
ArmConstants.kArmL2Position
)
); );
operator.povDown().onTrue( operator.povDown().onTrue(
elevator.goToSetpoint(0, 0) moveManipulator(
ElevatorConstants.kElevatorL1Position,
ArmConstants.kArmL1Position
)
);
operator.a().onTrue(
coralIntakeRoutine()
);
operator.x().onTrue(
algaeIntakeRoutine(true)
);
operator.b().onTrue(
algaeIntakeRoutine(false)
); );
} }
private void configureNamedCommands() {
NamedCommands.registerCommand("Drivetrain Set X", drivetrain.setXCommand());
}
//creates tabs and transforms them on the shuffleboard
private void configureShuffleboard() {
ShuffleboardTab autoTab = Shuffleboard.getTab(OIConstants.kAutoTab);
ShuffleboardTab sensorTab = Shuffleboard.getTab(OIConstants.kSensorsTab);
Shuffleboard.selectTab(OIConstants.kAutoTab);
autoTab.add("Auto Selection", autoChooser)
.withSize(2, 1)
.withPosition(0, 0)
.withWidget(BuiltInWidgets.kComboBoxChooser);
sensorTab.addDouble("ElevatorPosition", elevator::getEncoderPosition)
.withSize(2, 1)
.withPosition(0, 0)
.withWidget(BuiltInWidgets.kTextView);
sensorTab.addDouble("ArmPosition", arm::getEncoderPosition)
.withSize(2, 1)
.withPosition(2, 0)
.withWidget(BuiltInWidgets.kTextView);
}
public Command getAutonomousCommand() { public Command getAutonomousCommand() {
return new PrintCommand("NO AUTO DEFINED"); return autoChooser.getSelected();
}
//teleop routines
private Command coralIntakeRoutine() {
return moveManipulator(
ElevatorConstants.kElevatorCoralIntakePosition,
ArmConstants.kArmCoralIntakePosition
)
.andThen(manipulator.runUntilCollected(1, true));
}
private Command algaeIntakeRoutine(boolean l2) {
return moveManipulator(
l2 ? ElevatorConstants.kElevatorL2AlgaePosition : ElevatorConstants.kElevatorL3AlgaePosition,
l2 ? ArmConstants.kArmL2AlgaePosition : ArmConstants.kArmL3AlgaePosition
)
.andThen(manipulator.runUntilCollected(1, false));
}
private Command moveManipulator(double elevatorPosition, double armPosition) {
// If the elevator current and target positions are above the brace, or the arm current and target position is in
// front of the brace, move together
if ((elevator.isMotionSafe() && elevator.isMotionSafe(elevatorPosition)) || (arm.isMotionSafe() && arm.isMotionSafe(armPosition))) {
return moveManipulatorUtil(elevatorPosition, armPosition, false, false);
// If the target position is behind the brace, and the arm is not behind the brace, move the arm to a safe position first,
// then the elevator, then the arm again
} else if (!arm.isMotionSafe(armPosition) && !arm.isMotionSafe()) {
return moveManipulatorUtil(elevatorPosition, ArmConstants.kArmSafeStowPosition, false, true)
.andThen(arm.goToSetpoint(armPosition, 2));
// If the target position is behind the brace, and the arm is behind the brace, move the elevator first, then the arm
} else if (!arm.isMotionSafe(armPosition) && arm.isMotionSafe()) {
return moveManipulatorUtil(elevatorPosition, armPosition, true, true);
// If the arm is behind the brace, move the arm first, then the elevator
} else if (!arm.isMotionSafe()) {
return moveManipulatorUtil(elevatorPosition, armPosition, false, true);
// Catch all command that's safe regardless of arm and elevator positions
} else {
return moveManipulatorUtil(elevatorPosition, ArmConstants.kArmSafeStowPosition, false, true)
.andThen(arm.goToSetpoint(armPosition, 2));
}
}
private Command moveManipulatorUtil(double elevatorPosition, double armPosition, boolean elevatorFirst, boolean sequential) {
return Commands.either(
Commands.either(
elevator.goToSetpoint(elevatorPosition, 2).andThen(arm.goToSetpoint(armPosition, 2)),
elevator.goToSetpoint(elevatorPosition, 2).alongWith(arm.goToSetpoint(armPosition, 2)),
() -> sequential
),
Commands.either(
arm.goToSetpoint(armPosition, 2).andThen(elevator.goToSetpoint(elevatorPosition, 2)),
arm.goToSetpoint(armPosition, 2).alongWith(elevator.goToSetpoint(elevatorPosition, 2)),
() -> sequential
),
() -> elevatorFirst
);
}
/*
* A moveManipulator method that will guarantee a safe movement.
* Here in case we need want to skip moveManipulator debugging
*/
@SuppressWarnings("unused")
private Command safeMoveManipulator(double elevatorPosition, double armPosition) {
return moveManipulatorUtil(elevatorPosition, ArmConstants.kArmSafeStowPosition, false, true)
.andThen(arm.goToSetpoint(armPosition, 2));
} }
} }

View File

@@ -1,8 +1,79 @@
package frc.robot.constants; package frc.robot.constants;
import static edu.wpi.first.units.Units.Volts;
import static edu.wpi.first.units.Units.Second;
import static edu.wpi.first.units.Units.Seconds;
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.signals.SensorDirectionValue;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
public class ArmConstants { public class ArmConstants {
public static final int kArmMotorID = 0; public static final int kArmMotorID = 0;
public static final int kCANcoderID = 0; public static final int kCANcoderID = 0;
public static final double kEncoderConversionFactor = 0; public static final int kMotorAmpsMax = 0;
public static final double kArmMaxVelocity = 0;
public static final double kPositionalP = 0;
public static final double kPositionalI = 0;
public static final double kPositionalD = 0;
public static final double kPositionalTolerance = Units.degreesToRadians(1);
public static final double kVelocityP = 0;
public static final double kVelocityI = 0;
public static final double kVelocityD = 0;
// TODO Is this reasonable?
public static final double kVelocityTolerance = Units.degreesToRadians(3) / 60;
public static final double kArmCoralIntakePosition = 0;
public static final double kArmL1Position = 0;
public static final double kArmL2Position = 0;
public static final double kArmL3Position = 0;
public static final double kArmL4Position = 0;
public static final double kArmL2AlgaePosition = 0;
public static final double kArmL3AlgaePosition = 0;
public static final double kArmSafeStowPosition = 0;
public static final double kMagnetOffset = 0.0;
public static final double kAbsoluteSensorDiscontinuityPoint = 0.0;
public static final double kSysIDRampRate = 1;
public static final double kSysIDStepVolts = 7;
public static final double kSysIDTimeout = 10;
public static final SensorDirectionValue kSensorDirection = SensorDirectionValue.CounterClockwise_Positive;
public static final IdleMode kIdleMode = IdleMode.kBrake;
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A NEW CONFIG
public static final SysIdRoutine.Config kSysIDConfig = new Config(
Volts.of(kSysIDRampRate).per(Second),
Volts.of(kSysIDStepVolts),
Seconds.of(kSysIDTimeout)
);
public static final CANcoderConfiguration canCoderConfig = new CANcoderConfiguration();
public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
static {
canCoderConfig.MagnetSensor.SensorDirection = SensorDirectionValue.CounterClockwise_Positive;
canCoderConfig.MagnetSensor.MagnetOffset = 0.0;
// TODO Need to do more reading on this setting, and how to properly offset the Arm so that horizontal is 0
//canCoderConfig.MagnetSensor.AbsoluteSensorDiscontinuityPoint = 0.5;
motorConfig
.smartCurrentLimit(kMotorAmpsMax)
.idleMode(kIdleMode);
}
} }

View File

@@ -1,5 +1,13 @@
package frc.robot.constants; package frc.robot.constants;
import java.io.IOException;
import org.json.simple.parser.ParseException;
import com.pathplanner.lib.config.PIDConstants;
import com.pathplanner.lib.config.RobotConfig;
import com.pathplanner.lib.controllers.PPHolonomicDriveController;
import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.math.trajectory.TrapezoidProfile;
public class AutoConstants { public class AutoConstants {
@@ -15,4 +23,21 @@ public class AutoConstants {
// Constraint for the motion profiled robot angle controller // Constraint for the motion profiled robot angle controller
public static final TrapezoidProfile.Constraints kThetaControllerConstraints = new TrapezoidProfile.Constraints( public static final TrapezoidProfile.Constraints kThetaControllerConstraints = new TrapezoidProfile.Constraints(
kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared); kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
// TODO This is a constant being managed like a static rewriteable variable
public static RobotConfig kRobotConfig;
public static final PPHolonomicDriveController kPPDriveController = new PPHolonomicDriveController(
new PIDConstants(kPXController, 0, 0),
new PIDConstants(kPYController, 0, 0)
);
static {
try {
kRobotConfig = RobotConfig.fromGUISettings();
} catch (IOException | ParseException e) {
System.err.println("FAILED TO READ ROBOTCONFIG, WAS THE CONFIG SET UP IN PATHPLANNER?");
e.printStackTrace();
}
}
} }

View File

@@ -11,20 +11,40 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
public class ElevatorConstants { public class ElevatorConstants {
public static final int kElevatorMotorID = 0; public static final int kElevatorMotor1ID = 0;
public static final int kElevatorMotor2ID = 0;
public static final int kTopLimitSwitchID = 0;
public static final int kBottomLimitSwitchID = 0;
public static final double kEncoderConversionFactor = 0; public static final double kEncoderConversionFactor = 0;
public static final int kMotorAmpsMax = 0; public static final int kMotorAmpsMax = 0;
public static final double kPIDControllerP = 0; public static final double kPositionControllerP = 0;
public static final double kPIDControllerI = 0; public static final double kPositionControllerI = 0;
public static final double kPIDControllerD = 0; public static final double kPositionControllerD = 0;
public static final double kVelocityControllerP = 0;
public static final double kVelocityControllerI = 0;
public static final double kVelocityControllerD = 0;
public static final double kFeedForwardS = 0; public static final double kFeedForwardS = 0;
public static final double kFeedForwardG = 0; public static final double kFeedForwardG = 0;
public static final double kFeedForwardV = 0; public static final double kFeedForwardV = 0;
public static final double kElevatorMaxVelocity = 0;
public static final double kElevatorCoralIntakePosition = 0;
public static final double kElevatorL1Position = 0;
public static final double kElevatorL2Position = 0;
public static final double kElevatorL3Position = 0;
public static final double kElevatorL4Position = 0;
public static final double kElevatorL2AlgaePosition = 0;
public static final double kElevatorL3AlgaePosition = 0;
public static final double kElevatorBracePosition = 0;
public static final double kElevatorMaxHeight = 0;
// 1, 7, 10 are the defaults for these, change as necessary // 1, 7, 10 are the defaults for these, change as necessary
public static final double kSysIDRampRate = 1; public static final double kSysIDRampRate = 1;
public static final double kSysIDStepVolts = 7; public static final double kSysIDStepVolts = 7;

View File

@@ -2,6 +2,12 @@ package frc.robot.constants;
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor; import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode; import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.FeedbackConfigs;
import com.ctre.phoenix6.configs.MotorOutputConfigs;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.revrobotics.spark.config.SparkMaxConfig; import com.revrobotics.spark.config.SparkMaxConfig;
public class ModuleConstants { public class ModuleConstants {
@@ -20,52 +26,73 @@ public class ModuleConstants {
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters) public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
/ kDrivingMotorReduction; / kDrivingMotorReduction;
public static final int kDriveMotorCurrentLimit = 40; public static final double kDrivingFactor = kWheelDiameterMeters * Math.PI / kDrivingMotorReduction;
public static final double kTurningFactor = 2 * Math.PI;
public static final double kDrivingVelocityFeedForward = 1 / kDriveWheelFreeSpeedRps;
public static final double kDriveP = .04;
public static final double kDriveI = 0;
public static final double kDriveD = 0;
public static final double kDriveS = 0;
public static final double kDriveV = kDrivingVelocityFeedForward;
public static final double kDriveA = 0;
public static final double kTurnP = 1;
public static final double kTurnI = 0;
public static final double kTurnD = 0;
public static final int kDriveMotorStatorCurrentLimit = 120;
public static final int kTurnMotorCurrentLimit = 20; public static final int kTurnMotorCurrentLimit = 20;
public static final IdleMode kTurnIdleMode = IdleMode.kBrake;
public static final InvertedValue kDriveInversionState = InvertedValue.Clockwise_Positive;
public static final NeutralModeValue kDriveIdleMode = NeutralModeValue.Brake;
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A NEW CONFIGURATION ITEM // YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A NEW CONFIGURATION ITEM
public static final SparkMaxConfig drivingConfig = new SparkMaxConfig();
public static final SparkMaxConfig turningConfig = new SparkMaxConfig(); public static final SparkMaxConfig turningConfig = new SparkMaxConfig();
static { public static final FeedbackConfigs kDriveFeedConfig = new FeedbackConfigs();
// Use module constants to calculate conversion factors and feed forward gain. public static final CurrentLimitsConfigs kDriveCurrentLimitConfig = new CurrentLimitsConfigs();
double drivingFactor = kWheelDiameterMeters * Math.PI / kDrivingMotorReduction; public static final MotorOutputConfigs kDriveMotorConfig = new MotorOutputConfigs();
double turningFactor = 2 * Math.PI; public static final Slot0Configs kDriveSlot0Config = new Slot0Configs();
double drivingVelocityFeedForward = 1 / kDriveWheelFreeSpeedRps;
drivingConfig static {
.idleMode(IdleMode.kBrake) kDriveFeedConfig.SensorToMechanismRatio = kDrivingMotorReduction;
.smartCurrentLimit(kDriveMotorCurrentLimit);
drivingConfig.encoder kDriveCurrentLimitConfig.StatorCurrentLimitEnable = true;
.positionConversionFactor(drivingFactor) // meters kDriveCurrentLimitConfig.StatorCurrentLimit = kDriveMotorStatorCurrentLimit;
.velocityConversionFactor(drivingFactor / 60.0); // meters per second
drivingConfig.closedLoop kDriveMotorConfig.Inverted = kDriveInversionState;
.feedbackSensor(FeedbackSensor.kPrimaryEncoder) kDriveMotorConfig.NeutralMode = kDriveIdleMode;
// These are example gains you may need to them for your own robot!
.pid(0.04, 0, 0) kDriveSlot0Config.kP = kDriveP;
.velocityFF(drivingVelocityFeedForward) kDriveSlot0Config.kI = kDriveI;
.outputRange(-1, 1); kDriveSlot0Config.kD = kDriveD;
kDriveSlot0Config.kS = kDriveS;
kDriveSlot0Config.kV = kDriveV;
kDriveSlot0Config.kA = kDriveA;
turningConfig turningConfig
.idleMode(IdleMode.kBrake) .idleMode(kTurnIdleMode)
.smartCurrentLimit(20); .smartCurrentLimit(kTurnMotorCurrentLimit);
turningConfig.absoluteEncoder turningConfig.absoluteEncoder
// Invert the turning encoder, since the output shaft rotates in the opposite // Invert the turning encoder, since the output shaft rotates in the opposite
// direction of the steering motor in the MAXSwerve Module. // direction of the steering motor in the MAXSwerve Module.
.inverted(true) .inverted(true)
.positionConversionFactor(turningFactor) // radians .positionConversionFactor(kTurningFactor) // radians
.velocityConversionFactor(turningFactor / 60.0); // radians per second .velocityConversionFactor(kTurningFactor / 60.0); // radians per second
turningConfig.closedLoop turningConfig.closedLoop
.feedbackSensor(FeedbackSensor.kAbsoluteEncoder) .feedbackSensor(FeedbackSensor.kAbsoluteEncoder)
// These are example gains you may need to them for your own robot! // These are example gains you may need to them for your own robot!
.pid(1, 0, 0) .pid(kTurnP, kTurnI, kTurnD)
.outputRange(-1, 1) .outputRange(-1, 1)
// Enable PID wrap around for the turning motor. This will allow the PID // Enable PID wrap around for the turning motor. This will allow the PID
// controller to go through 0 to get to the setpoint i.e. going from 350 degrees // controller to go through 0 to get to the setpoint i.e. going from 350 degrees
// to 10 degrees will go through 0 rather than the other direction which is a // to 10 degrees will go through 0 rather than the other direction which is a
// longer route. // longer route.
.positionWrappingEnabled(true) .positionWrappingEnabled(true)
.positionWrappingInputRange(0, turningFactor); .positionWrappingInputRange(0, kTurningFactor);
} }
} }

View File

@@ -5,4 +5,7 @@ public class OIConstants {
public static final int kOperatorControllerPort = 1; public static final int kOperatorControllerPort = 1;
public static final double kDriveDeadband = 0.05; public static final double kDriveDeadband = 0.05;
public static final String kAutoTab = "Auto Tab";
public static final String kSensorsTab = "Sensors Tab";
} }

View File

@@ -1,43 +1,117 @@
package frc.robot.subsystems; package frc.robot.subsystems;
import java.util.function.DoubleSupplier;
import com.ctre.phoenix6.hardware.CANcoder; import com.ctre.phoenix6.hardware.CANcoder;
import com.revrobotics.spark.SparkMax; import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType; import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.math.controller.ArmFeedforward; import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ArmConstants; import frc.robot.constants.ArmConstants;
public class Arm extends SubsystemBase { public class Arm extends SubsystemBase {
private SparkMax ArmMotor; protected SparkMax armMotor;
private CANcoder canCoder; private CANcoder canCoder;
private PIDController pidController; private PIDController positionController;
private PIDController velocityController;
private ArmFeedforward feedForward; private ArmFeedforward feedForward;
public Arm() { public Arm() {
ArmMotor = new SparkMax( armMotor = new SparkMax(
ArmConstants.kArmMotorID, ArmConstants.kArmMotorID,
MotorType.kBrushless MotorType.kBrushless
); );
armMotor.configure(ArmConstants.motorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
positionController = new PIDController(
ArmConstants.kPositionalP,
ArmConstants.kPositionalI,
ArmConstants.kPositionalD
);
// TODO: Generate constants for continuous input range based on CANcoder configuration?
positionController.enableContinuousInput(Units.degreesToRadians(-180), Units.degreesToRadians(179));
positionController.setTolerance(ArmConstants.kPositionalTolerance);
velocityController = new PIDController(
ArmConstants.kVelocityP,
ArmConstants.kVelocityI,
ArmConstants.kVelocityD
);
velocityController.setTolerance(ArmConstants.kVelocityTolerance);
canCoder = new CANcoder(ArmConstants.kCANcoderID); canCoder = new CANcoder(ArmConstants.kCANcoderID);
canCoder.getConfigurator().apply(ArmConstants.canCoderConfig);
}
/**
* Returns whether or not the motion is safe relative to the encoder's current position
* and the arm safe stow position
*
* @return Is the motion safe
*/
public boolean isMotionSafe() {
return isMotionSafe(getEncoderPosition());
}
/**
* Returns whether or not the motion is safe relative to some target position and the
* arm safe stow position
*
* @param motionTarget The target position to determine the safety of
* @return Is the motion safe
*/
public boolean isMotionSafe(double motionTarget) {
return motionTarget > ArmConstants.kArmSafeStowPosition;
}
//manual command that keeps ouput speed consistent no matter the direction
public Command runArm(DoubleSupplier speed) {
return run(() -> {
double realSpeedTarget = speed.getAsDouble() * ArmConstants.kArmMaxVelocity;
double voltsOut = velocityController.calculate(
getEncoderVelocity(),
realSpeedTarget
) + feedForward.calculate(
getEncoderPosition(),
getEncoderVelocity()
);
armMotor.setVoltage(voltsOut);
});
} }
public Command goToSetpoint(double setpoint, double timeout) { public Command goToSetpoint(double setpoint, double timeout) {
return run(() -> { return run(() -> {
double voltsOut = pidController.calculate( double voltsOut = positionController.calculate(
canCoder.getPosition().getValueAsDouble(), getEncoderPosition(),
setpoint setpoint
) + feedForward.calculate( ) + feedForward.calculate(
canCoder.getPosition().getValueAsDouble(), getEncoderPosition(),
canCoder.getVelocity().getValueAsDouble() getEncoderVelocity()
); );
ArmMotor.setVoltage(voltsOut); armMotor.setVoltage(voltsOut);
}).until(pidController::atSetpoint).withTimeout(timeout); }).until(positionController::atSetpoint).withTimeout(timeout);
}
public double getEncoderPosition() {
return Units.rotationsToRadians(canCoder.getAbsolutePosition().getValueAsDouble());
}
public double getEncoderVelocity() {
return Units.rotationsToRadians(canCoder.getVelocity().getValueAsDouble());
} }
} }

View File

@@ -1,6 +1,6 @@
package frc.robot.subsystems; package frc.robot.subsystems;
import com.revrobotics.AbsoluteEncoder; import com.revrobotics.RelativeEncoder;
import com.revrobotics.spark.SparkMax; import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkLowLevel.MotorType; import com.revrobotics.spark.SparkLowLevel.MotorType;
@@ -13,7 +13,7 @@ import frc.robot.constants.ClimberPivotConstants;
public class ClimberPivot extends SubsystemBase { public class ClimberPivot extends SubsystemBase {
private SparkMax pivotMotor; private SparkMax pivotMotor;
private AbsoluteEncoder neoEncoder; private RelativeEncoder neoEncoder;
private DigitalInput cageLimitSwitch; private DigitalInput cageLimitSwitch;
@@ -25,9 +25,9 @@ public class ClimberPivot extends SubsystemBase {
MotorType.kBrushless MotorType.kBrushless
); );
neoEncoder = pivotMotor.getAbsoluteEncoder(); neoEncoder = pivotMotor.getEncoder();
cageLimitSwitch = new DigitalInput(0); cageLimitSwitch = new DigitalInput(ClimberPivotConstants.kClimberLimitSwitchID);
pidController = new PIDController( pidController = new PIDController(
ClimberPivotConstants.kPIDControllerP, ClimberPivotConstants.kPIDControllerP,
@@ -42,7 +42,7 @@ public class ClimberPivot extends SubsystemBase {
}); });
} }
public Command goToAngle(double setpoint) { public Command goToAngle(double setpoint, double timeout) {
return run(() -> { return run(() -> {
pivotMotor.set( pivotMotor.set(
pidController.calculate( pidController.calculate(
@@ -50,7 +50,7 @@ public class ClimberPivot extends SubsystemBase {
setpoint setpoint
) )
); );
}); }).withTimeout(timeout);
} }
public boolean getCageLimitSwitch() { public boolean getCageLimitSwitch() {

View File

@@ -4,9 +4,14 @@
package frc.robot.subsystems; package frc.robot.subsystems;
import java.util.Optional;
import java.util.function.BooleanSupplier; import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier; import java.util.function.DoubleSupplier;
import com.pathplanner.lib.auto.AutoBuilder;
import com.studica.frc.AHRS;
import com.studica.frc.AHRS.NavXComType;
import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Rotation2d;
@@ -15,10 +20,10 @@ import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveDriveOdometry; import edu.wpi.first.math.kinematics.SwerveDriveOdometry;
import edu.wpi.first.math.kinematics.SwerveModulePosition; import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState; import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.ADIS16470_IMU; import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.ADIS16470_IMU.IMUAxis;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.AutoConstants;
import frc.robot.constants.DrivetrainConstants; import frc.robot.constants.DrivetrainConstants;
import frc.robot.constants.OIConstants; import frc.robot.constants.OIConstants;
@@ -30,7 +35,7 @@ public class Drivetrain extends SubsystemBase {
protected MAXSwerveModule m_rearRight; protected MAXSwerveModule m_rearRight;
// The gyro sensor // The gyro sensor
private ADIS16470_IMU m_gyro; private AHRS ahrs;
// Odometry class for tracking robot pose // Odometry class for tracking robot pose
private SwerveDriveOdometry m_odometry; private SwerveDriveOdometry m_odometry;
@@ -61,11 +66,41 @@ public class Drivetrain extends SubsystemBase {
DrivetrainConstants.kBackRightChassisAngularOffset DrivetrainConstants.kBackRightChassisAngularOffset
); );
m_gyro = new ADIS16470_IMU(); ahrs = new AHRS(NavXComType.kMXP_SPI);
m_odometry = new SwerveDriveOdometry( m_odometry = new SwerveDriveOdometry(
DrivetrainConstants.kDriveKinematics, DrivetrainConstants.kDriveKinematics,
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)), Rotation2d.fromDegrees(ahrs.getAngle()),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
m_rearLeft.getPosition(),
m_rearRight.getPosition()
});
AutoBuilder.configure(
this::getPose,
this::resetOdometry,
this::getCurrentChassisSpeeds,
this::driveWithChassisSpeeds,
AutoConstants.kPPDriveController,
AutoConstants.kRobotConfig,
() -> {
Optional<DriverStation.Alliance> alliance = DriverStation.getAlliance();
if (alliance.isPresent()) {
return alliance.get() == DriverStation.Alliance.Red;
}
return false;
},
this
);
}
@Override
public void periodic() {
// Update the odometry in the periodic block
m_odometry.update(
Rotation2d.fromDegrees(getGyroValue()),
new SwerveModulePosition[] { new SwerveModulePosition[] {
m_frontLeft.getPosition(), m_frontLeft.getPosition(),
m_frontRight.getPosition(), m_frontRight.getPosition(),
@@ -74,17 +109,21 @@ public class Drivetrain extends SubsystemBase {
}); });
} }
@Override public ChassisSpeeds getCurrentChassisSpeeds() {
public void periodic() { return DrivetrainConstants.kDriveKinematics.toChassisSpeeds(
// Update the odometry in the periodic block m_frontLeft.getState(),
m_odometry.update( m_frontRight.getState(),
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)), m_rearLeft.getState(),
new SwerveModulePosition[] { m_rearRight.getState()
m_frontLeft.getPosition(), );
m_frontRight.getPosition(), }
m_rearLeft.getPosition(),
m_rearRight.getPosition() public void driveWithChassisSpeeds(ChassisSpeeds speeds) {
}); ChassisSpeeds discreteSpeeds = ChassisSpeeds.discretize(speeds, 0.2);
SwerveModuleState[] newStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(discreteSpeeds);
SwerveDriveKinematics.desaturateWheelSpeeds(newStates, DrivetrainConstants.kMaxSpeedMetersPerSecond);
setModuleStates(newStates);
} }
/** /**
@@ -103,7 +142,7 @@ public class Drivetrain extends SubsystemBase {
*/ */
public void resetOdometry(Pose2d pose) { public void resetOdometry(Pose2d pose) {
m_odometry.resetPosition( m_odometry.resetPosition(
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)), Rotation2d.fromDegrees(getGyroValue()),
new SwerveModulePosition[] { new SwerveModulePosition[] {
m_frontLeft.getPosition(), m_frontLeft.getPosition(),
m_frontRight.getPosition(), m_frontRight.getPosition(),
@@ -144,7 +183,7 @@ public class Drivetrain extends SubsystemBase {
var swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates( var swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(
fieldRelative fieldRelative
? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered, ? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered,
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ))) Rotation2d.fromDegrees(getGyroValue()))
: new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered)); : new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered));
SwerveDriveKinematics.desaturateWheelSpeeds( SwerveDriveKinematics.desaturateWheelSpeeds(
swerveModuleStates, DrivetrainConstants.kMaxSpeedMetersPerSecond); swerveModuleStates, DrivetrainConstants.kMaxSpeedMetersPerSecond);
@@ -194,7 +233,11 @@ public class Drivetrain extends SubsystemBase {
/** Zeroes the heading of the robot. */ /** Zeroes the heading of the robot. */
public void zeroHeading() { public void zeroHeading() {
m_gyro.reset(); ahrs.reset();;
}
public double getGyroValue() {
return ahrs.getAngle() * (DrivetrainConstants.kGyroReversed ? -1 : 1);
} }
/** /**
@@ -203,7 +246,7 @@ public class Drivetrain extends SubsystemBase {
* @return the robot's heading in degrees, from -180 to 180 * @return the robot's heading in degrees, from -180 to 180
*/ */
public double getHeading() { public double getHeading() {
return Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)).getDegrees(); return Rotation2d.fromDegrees(getGyroValue()).getDegrees();
} }
/** /**
@@ -212,6 +255,6 @@ public class Drivetrain extends SubsystemBase {
* @return The turn rate of the robot, in degrees per second * @return The turn rate of the robot, in degrees per second
*/ */
public double getTurnRate() { public double getTurnRate() {
return m_gyro.getRate(IMUAxis.kZ) * (DrivetrainConstants.kGyroReversed ? -1.0 : 1.0); return ahrs.getRate() * (DrivetrainConstants.kGyroReversed ? -1.0 : 1.0);
} }
} }

View File

@@ -1,5 +1,7 @@
package frc.robot.subsystems; package frc.robot.subsystems;
import java.util.function.DoubleSupplier;
import com.revrobotics.RelativeEncoder; import com.revrobotics.RelativeEncoder;
import com.revrobotics.spark.SparkMax; import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.PersistMode; import com.revrobotics.spark.SparkBase.PersistMode;
@@ -8,22 +10,32 @@ import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.math.controller.ElevatorFeedforward; import edu.wpi.first.math.controller.ElevatorFeedforward;
import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ElevatorConstants; import frc.robot.constants.ElevatorConstants;
public class Elevator extends SubsystemBase { public class Elevator extends SubsystemBase {
protected SparkMax elevatorMotor1; protected SparkMax elevatorMotor1;
protected SparkMax elevatorMotor2;
protected RelativeEncoder encoder; protected RelativeEncoder encoder;
private PIDController pidController; private DigitalInput bottomLimitSwitch;
private PIDController positionController;
private PIDController velocityController;
private ElevatorFeedforward feedForward; private ElevatorFeedforward feedForward;
public Elevator() { public Elevator() {
elevatorMotor1 = new SparkMax( elevatorMotor1 = new SparkMax(
ElevatorConstants.kElevatorMotorID, ElevatorConstants.kElevatorMotor1ID,
MotorType.kBrushless
);
elevatorMotor2 = new SparkMax(
ElevatorConstants.kElevatorMotor2ID,
MotorType.kBrushless MotorType.kBrushless
); );
@@ -33,12 +45,28 @@ public class Elevator extends SubsystemBase {
PersistMode.kPersistParameters PersistMode.kPersistParameters
); );
elevatorMotor2.configure(
ElevatorConstants.motorConfig.follow(ElevatorConstants.kElevatorMotor1ID),
ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters
);
encoder = elevatorMotor1.getEncoder(); encoder = elevatorMotor1.getEncoder();
pidController = new PIDController( bottomLimitSwitch = new DigitalInput(
ElevatorConstants.kPIDControllerP, ElevatorConstants.kBottomLimitSwitchID
ElevatorConstants.kPIDControllerI, );
ElevatorConstants.kPIDControllerD
positionController = new PIDController(
ElevatorConstants.kPositionControllerP,
ElevatorConstants.kPositionControllerI,
ElevatorConstants.kPositionControllerD
);
velocityController = new PIDController(
ElevatorConstants.kVelocityControllerP,
ElevatorConstants.kVelocityControllerI,
ElevatorConstants.kVelocityControllerD
); );
feedForward = new ElevatorFeedforward( feedForward = new ElevatorFeedforward(
@@ -48,20 +76,94 @@ public class Elevator extends SubsystemBase {
); );
} }
public Command runElevator(double speed) { /**
* Returns whether or not the motion is safe relative to the encoder's current position
* and the elevator brace position
*
* @return Is the motion safe
*/
public boolean isMotionSafe() {
return isMotionSafe(getEncoderPosition());
}
/**
* Returns whether or not the motion is safe relative to some target position and the elevator
* brace position
*
* @param motionTarget The target position to determine the safety of
* @return Is the motion safe
*/
public boolean isMotionSafe(double motionTarget) {
return motionTarget > ElevatorConstants.kElevatorBracePosition;
}
/**
* A manual translation command that will move the elevator using a consistent velocity disregarding direction
*
* @param speed How fast the elevator moves
* @return Sets motor voltage to move the elevator relative to the speed parameter
*/
public Command runAssistedElevator(DoubleSupplier speed) {
return run(() -> {
double realSpeedTarget = speed.getAsDouble() * ElevatorConstants.kElevatorMaxVelocity;
double voltsOut = velocityController.calculate(
encoder.getVelocity(),
realSpeedTarget
) + feedForward.calculate(realSpeedTarget);
elevatorMotor1.setVoltage(voltsOut);
}).until(
() -> bottomLimitSwitch.get() || encoder.getPosition() >= ElevatorConstants.kElevatorMaxHeight);
}
/**
* A manual translation command that uses feed forward calculation to maintain position
*
* @param speed The speed at which the elevator translates
* @return Sets motor voltage to translate the elevator and maintain position
*/
public Command runManualElevator(double speed) {
return run(() -> { return run(() -> {
elevatorMotor1.set(speed); elevatorMotor1.set(speed);
}); });
} }
/**
* Moves the elevator to a target destination (setpoint)
*
* @param setpoint Target destination of the subsystem
* @param timeout Time to achieve the setpoint before quitting
* @return Sets motor voltage to achieve the target destination
*/
public Command goToSetpoint(double setpoint, double timeout) { public Command goToSetpoint(double setpoint, double timeout) {
return run(() -> { return run(() -> {
double voltsOut = pidController.calculate( double voltsOut = positionController.calculate(
encoder.getPosition(), encoder.getPosition(),
setpoint setpoint
) + feedForward.calculate(0); ) + feedForward.calculate(0);
elevatorMotor1.setVoltage(voltsOut); elevatorMotor1.setVoltage(voltsOut);
}).until(pidController::atSetpoint).withTimeout(timeout); }).until(
() -> positionController.atSetpoint() || bottomLimitSwitch.get()
).withTimeout(timeout);
}
/**
* Returns the current encoder position
*
* @return Current encoder position
*/
public double getEncoderPosition() {
return encoder.getPosition();
}
/**
* Returns the value of the bottom limit switch on the elevator (false = disabled, true = enabled)
*
* @return The value of bottomLimitSwitch
*/
public boolean getBottomLimitSwitch() {
return bottomLimitSwitch.get();
} }
} }

View File

@@ -31,7 +31,6 @@ public class Indexer extends SubsystemBase {
public Command indexCoral(double speed) { public Command indexCoral(double speed) {
return run(() -> { return run(() -> {
indexerMotor.set(speed); indexerMotor.set(speed);
}) }).until(indexerBeamBreak::get);
.until(indexerBeamBreak::get);
} }
} }

View File

@@ -15,21 +15,22 @@ import com.revrobotics.spark.SparkBase.ControlType;
import com.revrobotics.spark.SparkBase.PersistMode; import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode; import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType; import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.ctre.phoenix6.controls.VelocityVoltage;
import com.ctre.phoenix6.hardware.TalonFX;
import com.revrobotics.AbsoluteEncoder; import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.RelativeEncoder;
import frc.robot.constants.ModuleConstants; import frc.robot.constants.ModuleConstants;
public class MAXSwerveModule { public class MAXSwerveModule {
private final SparkMax m_drivingSpark; private final TalonFX m_drive;
private final SparkMax m_turningSpark; private final SparkMax m_turningSpark;
private final RelativeEncoder m_drivingEncoder;
private final AbsoluteEncoder m_turningEncoder; private final AbsoluteEncoder m_turningEncoder;
private final SparkClosedLoopController m_drivingClosedLoopController;
private final SparkClosedLoopController m_turningClosedLoopController; private final SparkClosedLoopController m_turningClosedLoopController;
private final VelocityVoltage driveVelocityRequest;
private double m_chassisAngularOffset = 0; private double m_chassisAngularOffset = 0;
private SwerveModuleState m_desiredState = new SwerveModuleState(0.0, new Rotation2d()); private SwerveModuleState m_desiredState = new SwerveModuleState(0.0, new Rotation2d());
@@ -40,26 +41,29 @@ public class MAXSwerveModule {
* Encoder. * Encoder.
*/ */
public MAXSwerveModule(int drivingCANId, int turningCANId, double chassisAngularOffset) { public MAXSwerveModule(int drivingCANId, int turningCANId, double chassisAngularOffset) {
m_drivingSpark = new SparkMax(drivingCANId, MotorType.kBrushless); m_drive = new TalonFX(drivingCANId);
m_turningSpark = new SparkMax(turningCANId, MotorType.kBrushless); m_turningSpark = new SparkMax(turningCANId, MotorType.kBrushless);
m_drivingEncoder = m_drivingSpark.getEncoder();
m_turningEncoder = m_turningSpark.getAbsoluteEncoder(); m_turningEncoder = m_turningSpark.getAbsoluteEncoder();
m_drivingClosedLoopController = m_drivingSpark.getClosedLoopController();
m_turningClosedLoopController = m_turningSpark.getClosedLoopController(); m_turningClosedLoopController = m_turningSpark.getClosedLoopController();
driveVelocityRequest = new VelocityVoltage(0).withSlot(0);
// Apply the respective configurations to the SPARKS. Reset parameters before // Apply the respective configurations to the SPARKS. Reset parameters before
// applying the configuration to bring the SPARK to a known good state. Persist // applying the configuration to bring the SPARK to a known good state. Persist
// the settings to the SPARK to avoid losing them on a power cycle. // the settings to the SPARK to avoid losing them on a power cycle.
m_drivingSpark.configure(ModuleConstants.drivingConfig, ResetMode.kResetSafeParameters, m_drive.getConfigurator().apply(ModuleConstants.kDriveCurrentLimitConfig);
PersistMode.kPersistParameters); m_drive.getConfigurator().apply(ModuleConstants.kDriveFeedConfig);
m_drive.getConfigurator().apply(ModuleConstants.kDriveMotorConfig);
m_drive.getConfigurator().apply(ModuleConstants.kDriveSlot0Config);
m_turningSpark.configure(ModuleConstants.turningConfig, ResetMode.kResetSafeParameters, m_turningSpark.configure(ModuleConstants.turningConfig, ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters); PersistMode.kPersistParameters);
m_chassisAngularOffset = chassisAngularOffset; m_chassisAngularOffset = chassisAngularOffset;
m_desiredState.angle = new Rotation2d(m_turningEncoder.getPosition()); m_desiredState.angle = new Rotation2d(m_turningEncoder.getPosition());
m_drivingEncoder.setPosition(0); m_drive.setPosition(0);
} }
/** /**
@@ -70,7 +74,7 @@ public class MAXSwerveModule {
public SwerveModuleState getState() { public SwerveModuleState getState() {
// Apply chassis angular offset to the encoder position to get the position // Apply chassis angular offset to the encoder position to get the position
// relative to the chassis. // relative to the chassis.
return new SwerveModuleState(m_drivingEncoder.getVelocity(), return new SwerveModuleState(m_drive.getVelocity().getValueAsDouble(),
new Rotation2d(m_turningEncoder.getPosition() - m_chassisAngularOffset)); new Rotation2d(m_turningEncoder.getPosition() - m_chassisAngularOffset));
} }
@@ -82,8 +86,7 @@ public class MAXSwerveModule {
public SwerveModulePosition getPosition() { public SwerveModulePosition getPosition() {
// Apply chassis angular offset to the encoder position to get the position // Apply chassis angular offset to the encoder position to get the position
// relative to the chassis. // relative to the chassis.
return new SwerveModulePosition( return new SwerveModulePosition(m_drive.getPosition().getValueAsDouble(),
m_drivingEncoder.getPosition(),
new Rotation2d(m_turningEncoder.getPosition() - m_chassisAngularOffset)); new Rotation2d(m_turningEncoder.getPosition() - m_chassisAngularOffset));
} }
@@ -102,14 +105,21 @@ public class MAXSwerveModule {
correctedDesiredState.optimize(new Rotation2d(m_turningEncoder.getPosition())); correctedDesiredState.optimize(new Rotation2d(m_turningEncoder.getPosition()));
// Command driving and turning SPARKS towards their respective setpoints. // Command driving and turning SPARKS towards their respective setpoints.
m_drivingClosedLoopController.setReference(correctedDesiredState.speedMetersPerSecond, ControlType.kVelocity); m_drive.setControl(
driveVelocityRequest.withVelocity(
correctedDesiredState.speedMetersPerSecond
).withFeedForward(
correctedDesiredState.speedMetersPerSecond
)
);
m_turningClosedLoopController.setReference(correctedDesiredState.angle.getRadians(), ControlType.kPosition); m_turningClosedLoopController.setReference(correctedDesiredState.angle.getRadians(), ControlType.kPosition);
m_desiredState = desiredState; m_desiredState = desiredState;
} }
public void setVoltageDrive(double voltage){ public void setVoltageDrive(double voltage){
m_drivingSpark.setVoltage(voltage); m_drive.setVoltage(voltage);
} }
public void setVoltageTurn(double voltage) { public void setVoltageTurn(double voltage) {
@@ -117,7 +127,7 @@ public class MAXSwerveModule {
} }
public double getVoltageDrive() { public double getVoltageDrive() {
return m_drivingSpark.get() * RobotController.getBatteryVoltage(); return m_drive.get() * RobotController.getBatteryVoltage();
} }
public double getVoltageTurn() { public double getVoltageTurn() {
@@ -126,6 +136,6 @@ public class MAXSwerveModule {
/** Zeroes all the SwerveModule encoders. */ /** Zeroes all the SwerveModule encoders. */
public void resetEncoders() { public void resetEncoders() {
m_drivingEncoder.setPosition(0); m_drive.setPosition(0);
} }
} }

View File

@@ -33,14 +33,6 @@ public class Manipulator extends SubsystemBase {
public Command runUntilCollected(double speed, boolean coral) { public Command runUntilCollected(double speed, boolean coral) {
return run(() -> { return run(() -> {
manipulatorMotor.set(coral ? speed : speed * -1); manipulatorMotor.set(coral ? speed : speed * -1);
}) }).until(() -> coralBeamBreak.get() || algaeBeamBreak.get());
.until(() -> coralBeamBreak.get() || algaeBeamBreak.get());
}
public Command indexCoral(double speed) {
return run(() -> {
manipulatorMotor.set(speed);
})
.until(coralBeamBreak::get);
} }
} }

View File

@@ -0,0 +1,62 @@
package frc.robot.subsystems.sysid;
import static edu.wpi.first.units.Units.Volts;
import static edu.wpi.first.units.Units.Radians;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import edu.wpi.first.units.measure.MutAngle;
import edu.wpi.first.units.measure.MutAngularVelocity;
import edu.wpi.first.units.measure.MutVoltage;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.constants.ArmConstants;
import frc.robot.subsystems.Arm;
public class ArmSysID extends Arm {
private MutVoltage appliedVoltage;
private MutAngle armPosition;
private MutAngularVelocity armVelocity;
private SysIdRoutine routine;
public ArmSysID() {
super();
appliedVoltage = Volts.mutable(0);
armPosition = Radians.mutable(0);
armVelocity = RadiansPerSecond.mutable(0);
routine = new SysIdRoutine(
ArmConstants.kSysIDConfig,
new SysIdRoutine.Mechanism(
armMotor::setVoltage,
(log) -> {
log.motor("armMotor")
.voltage(appliedVoltage.mut_replace(
armMotor.get() * RobotController.getBatteryVoltage(), Volts
))
.angularPosition(armPosition.mut_replace(
getEncoderPosition(), Radians
))
.angularVelocity(armVelocity.mut_replace(
getEncoderVelocity(), RadiansPerSecond
));
},
this
)
);
}
public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {
return routine.quasistatic(direction);
}
public Command sysIdDynamic(SysIdRoutine.Direction direction) {
return routine.dynamic(direction);
}
}

View File

@@ -0,0 +1,38 @@
{
"fileName": "PathplannerLib-2025.2.1.json",
"name": "PathplannerLib",
"version": "2025.2.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.2.1"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2025.2.1",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal",
"linuxathena",
"linuxarm32",
"linuxarm64"
]
}
]
}

View File

@@ -1,50 +1,50 @@
{ {
"fileName": "Phoenix5-5.34.0-beta-4.json", "fileName": "Phoenix5-5.35.1.json",
"name": "CTRE-Phoenix (v5)", "name": "CTRE-Phoenix (v5)",
"version": "5.34.0-beta-4", "version": "5.35.1",
"frcYear": "2025", "frcYear": "2025",
"uuid": "ab676553-b602-441f-a38d-f1296eff6537", "uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [ "mavenUrls": [
"https://maven.ctr-electronics.com/release/" "https://maven.ctr-electronics.com/release/"
], ],
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-beta-latest.json", "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-latest.json",
"requires": [ "requires": [
{ {
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "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.", "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", "offlineFileName": "Phoenix6-frc2025-latest.json",
"onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json" "onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json"
} }
], ],
"conflictsWith": [ "conflictsWith": [
{ {
"uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af",
"errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.", "errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.",
"offlineFileName": "Phoenix6-replay-frc2025-beta-latest.json" "offlineFileName": "Phoenix6-replay-frc2025-latest.json"
}, },
{ {
"uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df", "uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df",
"errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.", "errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.",
"offlineFileName": "Phoenix5-replay-frc2025-beta-latest.json" "offlineFileName": "Phoenix5-replay-frc2025-latest.json"
} }
], ],
"javaDependencies": [ "javaDependencies": [
{ {
"groupId": "com.ctre.phoenix", "groupId": "com.ctre.phoenix",
"artifactId": "api-java", "artifactId": "api-java",
"version": "5.34.0-beta-4" "version": "5.35.1"
}, },
{ {
"groupId": "com.ctre.phoenix", "groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java", "artifactId": "wpiapi-java",
"version": "5.34.0-beta-4" "version": "5.35.1"
} }
], ],
"jniDependencies": [ "jniDependencies": [
{ {
"groupId": "com.ctre.phoenix", "groupId": "com.ctre.phoenix",
"artifactId": "cci", "artifactId": "cci",
"version": "5.34.0-beta-4", "version": "5.35.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -58,7 +58,7 @@
{ {
"groupId": "com.ctre.phoenix.sim", "groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim", "artifactId": "cci-sim",
"version": "5.34.0-beta-4", "version": "5.35.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -74,7 +74,7 @@
{ {
"groupId": "com.ctre.phoenix", "groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp", "artifactId": "wpiapi-cpp",
"version": "5.34.0-beta-4", "version": "5.35.1",
"libName": "CTRE_Phoenix_WPI", "libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -90,7 +90,7 @@
{ {
"groupId": "com.ctre.phoenix", "groupId": "com.ctre.phoenix",
"artifactId": "api-cpp", "artifactId": "api-cpp",
"version": "5.34.0-beta-4", "version": "5.35.1",
"libName": "CTRE_Phoenix", "libName": "CTRE_Phoenix",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -106,7 +106,7 @@
{ {
"groupId": "com.ctre.phoenix", "groupId": "com.ctre.phoenix",
"artifactId": "cci", "artifactId": "cci",
"version": "5.34.0-beta-4", "version": "5.35.1",
"libName": "CTRE_PhoenixCCI", "libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -122,7 +122,7 @@
{ {
"groupId": "com.ctre.phoenix.sim", "groupId": "com.ctre.phoenix.sim",
"artifactId": "wpiapi-cpp-sim", "artifactId": "wpiapi-cpp-sim",
"version": "5.34.0-beta-4", "version": "5.35.1",
"libName": "CTRE_Phoenix_WPISim", "libName": "CTRE_Phoenix_WPISim",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -138,7 +138,7 @@
{ {
"groupId": "com.ctre.phoenix.sim", "groupId": "com.ctre.phoenix.sim",
"artifactId": "api-cpp-sim", "artifactId": "api-cpp-sim",
"version": "5.34.0-beta-4", "version": "5.35.1",
"libName": "CTRE_PhoenixSim", "libName": "CTRE_PhoenixSim",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -154,7 +154,7 @@
{ {
"groupId": "com.ctre.phoenix.sim", "groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim", "artifactId": "cci-sim",
"version": "5.34.0-beta-4", "version": "5.35.1",
"libName": "CTRE_PhoenixCCISim", "libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,

View File

@@ -1,32 +1,32 @@
{ {
"fileName": "Phoenix6-25.0.0-beta-4.json", "fileName": "Phoenix6-25.2.1.json",
"name": "CTRE-Phoenix (v6)", "name": "CTRE-Phoenix (v6)",
"version": "25.0.0-beta-4", "version": "25.2.1",
"frcYear": "2025", "frcYear": "2025",
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19", "uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
"mavenUrls": [ "mavenUrls": [
"https://maven.ctr-electronics.com/release/" "https://maven.ctr-electronics.com/release/"
], ],
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-beta-latest.json", "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json",
"conflictsWith": [ "conflictsWith": [
{ {
"uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af",
"errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.",
"offlineFileName": "Phoenix6-replay-frc2025-beta-latest.json" "offlineFileName": "Phoenix6-replay-frc2025-latest.json"
} }
], ],
"javaDependencies": [ "javaDependencies": [
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-java", "artifactId": "wpiapi-java",
"version": "25.0.0-beta-4" "version": "25.2.1"
} }
], ],
"jniDependencies": [ "jniDependencies": [
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "api-cpp", "artifactId": "api-cpp",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -40,7 +40,7 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "tools", "artifactId": "tools",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -54,7 +54,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "api-cpp-sim", "artifactId": "api-cpp-sim",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -68,7 +68,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim", "artifactId": "tools-sim",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -82,7 +82,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX", "artifactId": "simTalonSRX",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -96,7 +96,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX", "artifactId": "simVictorSPX",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -110,7 +110,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU", "artifactId": "simPigeonIMU",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -124,7 +124,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder", "artifactId": "simCANCoder",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -138,7 +138,21 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX", "artifactId": "simProTalonFX",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS",
"version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -152,21 +166,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder", "artifactId": "simProCANcoder",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange",
"version": "25.0.0-beta-4",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -180,7 +180,21 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2", "artifactId": "simProPigeon2",
"version": "25.0.0-beta-4", "version": "25.2.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange",
"version": "25.2.1",
"isJar": false, "isJar": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"validPlatforms": [ "validPlatforms": [
@@ -196,7 +210,7 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-cpp", "artifactId": "wpiapi-cpp",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_Phoenix6_WPI", "libName": "CTRE_Phoenix6_WPI",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -212,7 +226,7 @@
{ {
"groupId": "com.ctre.phoenix6", "groupId": "com.ctre.phoenix6",
"artifactId": "tools", "artifactId": "tools",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_PhoenixTools", "libName": "CTRE_PhoenixTools",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -228,7 +242,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "wpiapi-cpp-sim", "artifactId": "wpiapi-cpp-sim",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_Phoenix6_WPISim", "libName": "CTRE_Phoenix6_WPISim",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -244,7 +258,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim", "artifactId": "tools-sim",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_PhoenixTools_Sim", "libName": "CTRE_PhoenixTools_Sim",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -260,7 +274,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX", "artifactId": "simTalonSRX",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_SimTalonSRX", "libName": "CTRE_SimTalonSRX",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -276,7 +290,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX", "artifactId": "simVictorSPX",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_SimVictorSPX", "libName": "CTRE_SimVictorSPX",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -292,7 +306,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU", "artifactId": "simPigeonIMU",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_SimPigeonIMU", "libName": "CTRE_SimPigeonIMU",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -308,7 +322,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder", "artifactId": "simCANCoder",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_SimCANCoder", "libName": "CTRE_SimCANCoder",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -324,7 +338,7 @@
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX", "artifactId": "simProTalonFX",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_SimProTalonFX", "libName": "CTRE_SimProTalonFX",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -337,10 +351,26 @@
], ],
"simMode": "swsim" "simMode": "swsim"
}, },
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFXS",
"version": "25.2.1",
"libName": "CTRE_SimProTalonFXS",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxarm64",
"osxuniversal"
],
"simMode": "swsim"
},
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder", "artifactId": "simProCANcoder",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_SimProCANcoder", "libName": "CTRE_SimProCANcoder",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
@@ -355,9 +385,9 @@
}, },
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANrange", "artifactId": "simProPigeon2",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_SimProCANrange", "libName": "CTRE_SimProPigeon2",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
@@ -371,9 +401,9 @@
}, },
{ {
"groupId": "com.ctre.phoenix6.sim", "groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2", "artifactId": "simProCANrange",
"version": "25.0.0-beta-4", "version": "25.2.1",
"libName": "CTRE_SimProPigeon2", "libName": "CTRE_SimProCANrange",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": true, "sharedLibrary": true,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,

View File

@@ -1,7 +1,7 @@
{ {
"fileName": "REVLib-2025.0.0-beta-3.json", "fileName": "REVLib-2025.0.1.json",
"name": "REVLib", "name": "REVLib",
"version": "2025.0.0-beta-3", "version": "2025.0.1",
"frcYear": "2025", "frcYear": "2025",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [ "mavenUrls": [
@@ -12,19 +12,18 @@
{ {
"groupId": "com.revrobotics.frc", "groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java", "artifactId": "REVLib-java",
"version": "2025.0.0-beta-3" "version": "2025.0.1"
} }
], ],
"jniDependencies": [ "jniDependencies": [
{ {
"groupId": "com.revrobotics.frc", "groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver", "artifactId": "REVLib-driver",
"version": "2025.0.0-beta-3", "version": "2025.0.1",
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"isJar": false, "isJar": false,
"validPlatforms": [ "validPlatforms": [
"windowsx86-64", "windowsx86-64",
"windowsx86",
"linuxarm64", "linuxarm64",
"linuxx86-64", "linuxx86-64",
"linuxathena", "linuxathena",
@@ -37,14 +36,13 @@
{ {
"groupId": "com.revrobotics.frc", "groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp", "artifactId": "REVLib-cpp",
"version": "2025.0.0-beta-3", "version": "2025.0.1",
"libName": "REVLib", "libName": "REVLib",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": false, "sharedLibrary": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"binaryPlatforms": [ "binaryPlatforms": [
"windowsx86-64", "windowsx86-64",
"windowsx86",
"linuxarm64", "linuxarm64",
"linuxx86-64", "linuxx86-64",
"linuxathena", "linuxathena",
@@ -55,14 +53,13 @@
{ {
"groupId": "com.revrobotics.frc", "groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver", "artifactId": "REVLib-driver",
"version": "2025.0.0-beta-3", "version": "2025.0.1",
"libName": "REVLibDriver", "libName": "REVLibDriver",
"headerClassifier": "headers", "headerClassifier": "headers",
"sharedLibrary": false, "sharedLibrary": false,
"skipInvalidPlatforms": true, "skipInvalidPlatforms": true,
"binaryPlatforms": [ "binaryPlatforms": [
"windowsx86-64", "windowsx86-64",
"windowsx86",
"linuxarm64", "linuxarm64",
"linuxx86-64", "linuxx86-64",
"linuxathena", "linuxathena",

View File

@@ -0,0 +1,71 @@
{
"fileName": "Studica-2025.0.1.json",
"name": "Studica",
"version": "2025.0.1",
"uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
"frcYear": "2025",
"mavenUrls": [
"https://dev.studica.com/maven/release/2025/"
],
"jsonUrl": "https://dev.studica.com/releases/2025/Studica-2025.0.1.json",
"cppDependencies": [
{
"artifactId": "Studica-cpp",
"binaryPlatforms": [
"linuxathena",
"linuxarm32",
"linuxarm64",
"linuxx86-64",
"osxuniversal",
"windowsx86-64"
],
"groupId": "com.studica.frc",
"headerClassifier": "headers",
"libName": "Studica",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"version": "2025.0.1"
},
{
"artifactId": "Studica-driver",
"binaryPlatforms": [
"linuxathena",
"linuxarm32",
"linuxarm64",
"linuxx86-64",
"osxuniversal",
"windowsx86-64"
],
"groupId": "com.studica.frc",
"headerClassifier": "headers",
"libName": "StudicaDriver",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"version": "2025.0.1"
}
],
"javaDependencies": [
{
"artifactId": "Studica-java",
"groupId": "com.studica.frc",
"version": "2025.0.1"
}
],
"jniDependencies": [
{
"artifactId": "Studica-driver",
"groupId": "com.studica.frc",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"linuxathena",
"linuxarm32",
"linuxarm64",
"linuxx86-64",
"osxuniversal",
"windowsx86-64"
],
"version": "2025.0.1"
}
]
}