Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
9e01ed8
pre vision shooting
arcadeArchitect Mar 18, 2026
8639b36
pre intake pivot merge
arcadeArchitect Mar 18, 2026
1368047
Merge remote-tracking branch 'origin' into launch-calc
arcadeArchitect Mar 18, 2026
a5ddcb7
pre systems check
arcadeArchitect Mar 18, 2026
ab40d57
Merge remote-tracking branch 'origin' into launch-calc
arcadeArchitect Mar 18, 2026
4e2e0cc
initial test, code wip: drive 5 sec crash, loop overrun
arcadeArchitect Mar 18, 2026
f1b6ee5
pre launch calc tuning
arcadeArchitect Mar 21, 2026
da57b3a
add theoretical launch calc values, indexer wait on flywheel, works!!
arcadeArchitect Mar 22, 2026
4a5e04f
tuning mode off
arcadeArchitect Mar 22, 2026
7ed3a5e
deprecate left/right side of subsystems in implementation and constan…
arcadeArchitect Mar 24, 2026
31f7584
update flywheel to have 4 motors
arcadeArchitect Mar 25, 2026
32a6e2e
update launcher position (roughly accurate)
arcadeArchitect Mar 25, 2026
b42598b
make TalonFXConfigurators final, reformatting
arcadeArchitect Mar 25, 2026
043dd67
remove beam break constants
arcadeArchitect Mar 25, 2026
beae2f1
add disconnection + temp logging and alerts for flywheel
arcadeArchitect Mar 25, 2026
336f771
alert rename
arcadeArchitect Mar 25, 2026
89f9b8c
coderabbit fixes
arcadeArchitect Mar 25, 2026
17a7673
Merge pull request #2 from Team5924/launch-calc
arcadeArchitect Mar 25, 2026
5a320a1
Merge remote-tracking branch 'origin' into subsystem-deprecation
arcadeArchitect Mar 25, 2026
825fcf9
add intake follower
arcadeArchitect Mar 25, 2026
5eea72d
fixes, intake wip
arcadeArchitect Mar 26, 2026
49ac064
fixes, intake wip wip
arcadeArchitect Mar 26, 2026
a29d265
intake should work with two motors
arcadeArchitect Mar 28, 2026
e521b73
robot container formatting changes, add toggle for vision
arcadeArchitect Mar 28, 2026
b3809de
add shooting bindings
arcadeArchitect Mar 28, 2026
f430c17
fix shooter hood states and bindings
arcadeArchitect Mar 28, 2026
cf6d953
added documentation so we can merge
maiKuneho Mar 28, 2026
2b4ce7b
Merge pull request #3 from Team5924/subsystem-deprecation
arcadeArchitect Mar 28, 2026
ea8b214
fixed build error
maiKuneho Mar 28, 2026
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 .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -62,5 +62,5 @@
null
],
"java.dependency.enableDependencyCheckup": false,
"java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx2G -Xms100m -Xlog:disable"
"java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx4G -Xms100m -Xlog:disable"
}
254 changes: 46 additions & 208 deletions src/main/java/org/team5924/frc2026/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,6 @@
import edu.wpi.first.math.util.Units;
import com.ctre.phoenix6.signals.SensorDirectionValue;

import edu.wpi.first.math.geometry.Translation3d;

import edu.wpi.first.wpilibj.RobotBase;

/**
Expand Down Expand Up @@ -103,7 +101,18 @@ public final class Field {
.withVoltageClosedLoopRampPeriod(0.02);

public final class GenericRoller {
public static final TalonFXConfiguration CONFIG =
public static final TalonFXConfiguration CLOCKWISE_CONFIG =
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(60)
.withStatorCurrentLimit(60))
.withMotorOutput(
new MotorOutputConfigs()
.withInverted(InvertedValue.Clockwise_Positive)
.withNeutralMode(NeutralModeValue.Brake));

public static final TalonFXConfiguration COUNTERCLOCKWISE_CONFIG =
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
Expand All @@ -122,11 +131,12 @@ public final class GenericRoller {

public final class Intake {
public static final int CAN_ID = 41;
public static final int FOLLOWER_CAN_ID = 42;
public static final String BUS = "rio";
public static final double MOTOR_TO_MECHANISM = 36.0 / 16.0;
public static final double SIM_MOI = 0.001;

public static final TalonFXConfiguration CONFIG = GenericRoller.CONFIG;
public static final TalonFXConfiguration CONFIG = GenericRoller.COUNTERCLOCKWISE_CONFIG.clone();
}

public final class IntakePivot {
Expand Down Expand Up @@ -155,8 +165,8 @@ public final class IntakePivot {
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(120)
.withStatorCurrentLimit(120)
.withSupplyCurrentLimit(60)
.withStatorCurrentLimit(60)
.withSupplyCurrentLimitEnable(true)
.withStatorCurrentLimitEnable(true))
.withMotorOutput(
Expand All @@ -168,48 +178,49 @@ public final class IntakePivot {
new SoftwareLimitSwitchConfigs()
.withReverseSoftLimitThreshold(MIN_POSITION_ROTATIONS)
.withForwardSoftLimitThreshold(MAX_POSITION_ROTATIONS)
.withForwardSoftLimitEnable(true)
.withReverseSoftLimitEnable(true);
.withForwardSoftLimitEnable(false)
.withReverseSoftLimitEnable(false);

public static final FeedbackConfigs FEEDBACK_CONFIGS =
new FeedbackConfigs()
.withFeedbackSensorSource(FeedbackSensorSourceValue.RotorSensor)
.withSensorToMechanismRatio(MOTOR_TO_MECHANISM)
.withRotorToSensorRatio(1.0);
}
}

public final class Hopper {
public static final int CAN_ID = 50;
public static final String BUS = "rio";
public static final double MOTOR_TO_MECHANISM = (16.0 / 12.0) * (24.0 / 16.0);
public static final double SIM_MOI = 0.001;

public static final int BEAM_BREAK_ID = 0;

public static final TalonFXConfiguration CONFIG = GenericRoller.CONFIG;
public static final TalonFXConfiguration CONFIG = GenericRoller.COUNTERCLOCKWISE_CONFIG.clone();
}

public final class Indexer {
public final static int CAN_ID = 51;
public static final String BUS = "rio";

// controls two rollers, so reduction is weird
public static final double MOTOR_TO_MECHANISM = 36.0 / 16.0;
public static final double SIM_MOI = 0.001;

public final static int BEAM_BREAK_ID = 0;

public static final TalonFXConfiguration CONFIG =
GenericRoller.CONFIG
GenericRoller.COUNTERCLOCKWISE_CONFIG.clone()
.withMotorOutput(
new MotorOutputConfigs()
.withInverted(InvertedValue.Clockwise_Positive));
}


/* General Subsystems */
public final class GeneralShooterHood {
public final class ShooterHood {
public static final String BUS = "rio";
public static final double SIM_MOI = 0.001;
public static final int CAN_ID = 34;

/* CANCoder */
public static final int CANCODER_ID = 36;
public static final double CANCODER_ABSOLUTE_OFFSET = 0.0;

// spur = hood driving gear, mechanism = shooter hood gear
public static final double MOTOR_TO_CANCODER = (40.0 / 12.0) * (24.0 / 17.0);
Expand All @@ -220,7 +231,7 @@ public final class GeneralShooterHood {
public static final double CANCODER_TO_MECHANISM = CANCODER_TO_SPUR * SPUR_TO_MECHANISM;
public static final double MOTOR_TO_MECHANISM = MOTOR_TO_CANCODER * CANCODER_TO_SPUR * SPUR_TO_MECHANISM;

public static final double EPSILON_RADS = Units.degreesToRadians(2.0);
public static final double EPSILON_RADS = Units.degreesToRadians(0.5);
public static final double STATE_TIMEOUT = 5.0;
public static final boolean ENABLE_TIMEOUT = false;

Expand Down Expand Up @@ -252,25 +263,36 @@ public final class GeneralShooterHood {
.withForwardSoftLimitEnable(false)
.withReverseSoftLimitEnable(false);

public static final FeedbackConfigs GENERAL_FEEDBACK_CONFIGS =
public static final FeedbackConfigs FEEDBACK_CONFIGS =
new FeedbackConfigs()
.withSensorToMechanismRatio(CANCODER_TO_MECHANISM)
.withRotorToSensorRatio(MOTOR_TO_CANCODER)
.withFeedbackSensorSource(FeedbackSensorSourceValue.FusedCANcoder);
.withFeedbackSensorSource(FeedbackSensorSourceValue.FusedCANcoder)
.withFeedbackRemoteSensorID(CANCODER_ID)
.withFeedbackRotorOffset(-CANCODER_ABSOLUTE_OFFSET);

public static final MagnetSensorConfigs GENERAL_CANCODER_CONFIGS =
public static final MagnetSensorConfigs CANCODER_CONFIGS =
new MagnetSensorConfigs()
.withAbsoluteSensorDiscontinuityPoint(1.0)
.withSensorDirection(SensorDirectionValue.Clockwise_Positive);
.withSensorDirection(SensorDirectionValue.Clockwise_Positive)
.withMagnetOffset(-1 * CANCODER_ABSOLUTE_OFFSET);
}

public final class GeneralFlywheel {
public final class Flywheel {
public static final int CAN_ID = 30;

public static final int FOLLOWER_CAN_ID = 31;
public static final int OPPOSER_ONE_CAN_ID = 32;
public static final int OPPOSER_TWO_CAN_ID = 33;

public static final double FOLLOWER_SIM_MOI = 0.001;

public static final double EPSILON_VELOCITY = 2.5;
public static final double MOTOR_TO_MECHANISM = 15.0 / 26.0;
public static final String BUS = "rio";
public static final double SIM_MOI = 0.001;

public static final TalonFXConfiguration GENERAL_CONFIG =
public static final TalonFXConfiguration CONFIG =
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
Expand All @@ -287,188 +309,4 @@ public final class GeneralFlywheel {
.withSensorToMechanismRatio(MOTOR_TO_MECHANISM)
.withRotorToSensorRatio(1.0);
}

public final class GeneralTurret {
public static final String BUS = "rio";

public static final double SIM_MOI = 0.001;

public static final double MOTOR_TO_CANCODER = (20.0 / 12.0);
public static final double CANCODER_TO_MECHANISM = (135.0 / 20.0);
public static final double MOTOR_TO_MECHANISM = MOTOR_TO_CANCODER * CANCODER_TO_MECHANISM;

public static final double EPSILON_RADS = Units.degreesToRadians(10.0);
public static final double STATE_TIMEOUT = 1.0;

/* Configs */
public static final TalonFXConfiguration GENERAL_CONFIG =
new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(60)
.withStatorCurrentLimit(10)
.withStatorCurrentLimitEnable(true))
.withMotorOutput(
new MotorOutputConfigs()
.withInverted(InvertedValue.Clockwise_Positive)
.withNeutralMode(NeutralModeValue.Brake));

public static final SoftwareLimitSwitchConfigs GENERAL_SOFTWARE_LIMIT_CONFIGS =
new SoftwareLimitSwitchConfigs()
.withForwardSoftLimitEnable(false)
.withReverseSoftLimitEnable(false);

public static final FeedbackConfigs GENERAL_FEEDBACK_CONFIGS =
new FeedbackConfigs()
.withSensorToMechanismRatio(CANCODER_TO_MECHANISM)
.withRotorToSensorRatio(MOTOR_TO_CANCODER)
.withFeedbackSensorSource(FeedbackSensorSourceValue.FusedCANcoder);

public static final MagnetSensorConfigs GENERAL_CANCODER_CONFIGS =
new MagnetSensorConfigs()
.withAbsoluteSensorDiscontinuityPoint(1)
.withSensorDirection(SensorDirectionValue.CounterClockwise_Positive);
}

/* Left */
public final class ShooterHoodLeft {
public static final int CAN_ID = 34;

/* CANCoder */
public static final int CANCODER_ID = 36;
public static final double CANCODER_ABSOLUTE_OFFSET = 0.0;

public static final FeedbackConfigs FEEDBACK_CONFIGS =
GeneralShooterHood.GENERAL_FEEDBACK_CONFIGS
.withFeedbackRemoteSensorID(CANCODER_ID)
.withFeedbackRotorOffset(-CANCODER_ABSOLUTE_OFFSET);

public static final MagnetSensorConfigs CANCODER_CONFIGS =
GeneralShooterHood.GENERAL_CANCODER_CONFIGS
.withMagnetOffset(-1 * CANCODER_ABSOLUTE_OFFSET);
}

public final class FlywheelLeaderLeft {
public static final int CAN_ID = 30;
public static final int BEAM_BREAK_PORT = 0; // TODO: update later

public static final TalonFXConfiguration CONFIG = GeneralFlywheel.GENERAL_CONFIG;
}

public final class FlywheelFollowerLeft {
public static final int CAN_ID = 31;
public static final double SIM_MOI = 0.001;
public static final int BEAM_BREAK_ID = 0;

public static final TalonFXConfiguration CONFIG =
GeneralFlywheel.GENERAL_CONFIG
.withMotorOutput(
new MotorOutputConfigs()
.withInverted(InvertedValue.CounterClockwise_Positive));
}

public final class TurretLeft {
public static final int CAN_ID = 20;

// +x -> forward; +y -> left
public static final Translation3d ROBOT_TO_TURRET =
new Translation3d(
Units.inchesToMeters(4.5),
Units.inchesToMeters(7.505),
Units.inchesToMeters(15.340));

/* CANCoder */
public static final int CANCODER_ID = 22;
public static final double CANCODER_ABSOLUTE_OFFSET = 0.0;

public static final double MIN_POSITION_ROTATIONS = 0 - Units.radiansToRotations(GeneralTurret.EPSILON_RADS);
public static final double MAX_POSITION_ROTATIONS = 150.0 / 360.0 + Units.radiansToRotations(GeneralTurret.EPSILON_RADS);

public static final double MIN_POSITION_RADS = Units.rotationsToRadians(MIN_POSITION_ROTATIONS);
public static final double MAX_POSITION_RADS = Units.rotationsToRadians(MAX_POSITION_ROTATIONS);

public static final SoftwareLimitSwitchConfigs SOFTWARE_LIMIT_CONFIGS =
GeneralTurret.GENERAL_SOFTWARE_LIMIT_CONFIGS
.withReverseSoftLimitThreshold(MIN_POSITION_ROTATIONS)
.withForwardSoftLimitThreshold(MAX_POSITION_ROTATIONS);

public static final FeedbackConfigs FEEDBACK_CONFIGS =
GeneralTurret.GENERAL_FEEDBACK_CONFIGS
.withFeedbackRemoteSensorID(CANCODER_ID)
.withFeedbackRotorOffset(-CANCODER_ABSOLUTE_OFFSET);

public static final MagnetSensorConfigs CANCODER_CONFIGS =
GeneralTurret.GENERAL_CANCODER_CONFIGS
.withMagnetOffset(-1 * CANCODER_ABSOLUTE_OFFSET);
}

/* Right */
public final class ShooterHoodRight {
public static final int CAN_ID = 35;

/* CANCoder */
public static final int CANCODER_ID = 37;
public static final double CANCODER_ABSOLUTE_OFFSET = 0.0;

public static final FeedbackConfigs FEEDBACK_CONFIGS =
GeneralShooterHood.GENERAL_FEEDBACK_CONFIGS
.withFeedbackRemoteSensorID(CANCODER_ID)
.withFeedbackRotorOffset(-CANCODER_ABSOLUTE_OFFSET);

public static final MagnetSensorConfigs CANCODER_CONFIGS =
GeneralShooterHood.GENERAL_CANCODER_CONFIGS
.withMagnetOffset(-1 * CANCODER_ABSOLUTE_OFFSET);
}

public final class FlywheelLeaderRight {
public static final int CAN_ID = 32;
public static final int BEAM_BREAK_PORT = 0; // TODO: update later

public static final TalonFXConfiguration CONFIG = GeneralFlywheel.GENERAL_CONFIG;
}

public final class FlywheelFollowerRight {
public static final int CAN_ID = 33;

public static final TalonFXConfiguration CONFIG =
GeneralFlywheel.GENERAL_CONFIG
.withMotorOutput(
new MotorOutputConfigs()
.withInverted(InvertedValue.CounterClockwise_Positive));
}

public final class TurretRight {
public static final int CAN_ID = 21;

// +x -> forward; +y -> left
public static final Translation3d ROBOT_TO_TURRET =
new Translation3d(
Units.inchesToMeters(4.5),
Units.inchesToMeters(-7.505),
Units.inchesToMeters(15.340));

/* CANCoder */
public static final int CANCODER_ID = 23;
public static final double CANCODER_ABSOLUTE_OFFSET = 0.0;

public static final double MIN_POSITION_ROTATIONS = -150.0 / 360.0 - Units.radiansToRotations(GeneralTurret.EPSILON_RADS);
public static final double MAX_POSITION_ROTATIONS = 0.0 + Units.radiansToRotations(GeneralTurret.EPSILON_RADS);

public static final double MIN_POSITION_RADS = Units.rotationsToRadians(MIN_POSITION_ROTATIONS);
public static final double MAX_POSITION_RADS = Units.rotationsToRadians(MAX_POSITION_ROTATIONS);

public static final SoftwareLimitSwitchConfigs SOFTWARE_LIMIT_CONFIGS =
GeneralTurret.GENERAL_SOFTWARE_LIMIT_CONFIGS
.withReverseSoftLimitThreshold(MIN_POSITION_ROTATIONS)
.withForwardSoftLimitThreshold(MAX_POSITION_ROTATIONS);

public static final FeedbackConfigs FEEDBACK_CONFIGS =
GeneralTurret.GENERAL_FEEDBACK_CONFIGS
.withFeedbackRemoteSensorID(CANCODER_ID)
.withFeedbackRotorOffset(-CANCODER_ABSOLUTE_OFFSET);

public static final MagnetSensorConfigs CANCODER_CONFIGS =
GeneralTurret.GENERAL_CANCODER_CONFIGS
.withMagnetOffset(-1 * CANCODER_ABSOLUTE_OFFSET);
}
}
Loading
Loading