Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ allprojects {

// Set this to the latest version of StuyLib.
// You can check here: https://github.com/StuyPulse/StuyLib/releases.
final String STUYLIB_VERSION = 'v2025.1.1'
final String STUYLIB_VERSION = 'v2025.1.2'

def ROBOT_MAIN_CLASS = "com.stuypulse.robot.Main"

Expand Down
222 changes: 173 additions & 49 deletions src/main/java/com/stuypulse/robot/constants/Motors.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,21 @@

package com.stuypulse.robot.constants;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX;
import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs;
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.FeedbackConfigs;
import com.ctre.phoenix6.configs.MotionMagicConfigs;
import com.ctre.phoenix6.configs.MotorOutputConfigs;
import com.ctre.phoenix6.configs.OpenLoopRampsConfigs;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.Slot1Configs;
import com.ctre.phoenix6.configs.Slot2Configs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue;
import com.ctre.phoenix6.signals.GravityTypeValue;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;

/*-
* File containing all of the configurations that different motors require.
Expand All @@ -22,64 +34,176 @@ public interface Motors {

/** Classes to store all of the values a motor needs */

public static class TalonSRXConfig {
public final boolean INVERTED;
public final NeutralMode NEUTRAL_MODE;
public final int PEAK_CURRENT_LIMIT_AMPS;
public final double OPEN_LOOP_RAMP_RATE;

public TalonSRXConfig(
boolean inverted,
NeutralMode neutralMode,
int peakCurrentLimitAmps,
double openLoopRampRate) {
this.INVERTED = inverted;
this.NEUTRAL_MODE = neutralMode;
this.PEAK_CURRENT_LIMIT_AMPS = peakCurrentLimitAmps;
this.OPEN_LOOP_RAMP_RATE = openLoopRampRate;
public static class TalonFXConfig {
private final TalonFXConfiguration configuration = new TalonFXConfiguration();
private final Slot0Configs slot0Configs = new Slot0Configs();
private final Slot1Configs slot1Configs = new Slot1Configs();
private final Slot2Configs slot2Configs = new Slot2Configs();
private final MotorOutputConfigs motorOutputConfigs = new MotorOutputConfigs();
private final ClosedLoopRampsConfigs closedLoopRampsConfigs = new ClosedLoopRampsConfigs();
private final OpenLoopRampsConfigs openLoopRampsConfigs = new OpenLoopRampsConfigs();
private final CurrentLimitsConfigs currentLimitsConfigs = new CurrentLimitsConfigs();
private final FeedbackConfigs feedbackConfigs = new FeedbackConfigs();
private final MotionMagicConfigs motionMagicConfigs = new MotionMagicConfigs();

public void configure(TalonFX motor) {
motor.getConfigurator().apply(configuration);
}

public TalonSRXConfig(boolean inverted, NeutralMode neutralMode, int peakCurrentLimitAmps) {
this(inverted, neutralMode, peakCurrentLimitAmps, 0.0);
// SLOT 0 CONFIGS

public TalonFXConfig withPIDConstants(double kP, double kI, double kD, int slot) {
switch (slot) {
case 0:
slot0Configs.kP = kP;
slot0Configs.kI = kI;
slot0Configs.kD = kD;
configuration.withSlot0(slot0Configs);
break;
case 1:
slot1Configs.kP = kP;
slot1Configs.kI = kI;
slot1Configs.kD = kD;
configuration.withSlot1(slot1Configs);
break;
case 2:
slot2Configs.kP = kP;
slot2Configs.kI = kI;
slot2Configs.kD = kD;
configuration.withSlot2(slot2Configs);
break;
}
return this;
}

public TalonSRXConfig(boolean inverted, NeutralMode neutralMode) {
this(inverted, neutralMode, 80);
public TalonFXConfig withFFConstants(double kS, double kV, double kA, int slot) {
return withFFConstants(kS, kV, kA, 0, slot);
}

public void configure(WPI_TalonSRX motor) {
motor.setInverted(INVERTED);
motor.setNeutralMode(NEUTRAL_MODE);
motor.configContinuousCurrentLimit(PEAK_CURRENT_LIMIT_AMPS - 10, 0);
motor.configPeakCurrentLimit(PEAK_CURRENT_LIMIT_AMPS, 0);
motor.configPeakCurrentDuration(100, 0);
motor.enableCurrentLimit(true);
motor.configOpenloopRamp(OPEN_LOOP_RAMP_RATE);
public TalonFXConfig withFFConstants(double kS, double kV, double kA, double kG, int slot) {
switch (slot) {
case 0:
slot0Configs.kS = kS;
slot0Configs.kV = kV;
slot0Configs.kA = kA;
slot0Configs.kG = kG;
configuration.withSlot0(slot0Configs);
break;
case 1:
slot1Configs.kS = kS;
slot1Configs.kV = kV;
slot1Configs.kA = kA;
slot1Configs.kG = kG;
configuration.withSlot1(slot1Configs);
break;
case 2:
slot2Configs.kS = kS;
slot2Configs.kV = kV;
slot2Configs.kA = kA;
slot2Configs.kG = kG;
configuration.withSlot2(slot2Configs);
break;
}
return this;
}
}

public static class VictorSPXConfig {
public final boolean INVERTED;
public final NeutralMode NEUTRAL_MODE;
public final double OPEN_LOOP_RAMP_RATE;

public VictorSPXConfig(
boolean inverted,
NeutralMode neutralMode,
double openLoopRampRate) {
this.INVERTED = inverted;
this.NEUTRAL_MODE = neutralMode;
this.OPEN_LOOP_RAMP_RATE = openLoopRampRate;
public TalonFXConfig withGravityType(GravityTypeValue gravityType) {
slot0Configs.GravityType = gravityType;
slot1Configs.GravityType = gravityType;
slot2Configs.GravityType = gravityType;

configuration.withSlot0(slot0Configs);
configuration.withSlot1(slot1Configs);
configuration.withSlot2(slot2Configs);

return this;
}

// MOTOR OUTPUT CONFIGS

public TalonFXConfig withInvertedValue(InvertedValue invertedValue) {
motorOutputConfigs.Inverted = invertedValue;

configuration.withMotorOutput(motorOutputConfigs);

return this;
}

public VictorSPXConfig(boolean inverted, NeutralMode neutralMode) {
this(inverted, neutralMode, 0.0);
public TalonFXConfig withNeutralMode(NeutralModeValue neutralMode) {
motorOutputConfigs.NeutralMode = neutralMode;

configuration.withMotorOutput(motorOutputConfigs);

return this;
}

// RAMP RATE CONFIGS

public TalonFXConfig withRampRate(double rampRate) {
closedLoopRampsConfigs.DutyCycleClosedLoopRampPeriod = rampRate;
closedLoopRampsConfigs.TorqueClosedLoopRampPeriod = rampRate;
closedLoopRampsConfigs.VoltageClosedLoopRampPeriod = rampRate;

openLoopRampsConfigs.DutyCycleOpenLoopRampPeriod = rampRate;
openLoopRampsConfigs.TorqueOpenLoopRampPeriod = rampRate;
openLoopRampsConfigs.VoltageOpenLoopRampPeriod = rampRate;

configuration.withClosedLoopRamps(closedLoopRampsConfigs);
configuration.withOpenLoopRamps(openLoopRampsConfigs);

return this;
}

public void configure(WPI_VictorSPX motor) {
motor.setInverted(INVERTED);
motor.setNeutralMode(NEUTRAL_MODE);
motor.configOpenloopRamp(OPEN_LOOP_RAMP_RATE);
// CURRENT LIMIT CONFIGS

public TalonFXConfig withCurrentLimitAmps(double currentLimitAmps) {
currentLimitsConfigs.StatorCurrentLimit = currentLimitAmps;
currentLimitsConfigs.StatorCurrentLimitEnable = true;

configuration.withCurrentLimits(currentLimitsConfigs);

return this;
}

public TalonFXConfig withSupplyCurrentLimitAmps(double currentLimitAmps) {
currentLimitsConfigs.SupplyCurrentLimit = currentLimitAmps;
currentLimitsConfigs.SupplyCurrentLimitEnable = true;

configuration.withCurrentLimits(currentLimitsConfigs);

return this;
}

// MOTION MAGIC CONFIGS

public TalonFXConfig withMotionProfile(double maxVelocity, double maxAcceleration) {
motionMagicConfigs.MotionMagicCruiseVelocity = maxVelocity;
motionMagicConfigs.MotionMagicAcceleration = maxAcceleration;

configuration.withMotionMagic(motionMagicConfigs);

return this;
}

// FEEDBACK CONFIGS

public TalonFXConfig withRemoteSensor(
int ID, FeedbackSensorSourceValue source, double rotorToSensorRatio) {
feedbackConfigs.FeedbackRemoteSensorID = ID;
feedbackConfigs.FeedbackSensorSource = source;
feedbackConfigs.RotorToSensorRatio = rotorToSensorRatio;

configuration.withFeedback(feedbackConfigs);

return this;
}

public TalonFXConfig withSensorToMechanismRatio(double sensorToMechanismRatio) {
feedbackConfigs.SensorToMechanismRatio = sensorToMechanismRatio;

configuration.withFeedback(feedbackConfigs);

return this;
}
}
}
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "PathplannerLib.json",
"fileName": "PathplannerLib-2025.2.7.json",
"name": "PathplannerLib",
"version": "2025.1.1",
"version": "2025.2.7",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2025",
"mavenUrls": [
Expand All @@ -12,15 +12,15 @@
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2025.1.1"
"version": "2025.2.7"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2025.1.1",
"version": "2025.2.7",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down
24 changes: 12 additions & 12 deletions vendordeps/Phoenix5.json → vendordeps/Phoenix5-5.35.1.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "Phoenix5-frc2025-latest.json",
"fileName": "Phoenix5-5.35.1.json",
"name": "CTRE-Phoenix (v5)",
"version": "5.35.0",
"version": "5.35.1",
"frcYear": "2025",
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
Expand Down Expand Up @@ -32,19 +32,19 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.35.0"
"version": "5.35.1"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.35.0"
"version": "5.35.1"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.35.0",
"version": "5.35.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -58,7 +58,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.35.0",
"version": "5.35.1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -74,7 +74,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.35.0",
"version": "5.35.1",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -90,7 +90,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
"version": "5.35.0",
"version": "5.35.1",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -106,7 +106,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.35.0",
"version": "5.35.1",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -122,7 +122,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "wpiapi-cpp-sim",
"version": "5.35.0",
"version": "5.35.1",
"libName": "CTRE_Phoenix_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -138,7 +138,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "api-cpp-sim",
"version": "5.35.0",
"version": "5.35.1",
"libName": "CTRE_PhoenixSim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -154,7 +154,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.35.0",
"version": "5.35.1",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand Down
Loading