Skip to content

Commit

Permalink
rough snaps start
Browse files Browse the repository at this point in the history
  • Loading branch information
ryanknj5 committed Oct 19, 2024
1 parent 6ecb3ce commit c535453
Show file tree
Hide file tree
Showing 3 changed files with 32 additions and 2 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ public class Robot extends TimedRobot {
private final LocalizationSubsystem localization = new LocalizationSubsystem(imu, vision, swerve);
private final Autos autos = new Autos();
private final RobotManager robotManager =
new RobotManager(arm, shooter, localization, vision, imu, intake, queuer);
new RobotManager(arm, shooter, localization, vision, imu, intake, queuer,swerve);

private final RobotCommands robotCommands = new RobotCommands(robotManager);

Expand Down
26 changes: 25 additions & 1 deletion src/main/java/frc/robot/robot_manager/RobotManager.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@
import frc.robot.queuer.QueuerSubsystem;
import frc.robot.shooter.ShooterState;
import frc.robot.shooter.ShooterSubsystem;
import frc.robot.swerve.SwerveState;
import frc.robot.swerve.SwerveSubsystem;
import frc.robot.util.scheduling.SubsystemPriority;
import frc.robot.util.state_machines.StateMachine;
import frc.robot.vision.VisionSubsystem;
Expand All @@ -23,6 +25,7 @@ public class RobotManager extends StateMachine<RobotState> {
public final ImuSubsystem imu;
public final IntakeSubsystem intake;
public final QueuerSubsystem queuer;
public final SwerveSubsystem swerve;

private final double distanceToFeedSpot = 0.0;
private final double distanceToSpeaker = 0.0;
Expand All @@ -36,7 +39,8 @@ public RobotManager(
VisionSubsystem vision,
ImuSubsystem imu,
IntakeSubsystem intake,
QueuerSubsystem queuer) {
QueuerSubsystem queuer,
SwerveSubsystem swerve) {
super(SubsystemPriority.ROBOT_MANAGER, RobotState.IDLE_NO_GP);
this.arm = arm;
this.shooter = shooter;
Expand All @@ -45,6 +49,7 @@ public RobotManager(
this.imu = imu;
this.intake = intake;
this.queuer = queuer;
this.swerve = swerve;
}

@Override
Expand Down Expand Up @@ -103,102 +108,121 @@ protected void afterTransition(RobotState newState) {
shooter.setState(ShooterState.SUBWOOFER_SHOT);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.IDLE);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case PODIUM_PREPARE_TO_SCORE, PODIUM_WAITING -> {
arm.setState(ArmState.PODIUM_SHOT);
shooter.setState(ShooterState.PODIUM_SHOT);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.IDLE);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case PODIUM_SCORING -> {
arm.setState(ArmState.PODIUM_SHOT);
shooter.setState(ShooterState.PODIUM_SHOT);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.SHOOTING);
swerve.setState(SwerveState.TELEOP_SNAPS);

}
case SUBWOOFER_SCORING -> {
arm.setState(ArmState.SUBWOOFER_SHOT);
shooter.setState(ShooterState.SUBWOOFER_SHOT);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.SHOOTING);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case SPEAKER_PREPARE_TO_SCORE, SPEAKER_WAITING -> {
arm.setState(ArmState.SPEAKER_SHOT);
shooter.setState(ShooterState.SPEAKER_SHOT);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.IDLE);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case SPEAKER_SCORING -> {
arm.setState(ArmState.SPEAKER_SHOT);
shooter.setState(ShooterState.SPEAKER_SHOT);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.SHOOTING);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case AMP_PREPARE_TO_SCORE, AMP_WAITING -> {
arm.setState(ArmState.AMP);
shooter.setState(ShooterState.AMP);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.IDLE);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case AMP_SCORING -> {
arm.setState(ArmState.AMP);
shooter.setState(ShooterState.AMP);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.AMPING);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case FEEDING_PREPARE_TO_SHOOT, FEEDING_WAITING -> {
arm.setState(ArmState.FEEDING);
shooter.setState(ShooterState.FEEDING);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.IDLE);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case FEEDING_SHOOTING -> {
arm.setState(ArmState.FEEDING);
shooter.setState(ShooterState.FEEDING);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.SHOOTING);

swerve.setState(SwerveState.TELEOP_SNAPS);
}
case PASS_PREPARE_TO_SHOOT -> {
arm.setState(ArmState.PASS);
shooter.setState(ShooterState.PASS);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.IDLE);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case PASS_SHOOTING -> {
arm.setState(ArmState.PASS);
shooter.setState(ShooterState.PASS);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.SHOOTING);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case UNJAM -> {
arm.setState(ArmState.AMP);
shooter.setState(ShooterState.PASS);
intake.setState(IntakeState.OUTTAKING);
queuer.setState(QueuerState.OUTTAKING);
swerve.setState(SwerveState.TELEOP);
}
case INTAKING -> {
arm.setState(ArmState.IDLE);
shooter.setState(ShooterState.IDLE_STOPPED);
intake.setState(IntakeState.INTAKING);
queuer.setState(QueuerState.INTAKING);
swerve.setState(SwerveState.TELEOP);
}
case OUTTAKING -> {
arm.setState(ArmState.IDLE);
shooter.setState(ShooterState.IDLE_STOPPED);
intake.setState(IntakeState.OUTTAKING);
queuer.setState(QueuerState.OUTTAKING);
swerve.setState(SwerveState.TELEOP);
}
case CLIMBING_1_LINEUP -> {
arm.setState(ArmState.CLIMBING_1_LINEUP);
shooter.setState(ShooterState.IDLE_STOPPED);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.IDLE);
swerve.setState(SwerveState.TELEOP_SNAPS);
}
case CLIMBING_2_HANGING -> {
arm.setState(ArmState.CLIMBING_2_HANGING);
shooter.setState(ShooterState.IDLE_STOPPED);
intake.setState(IntakeState.IDLE);
queuer.setState(QueuerState.IDLE);
swerve.setState(SwerveState.TELEOP);
}
case IDLE_NO_GP -> {
arm.setState(ArmState.IDLE);
Expand Down
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/swerve/SwerveSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -234,4 +234,10 @@ private void sendSwerveRequest() {
.withDriveRequestType(DriveRequestType.Velocity));
}
}
public void setState(SwerveState newState) {


setStateFromRequest(newState);

}
}

0 comments on commit c535453

Please sign in to comment.