This commit is contained in:
Shikhar
2026-01-29 18:07:19 -07:00
parent 8bda61b983
commit 5d38173168
7 changed files with 76 additions and 14 deletions
@@ -30,7 +30,7 @@ public class LED extends SubsystemBase implements Queryable {
private static Spark LEDController = new Spark(LEDConstants.LED_SPARK_ID);
private LEDPatterns mode = LEDConstants.DEFAULT_PATTERN;
//hello
public void setMode(LEDPatterns pattern){
this.mode = pattern;
}
@@ -34,6 +34,7 @@ public class Intake extends SubsystemBase {
switch (mode) {
case Up:
io.setArmAngle(state, IntakeConstants.ARM_LIMIT_UPPER);
io.setRollerVelocity(state, IntakeConstants.ROLLER_STOP);
break;
case Down:
io.setArmAngle(state, IntakeConstants.ARM_LIMIT_LOWER);
@@ -33,7 +33,9 @@ public class IntakeConstants {
// negative is left, positive is right
public static final Angle ARM_LIMIT_LOWER = Degrees.of(-180);
public static final Angle ARM_LIMIT_UPPER = Degrees.of(180);
public static final AngularVelocity ROLLER_MAX_VELOCITY = RotationsPerSecond.of(0.0);
public static final AngularVelocity ROLLER_MAX_VELOCITY = RotationsPerSecond.of(4.0);
public static final AngularVelocity ROLLER_STOP = RotationsPerSecond.of(0.0);
public static final Slot0Configs ARM_PID = new Slot0Configs()
.withKP(2.0)
@@ -1,7 +1,5 @@
package frc4388.robot.subsystems.shooter;
import static edu.wpi.first.units.Units.Rotation;
import java.util.function.Supplier;
import org.littletonrobotics.junction.Logger;
@@ -9,7 +7,8 @@ import org.littletonrobotics.junction.Logger;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc4388.utility.status.FaultReporter;
import frc4388.robot.subsystems.intake.IntakeConstants;
import frc4388.robot.subsystems.shooter.ShooterIO.ShooterState;
public class Shooter extends SubsystemBase {
ShooterIO io;
@@ -17,6 +16,7 @@ public class Shooter extends SubsystemBase {
Supplier<Pose2d> m_swervePoseSupplier;
public Shooter(
ShooterIO io,
Supplier<Pose2d> swervePoseSupplier
@@ -33,12 +33,43 @@ public class Shooter extends SubsystemBase {
}
public enum ShooterMode {
//Shooter is at speed it fires balls
Active,
//Shooter is at a resting velocity
Resting,
//Shooter is inactive (Off)
Inactive,
}
public void setMode(ShooterMode mode) {
switch (mode) {
case Active:
io.setMotor1Velocity(state, ShooterConstants.SHOOTER_ACTIVE_VELOCITY);
io.setMotor2Velocity(state, ShooterConstants.SHOOTER_ACTIVE_VELOCITY);
io.setIndexerVelocity(state, ShooterConstants.INDEXER_ACTIVE_VELOCITY);
break;
case Resting:
io.setMotor1Velocity(state, ShooterConstants.SHOOTER_RESTING_VELOCITY);
io.setMotor2Velocity(state, ShooterConstants.SHOOTER_RESTING_VELOCITY);
io.setIndexerVelocity(state, ShooterConstants.INDEXER_INACTIVE_VELOCITY);
break;
case Inactive:
io.setMotor1Velocity(state, ShooterConstants.SHOOTER_RESTING_VELOCITY);
io.setMotor2Velocity(state, ShooterConstants.SHOOTER_RESTING_VELOCITY);
io.setIndexerVelocity(state, ShooterConstants.INDEXER_INACTIVE_VELOCITY);
break;
}
}
// Calculate what should be done based off of the position of the robot
// TODO: Implement field zones
public FieldZone getTarget(Pose2d position) {
return FieldZone.InShootZone;
}
@Override
public void periodic() {
@@ -1,6 +1,7 @@
package frc4388.robot.subsystems.shooter;
import static edu.wpi.first.units.Units.Degrees;
import static edu.wpi.first.units.Units.RotationsPerSecond;
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.configs.MotorOutputConfigs;
@@ -9,6 +10,7 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.AngularVelocity;
import frc4388.utility.status.CanDevice;
public class ShooterConstants {
@@ -19,6 +21,15 @@ public class ShooterConstants {
public static final double SHOOTERMOTOR2_GEAR_RATIO = 1.;
public static final double INDEXER_GEAR_RATIO = 1.;
public static final AngularVelocity SHOOTER_RESTING_VELOCITY = RotationsPerSecond.of(0.0);
public static final AngularVelocity SHOOTER_ACTIVE_VELOCITY = RotationsPerSecond.of(0.0);
public static final AngularVelocity SHOOTER_INACTIVE_VELOCITY = RotationsPerSecond.of(0.0);
public static final AngularVelocity INDEXER_ACTIVE_VELOCITY = RotationsPerSecond.of(0.0);
public static final AngularVelocity INDEXER_INACTIVE_VELOCITY = RotationsPerSecond.of(0.0);
public static Slot0Configs SHOOTER_PID = new Slot0Configs()
.withKV(0.0)
.withKP(0.0)