From 82be568dc4e3127e5794333ff341d0dbba3dde54 Mon Sep 17 00:00:00 2001 From: mimigamin Date: Wed, 1 Apr 2026 17:58:15 -0600 Subject: [PATCH] Switch Motor type --- src/main/java/frc4388/robot/RobotMap.java | 4 +-- .../robot/constants/BuildConstants.java | 10 +++---- .../subsystems/intake/IntakeConstants.java | 28 +++++++++++-------- .../robot/subsystems/intake/IntakeReal.java | 9 +++--- 4 files changed, 28 insertions(+), 23 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index fe771bf..21cf606 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -101,7 +101,7 @@ public class RobotMap { //Configure Intake 20,21 SparkMax arm = new SparkMax(IntakeConstants.ARM_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless); - SparkMax roller = new SparkMax(IntakeConstants.ROLLER_ID.id, com.revrobotics.spark.SparkLowLevel.MotorType.kBrushless); + TalonFX roller = new TalonFX(IntakeConstants.ROLLER_ID.id, Constants.CANIVORE_CANBUS); // DigitalInput armLimitSwitch = new DigitalInput(IntakeConstants.ARM_LIMIT_SWITCH_CHANNEL); // DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH); // DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH); @@ -120,7 +120,7 @@ public class RobotMap { FaultTalonFX.addDevice(shooter2, "Shooter2"); FaultTalonFX.addDevice(indexer, "Indexer"); FaultSparkMax.addDevice(arm, "Arm"); - FaultSparkMax.addDevice(roller, "Roller"); + FaultTalonFX.addDevice(roller, "Roller"); FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive"); FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer"); diff --git a/src/main/java/frc4388/robot/constants/BuildConstants.java b/src/main/java/frc4388/robot/constants/BuildConstants.java index f6d9f2d..59403f0 100644 --- a/src/main/java/frc4388/robot/constants/BuildConstants.java +++ b/src/main/java/frc4388/robot/constants/BuildConstants.java @@ -7,12 +7,12 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "2026KPopRobotHunters"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 197; - public static final String GIT_SHA = "2407a900c901efca8c60d0a6143e39db7cf90201"; - public static final String GIT_DATE = "2026-03-31 19:47:27 MDT"; + public static final int GIT_REVISION = 198; + public static final String GIT_SHA = "958bdc46fd90b8388750f8bf1a95b62ff91b2092"; + public static final String GIT_DATE = "2026-03-31 20:51:47 MDT"; public static final String GIT_BRANCH = "New-Intake"; - public static final String BUILD_DATE = "2026-03-31 20:33:43 MDT"; - public static final long BUILD_UNIX_TIME = 1775010823079L; + public static final String BUILD_DATE = "2026-04-01 17:29:06 MDT"; + public static final long BUILD_UNIX_TIME = 1775086146983L; public static final int DIRTY = 1; private BuildConstants(){} diff --git a/src/main/java/frc4388/robot/subsystems/intake/IntakeConstants.java b/src/main/java/frc4388/robot/subsystems/intake/IntakeConstants.java index c08d337..a5f7c02 100644 --- a/src/main/java/frc4388/robot/subsystems/intake/IntakeConstants.java +++ b/src/main/java/frc4388/robot/subsystems/intake/IntakeConstants.java @@ -1,5 +1,9 @@ package frc4388.robot.subsystems.intake; +import com.ctre.phoenix6.configs.CurrentLimitsConfigs; +import com.ctre.phoenix6.configs.MotorOutputConfigs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.signals.NeutralModeValue; import com.revrobotics.spark.FeedbackSensor; import com.revrobotics.spark.config.SparkMaxConfig; import com.revrobotics.spark.config.LimitSwitchConfig.Behavior; @@ -85,7 +89,7 @@ public class IntakeConstants { // Motor configs public static final SparkMaxConfig ARM_MOTOR_CONFIG = new SparkMaxConfig(); - public static final SparkMaxConfig ROLELR_MOTOR_CONFIG = new SparkMaxConfig(); + public static final CanDevice ROLLER_MOTOR_ID = new CanDevice("INTAKE_ROLLER", 21); static { ARM_MOTOR_CONFIG.limitSwitch @@ -101,7 +105,7 @@ public class IntakeConstants { ARM_MOTOR_CONFIG.idleMode(IdleMode.kBrake); - ROLELR_MOTOR_CONFIG.idleMode(IdleMode.kCoast); + // ROLLER_MOTOR_CONFIG.idleMode(IdleMode.kCoast); } // public static final TalonFXConfiguration ARM_MOTOR_CONFIG = new TalonFXConfiguration() @@ -115,14 +119,14 @@ public class IntakeConstants { // .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means // ); - // public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration() - // .withCurrentLimits( - // new CurrentLimitsConfigs() - // .withStatorCurrentLimit(40) // TODO: tune??? - // .withStatorCurrentLimitEnable(true) - // ).withMotorOutput( - // new MotorOutputConfigs() - // .withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny - // .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means - // ); + public static final TalonFXConfiguration ROLLER_MOTOR_CONFIG = new TalonFXConfiguration() + .withCurrentLimits( + new CurrentLimitsConfigs() + .withStatorCurrentLimit(40) // TODO: tune??? + .withStatorCurrentLimitEnable(true) + ).withMotorOutput( + new MotorOutputConfigs() + .withNeutralMode(NeutralModeValue.Coast) // Must be coast because this is spinny spinny + .withDutyCycleNeutralDeadband(0.04) // TODO: Figure out what this means + ); } diff --git a/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java b/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java index 1ccfd72..4d294be 100644 --- a/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java +++ b/src/main/java/frc4388/robot/subsystems/intake/IntakeReal.java @@ -21,17 +21,18 @@ import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.Velocity; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.DutyCycleEncoder; +import frc4388.robot.subsystems.shooter.ShooterConstants; import frc4388.utility.compute.JankCoder; public class IntakeReal implements IntakeIO { SparkMax m_armMotor; - SparkMax m_rollerMotor; + TalonFX m_rollerMotor; JankCoder m_encoder; public IntakeReal( SparkMax armMotor, - SparkMax rollerMotor, + TalonFX rollerMotor, JankCoder jankCoder ) { // m_angleMotor = angleMotor; @@ -41,7 +42,7 @@ public class IntakeReal implements IntakeIO { m_encoder = jankCoder; m_armMotor.configure(IntakeConstants.ARM_MOTOR_CONFIG, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters); - m_rollerMotor.configure(IntakeConstants.ROLELR_MOTOR_CONFIG, ResetMode.kNoResetSafeParameters, PersistMode.kPersistParameters); + m_rollerMotor.getConfigurator().apply(IntakeConstants.ROLLER_MOTOR_CONFIG); } @@ -113,7 +114,7 @@ public class IntakeReal implements IntakeIO { state.armMotorCurrent = Amps.of(m_armMotor.getOutputCurrent()); state.rollerOutput = m_rollerMotor.get(); - state.rollerMotorCurrent = Amps.of(m_rollerMotor.getOutputCurrent()); + // state.rollerMotorCurrent = Amps.of(m_rollerMotor.getOutputCurrent()); state.retractedSoftLimit = retractedLimit(); state.extendedSoftLimit = extendedLimit();