Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
Empty file modified gradlew
100644 → 100755
Empty file.
64 changes: 52 additions & 12 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ public static enum Mode {
public static class ShooterConstants {

public enum ShooterState {
SHOOTING,
SHOOTER,
REVERSE,
IDLE
}
Expand All @@ -60,25 +60,65 @@ public enum ShooterState {
public static final double maxReverseOutput = 0.5;

public static final AngularVelocity shooterSpeed = Units.RPM.of(4000);
public static final AngularVelocity reverseSpeed = Units.RPM.of(-1000);
public static final AngularVelocity reverseSpeed = Units.RPM.of(-1000);
public static final AngularVelocity idleSpeed = Units.RPM.of(0);

public enum ShooterModes {
SHOOTER(shooterSpeed, 1.0),
REVERSE(reverseSpeed, -0.5),
IDLE(idleSpeed, 0.0);
SHOOTER(shooterSpeed, 1.0),
REVERSE(reverseSpeed, -0.5),
IDLE(idleSpeed, 0.0);

public AngularVelocity speed;
public double output;
public AngularVelocity speed;
public double output;

ShooterModes(AngularVelocity speed, double output) {
this.speed = speed;
this.output = output;
}
}
}

public static class IndexerConstants {

ShooterModes(AngularVelocity speed, double output) {
this.speed = speed;
this.output = output;
}
public enum IndexerState {
INDEXER,
REVERSE,
IDLE
}

}
public static final boolean attached = true;

public static final int id = -1;

public static final double p = 1;
public static final double i = 0;
public static final double d = 0;

public static final boolean invert = false;
public static final boolean breakType = false;
public static final double gearRatio = 1 / 1;


public static final Current stallLimit = Units.Amps.of(60);
public static final Current supplyLimit = Units.Amps.of(80);
public static final double maxForwardOutput = 0.5;
public static final double maxReverseOutput = -0.5;

public static final double indexerSpeed = 0.5;
public static final double reverseSpeed = -0.5;
public static final double idleSpeed = 0.0;

public enum IndexerModes {
INDEXER(indexerSpeed),
REVERSE(reverseSpeed),
IDLE(idleSpeed);

public double output;

IndexerModes(double output) {
this.output = output;
}
}
}

public static final class IntakeConstants {
Expand Down
80 changes: 80 additions & 0 deletions src/main/java/frc/robot/subsystems/indexer/Indexer.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
package frc.robot.subsystems.indexer;

import com.ctre.phoenix6.hardware.TalonFX;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import frc.robot.Constants;
import frc.robot.Constants.IndexerConstants;
import frc.robot.Constants.IndexerConstants.IndexerModes;
import frc.robot.Constants.IndexerConstants.IndexerState;
import frc.robot.Constants.IntakeConstants;
import frc.team5431.titan.core.subsystem.CTREMechanism;
import lombok.Getter;
import lombok.Setter;

public class Indexer extends CTREMechanism {

@Getter @Setter private IndexerModes indexerModes;
@Getter @Setter private IndexerState indexerState;

private boolean attached;
private TalonFX motor;

public static class IndexerConfig extends Config {
public IndexerConfig() {
super("Indexer", IndexerConstants.id, Constants.canbus);

configNeutralBrakeMode(IndexerConstants.breakType);
configStatorCurrentLimit(IndexerConstants.stallLimit, true);
configSupplyCurrentLimit(IndexerConstants.supplyLimit, true);
configForwardSoftLimit(IndexerConstants.maxForwardOutput, true);
configReverseSoftLimit(IndexerConstants.maxReverseOutput, true);
configPIDGains(IndexerConstants.p, IndexerConstants.i, IndexerConstants.d);
configPeakOutput(IndexerConstants.maxForwardOutput, IndexerConstants.maxReverseOutput);
configGearRatio(IndexerConstants.gearRatio);
configMotorInverted(IndexerConstants.invert);
}
}

public Indexer(TalonFX motor, boolean attached) {
super(motor, attached);
this.attached = attached;
this.motor = motor;
this.indexerModes = IndexerModes.IDLE;
this.indexerState = IndexerState.IDLE;

config.applyTalonConfig(motor);
}

@Override
public void periodic() {
SmartDashboard.putString("Indexer Mode", getIndexerModes().toString());


switch (this.indexerModes) {
case IDLE:
setIndexerState(IndexerState.IDLE);
break;
case INDEXER:
setIndexerState(IndexerState.INDEXER);
break;
case REVERSE:
setIndexerState(IndexerState.REVERSE);
break;
}

}

public Command runIndexerCommand(IndexerModes indexerModes) {
return new RunCommand(() -> setPercentOutput(indexerModes.output), this).withName("Indexer.runEnum");
}

@Override
public Config setConfig() {
// configure motors/sensors here
this.config = new IndexerConfig();
return this.config;
}
}
1 change: 1 addition & 0 deletions src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ public IntakeConfig() {
IntakeConstants.maxReverseRotation.in(Rotation), IntakeConstants.useRMaxRotation);
configForwardSoftLimit(
IntakeConstants.maxFowardRotation.in(Rotation), IntakeConstants.useFMaxRotation);
configMotorInverted(IntakeConstants.invert);
}
}

Expand Down
37 changes: 26 additions & 11 deletions src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,24 +2,23 @@

import com.ctre.phoenix6.hardware.TalonFX;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import frc.robot.Constants;
import frc.robot.Constants.ShooterConstants;
import frc.robot.Constants.ShooterConstants.ShooterModes;
import frc.robot.Constants.ShooterConstants.ShooterState;
import frc.team5431.titan.core.misc.Logger;
import frc.team5431.titan.core.subsystem.CTREMechanism;
import lombok.Getter;
import lombok.Setter;

public class Shooter extends CTREMechanism {

@Getter
private ShooterState shooterState;
@Getter
@Setter
private ShooterModes shooterMode;
@Getter @Setter private ShooterState shooterState;
@Getter @Setter private ShooterModes shooterMode;
private boolean attached;
private TalonFX motor;

public static class ShooterConfig extends Config {
public ShooterConfig() {
Expand All @@ -32,7 +31,8 @@ public ShooterConfig() {
configReverseSoftLimit(ShooterConstants.maxReverseOutput, true);
configPIDGains(ShooterConstants.p, ShooterConstants.i, ShooterConstants.d);
configPeakOutput(ShooterConstants.maxForwardOutput, ShooterConstants.maxReverseOutput);

configGearRatio(ShooterConstants.gearRatio);
configMotorInverted(ShooterConstants.inverted);
}
}

Expand All @@ -44,14 +44,29 @@ public Shooter(TalonFX motor, boolean attached) {
this.shooterState = ShooterState.IDLE;

config.applyTalonConfig(motor);
this.setConfig();
}


@Override
public void periodic() {
SmartDashboard.putString("Shooter Mode", getShooterMode().toString());


switch (this.shooterMode) {
case IDLE:
setShooterState(ShooterState.IDLE);
break;
case SHOOTER:
setShooterState(ShooterState.SHOOTER);
break;
case REVERSE:
setShooterState(ShooterState.REVERSE);
break;
}

}

public Command runShooterCommand(ShooterModes shooterModes) {
return new RunCommand(() -> setVelocity(shooterModes.speed), this)
.withName("Shooter.runEnum");
return new RunCommand(() -> setVelocity(shooterModes.speed), this).withName("Shooter.runEnum");
}

@Override
Expand Down
Loading