From b2c4b37eda2b83ad095c68ce6ebe5cf4579964d0 Mon Sep 17 00:00:00 2001 From: chris park Date: Wed, 4 Mar 2026 19:55:12 -0500 Subject: [PATCH 1/2] Updated CAN IDs for all devices --- src/main/java/frc/robot/Constants.java | 20 ++++++++++++++----- src/main/java/frc/robot/RobotContainer.java | 18 ++++++++--------- .../frc/robot/generated/TunerConstants.java | 16 +++++++-------- 3 files changed, 32 insertions(+), 22 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 66e5dc5..c10e550 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -149,17 +149,27 @@ public class FieldConstants { public class Ports { // Constants for Port Values - public static final Device.CAN IntakeRoller = new CAN(1, "rio"); + public static final Device.CAN IntakeRoller = new CAN(11, "rio"); + public static final Device.CAN IntakePivot = new CAN(22, "rio"); + + public static final Device.CAN Spindexer = new CAN(40, "rio"); + + public static final Device.CAN TowerRoller = new CAN(13, "rio"); + public static final Device.CAN LeftFlywheel = new CAN(43, "rio"); + public static final Device.CAN RightFlywheel = new CAN(56, "rio"); + public static final Device.CAN HoodMotor = new CAN(44, "rio"); + + public static final Device.CAN ClimberMotor = new CAN(50, "rio"); + public static final Device.CAN LEDs = new CAN(2, "rio"); - public static final Device.CAN HopperRoller = new CAN(3, "rio"); - public static final Device.CAN ClimberLinearMechanism = new CAN(4, "rio"); - public static final Device.CAN ShooterRoller = new CAN(5, "rio"); + public static final Device.CAN Pigeon = new CAN(0, "rio"); + } public class HopperConstants { // holds constants for the hopper - public static final String MOTOR_NAME = "Hopper Roller"; + public static final String MOTOR_NAME = "Spindexer"; // CHANGE TO PROPER RPMS !!!! diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 330cbdd..07d8f66 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -98,24 +98,24 @@ public RobotContainer() { new MotorIOTalonFX( HopperConstants.MOTOR_NAME, HopperConstants.getFXConfig(), - Ports.HopperRoller))); + Ports.Spindexer))); shooter = new Shooter( new FlywheelMechanismReal( new MotorIOTalonFX( ShooterFlywheelConstants.NAME, ShooterFlywheelConstants.getFXConfig(), - Ports.ShooterRoller)), + Ports.LeftFlywheel)), new FlywheelMechanismReal( new MotorIOTalonFX( ShooterFlywheelConstants.NAME, ShooterFlywheelConstants.getFXConfig(), - Ports.ShooterRoller)), + Ports.TowerRoller)), new RotaryMechanismReal( new MotorIOTalonFX( ShooterRotaryConstants.NAME, ShooterRotaryConstants.getFXConfig(), - Ports.ShooterRoller), + Ports.HoodMotor), Constants.ShooterRotaryConstants.CONSTANTS, java.util.Optional.empty())); @@ -130,7 +130,7 @@ public RobotContainer() { new MotorIOTalonFX( IntakePivotConstants.NAME, IntakePivotConstants.getFXConfig(), - Ports.IntakeRoller), + Ports.IntakePivot), IntakePivotConstants.CONSTANTS, Optional.empty())); vision = @@ -158,7 +158,7 @@ public RobotContainer() { new MotorIOTalonFXSim( HopperConstants.MOTOR_NAME, HopperConstants.getFXConfig(), - Ports.HopperRoller), + Ports.Spindexer), HopperConstants.DCMOTOR, HopperConstants.MOI, HopperConstants.TOLERANCE)); @@ -168,7 +168,7 @@ public RobotContainer() { new MotorIOTalonFXSim( ShooterFlywheelConstants.NAME, ShooterFlywheelConstants.getFXConfig(), - Ports.ShooterRoller), + Ports.LeftFlywheel), ShooterFlywheelConstants.DCMOTOR, ShooterFlywheelConstants.MOI, ShooterFlywheelConstants.TOLERANCE), @@ -176,7 +176,7 @@ public RobotContainer() { new MotorIOTalonFXSim( ShooterFlywheelConstants.NAME, ShooterFlywheelConstants.getFXConfig(), - Ports.ShooterRoller), + Ports.TowerRoller), ShooterFlywheelConstants.DCMOTOR, ShooterFlywheelConstants.MOI, ShooterFlywheelConstants.TOLERANCE), @@ -184,7 +184,7 @@ public RobotContainer() { new MotorIOTalonFXSim( ShooterRotaryConstants.NAME, ShooterRotaryConstants.getFXConfig(), - Ports.ShooterRoller), + Ports.HoodMotor), ShooterRotaryConstants.DCMOTOR, ShooterRotaryConstants.MOI, true, diff --git a/src/main/java/frc/robot/generated/TunerConstants.java b/src/main/java/frc/robot/generated/TunerConstants.java index 5f1fb8c..fc20735 100644 --- a/src/main/java/frc/robot/generated/TunerConstants.java +++ b/src/main/java/frc/robot/generated/TunerConstants.java @@ -135,8 +135,8 @@ public class TunerConstants { .withDriveFrictionVoltage(kDriveFrictionVoltage); // Front Left - private static final int kFrontLeftDriveMotorId = 11; - private static final int kFrontLeftSteerMotorId = 21; + private static final int kFrontLeftDriveMotorId = 35; + private static final int kFrontLeftSteerMotorId = 12; private static final int kFrontLeftEncoderId = 1; private static final Angle kFrontLeftEncoderOffset = Rotations.of(-0.1416015625); private static final boolean kFrontLeftSteerMotorInverted = true; @@ -146,8 +146,8 @@ public class TunerConstants { private static final Distance kFrontLeftYPos = Inches.of(10.25); // Front Right - private static final int kFrontRightDriveMotorId = 14; - private static final int kFrontRightSteerMotorId = 24; + private static final int kFrontRightDriveMotorId = 41; + private static final int kFrontRightSteerMotorId = 42; private static final int kFrontRightEncoderId = 4; private static final Angle kFrontRightEncoderOffset = Rotations.of(-0.1748046875); private static final boolean kFrontRightSteerMotorInverted = true; @@ -157,8 +157,8 @@ public class TunerConstants { private static final Distance kFrontRightYPos = Inches.of(-10.25); // Back Left - private static final int kBackLeftDriveMotorId = 12; - private static final int kBackLeftSteerMotorId = 22; + private static final int kBackLeftDriveMotorId = 21; + private static final int kBackLeftSteerMotorId = 25; private static final int kBackLeftEncoderId = 2; private static final Angle kBackLeftEncoderOffset = Rotations.of(-0.369384765625); private static final boolean kBackLeftSteerMotorInverted = true; @@ -168,8 +168,8 @@ public class TunerConstants { private static final Distance kBackLeftYPos = Inches.of(10.25); // Back Right - private static final int kBackRightDriveMotorId = 13; - private static final int kBackRightSteerMotorId = 23; + private static final int kBackRightDriveMotorId = 31; + private static final int kBackRightSteerMotorId = 32; private static final int kBackRightEncoderId = 3; private static final Angle kBackRightEncoderOffset = Rotations.of(-0.388916015625); private static final boolean kBackRightSteerMotorInverted = true; From be4d4a0ae9090fc3233dc69af7bcf9f23111de7f Mon Sep 17 00:00:00 2001 From: chris park Date: Wed, 4 Mar 2026 19:57:59 -0500 Subject: [PATCH 2/2] i hate this --- src/main/java/frc/robot/Constants.java | 1 - src/main/java/frc/robot/RobotContainer.java | 4 +--- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index c10e550..2147a5f 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -163,7 +163,6 @@ public class Ports { public static final Device.CAN LEDs = new CAN(2, "rio"); public static final Device.CAN Pigeon = new CAN(0, "rio"); - } public class HopperConstants { diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 07d8f66..43eb209 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -156,9 +156,7 @@ public RobotContainer() { new Hopper( new FlywheelMechanismSim( new MotorIOTalonFXSim( - HopperConstants.MOTOR_NAME, - HopperConstants.getFXConfig(), - Ports.Spindexer), + HopperConstants.MOTOR_NAME, HopperConstants.getFXConfig(), Ports.Spindexer), HopperConstants.DCMOTOR, HopperConstants.MOI, HopperConstants.TOLERANCE));