From: Saara21 <113394225+Saara21@users.noreply.github.com> Date: Mon, 16 Feb 2026 18:37:04 +0000 (-0800) Subject: update X-Git-Url: https://git.taranathan.com/?a=commitdiff_plain;h=442d90fc35623ce62bae7ad2738492006a440f88;p=FRC2026.git update --- diff --git a/src/main/java/frc/robot/constants/IntakeConstants.java b/src/main/java/frc/robot/constants/IntakeConstants.java index 45966f6..02bc641 100644 --- a/src/main/java/frc/robot/constants/IntakeConstants.java +++ b/src/main/java/frc/robot/constants/IntakeConstants.java @@ -16,6 +16,10 @@ public class IntakeConstants { public static final double gearRatio = 36.0/12.0; /** radius (inches) of the rack gear which is a 10 tooth pinion at 10 DP */ public static final double radiusRackPinion = 0.5; + /** roller current limits */ + public static final double rCurrentLimits = 10.0; + /**right and left motor current limits */ + public static final double extendCurrentLimits = 40.0; // Intake positions diff --git a/src/main/java/frc/robot/subsystems/Intake/Intake.java b/src/main/java/frc/robot/subsystems/Intake/Intake.java index 1be0d55..2e8d8bf 100644 --- a/src/main/java/frc/robot/subsystems/Intake/Intake.java +++ b/src/main/java/frc/robot/subsystems/Intake/Intake.java @@ -5,6 +5,7 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.Follower; import com.ctre.phoenix6.controls.MotionMagicVoltage; import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.MotorAlignmentValue; import com.ctre.phoenix6.signals.NeutralModeValue; @@ -74,11 +75,10 @@ public class Intake extends SubsystemBase { TalonFXConfiguration rollerConfig = new TalonFXConfiguration(); // config the current limits (low value for testing) - // add constant for currentLimits rollerConfig.CurrentLimits - .withStatorCurrentLimit(40.0) + .withStatorCurrentLimit(IntakeConstants.extendCurrentLimits) .withStatorCurrentLimitEnable(true) - .withSupplyCurrentLimit(40.0) + .withSupplyCurrentLimit(IntakeConstants.extendCurrentLimits) .withSupplyCurrentLimitEnable(true); // config Slot 0 PID params @@ -101,9 +101,9 @@ public class Intake extends SubsystemBase { // config the current limits (low value for testing) config.CurrentLimits - .withStatorCurrentLimit(10.0) + .withStatorCurrentLimit(IntakeConstants.rCurrentLimits) .withStatorCurrentLimitEnable(true) - .withSupplyCurrentLimit(10.0) + .withSupplyCurrentLimit(IntakeConstants.rCurrentLimits) .withSupplyCurrentLimitEnable(true); // config Slot 0 PID params @@ -126,7 +126,7 @@ public class Intake extends SubsystemBase { // apply the configuration to the right motor (master) rightMotor.getConfigurator().apply(config); - + // apply the configuration to the left motor (slave) leftMotor.getConfigurator().apply(config); @@ -148,7 +148,7 @@ public class Intake extends SubsystemBase { SmartDashboard.putData("Retract Intake", new InstantCommand(this::retract)); SmartDashboard.putData("Intake On", new InstantCommand(this::spinStart)); SmartDashboard.putData("Intake Off", new InstantCommand(this::spinStop)); - SmartDashboard.putData("Roller Spin Forward", new InstantCommand(() -> this.spin(0.5), this)); + SmartDashboard.putData("Roller Spin Forward", new InstantCommand(() -> this.spin(0.8), this)); SmartDashboard.putData("Roller Spin Reverse", new InstantCommand(() -> this.spin(-0.5), this)); SmartDashboard.putData("Roller Stop", new InstantCommand(() -> this.spin(0.0), this)); SmartDashboard.putData("Zero Motors", new InstantCommand(this::zeroMotors)); @@ -241,6 +241,7 @@ public class Intake extends SubsystemBase { public void setPosition(double setpoint) { double motorRotations =inchesToRotations(setpoint); rightMotor.setControl(voltageRequest.withPosition(motorRotations)); + } /** diff --git a/src/main/java/frc/robot/subsystems/indexer/Spindexer.java b/src/main/java/frc/robot/subsystems/indexer/Spindexer.java deleted file mode 100644 index e5b4276..0000000 --- a/src/main/java/frc/robot/subsystems/indexer/Spindexer.java +++ /dev/null @@ -1,39 +0,0 @@ -package frc.robot.subsystems.indexer; - -import com.ctre.phoenix6.hardware.TalonFX; - -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.InstantCommand; -import edu.wpi.first.wpilibj2.command.SubsystemBase; - -public class Spindexer extends SubsystemBase { - private TalonFX motor; - - public Spindexer(){ - // TODO: change device id - motor = new TalonFX(1); - - // Smartdashboard commands - SmartDashboard.putData("Run", new InstantCommand(()-> run())); - SmartDashboard.putData("Slow", new InstantCommand(()-> slow())); - SmartDashboard.putData("Reverse", new InstantCommand(()-> reverse())); - SmartDashboard.putData("Stop", new InstantCommand(()-> stop())); - - } - - public void run(){ - motor.set(1); - } - - public void slow(){ - motor.set(0.6); - } - - public void reverse(){ - motor.set(-1); - } - - public void stop(){ - motor.set(0); - } -}