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
53 changes: 23 additions & 30 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction;
import frc.lib.utils.LocalADStarAK;
import frc.robot.RobotState.IntakePosition;
import frc.robot.commands.auto.Autos;
import frc.robot.commands.auto.DriveToPose;
import frc.robot.commands.drive.DriveCommands;
Expand All @@ -51,7 +50,6 @@
import frc.robot.subsystems.shooter.ShooterIOSparkMax;
import frc.robot.subsystems.vision.Vision;
import frc.robot.subsystems.vision.VisionIOPhotonVision;
import frc.robot.util.CustomTriggers;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

Expand Down Expand Up @@ -149,6 +147,7 @@ public RobotContainer() {
// leds = new Leds();
// hopperBelt = new HopperBelt(new HopperBeltSparkMax());
leds = new Leds();
shooter = new Shooter(new ShooterIOSparkMax(false));
}
}
}
Expand Down Expand Up @@ -333,28 +332,30 @@ private void configureButtonBindings() {
.ignoringDisable(true));
new Trigger(() -> driverController.getHID().getPOV() != -1)
.whileTrue(new DriveWithDpad(drive, () -> driverController.getHID().getPOV()));
driverController.x().toggleOnTrue(orchestrator.aimToHub());
driverController.y().toggleOnTrue(intake.extendToAngleAndIntake(IntakeConstants.COLLAPSE_POS));
driverController
.leftBumper()
.and(operatorController.pov(180))
.whileTrue(intake.runIntakeExtendVolts(-4))
.onFalse(intake.stopExtendingCommand());
CustomTriggers.toggleIntakeUp(
driverController.leftBumper(),
() -> RobotState.getInstance().intakePosition == IntakePosition.DEPLOYED)
.and(() -> !operatorController.pov(180).getAsBoolean())
.toggleOnTrue(intake.extendToAngle(IntakeConstants.COLLAPSE_POS));
CustomTriggers.toggleIntakeDown(
driverController.leftBumper(),
() -> RobotState.getInstance().intakePosition == IntakePosition.STOWED)
.and(() -> !operatorController.pov(180).getAsBoolean())
.toggleOnTrue(intake.extendToAngleAndIntake(IntakeConstants.EXTEND_POS));
// driverController.x().toggleOnTrue(orchestrator.aimToHub());
//
// driverController.y().toggleOnTrue(intake.extendToAngleAndIntake(IntakeConstants.COLLAPSE_POS));
// driverController
// .leftBumper()
// .and(operatorController.pov(180))
// .whileTrue(intake.runIntakeExtendVolts(-4))
// .onFalse(intake.stopExtendingCommand());
// CustomTriggers.toggleIntakeUp(
// driverController.leftBumper(),
// () -> RobotState.getInstance().intakePosition == IntakePosition.DEPLOYED)
// .and(() -> !operatorController.pov(180).getAsBoolean())
// .toggleOnTrue(intake.extendToAngle(IntakeConstants.COLLAPSE_POS));
// CustomTriggers.toggleIntakeDown(
// driverController.leftBumper(),
// () -> RobotState.getInstance().intakePosition == IntakePosition.STOWED)
// .and(() -> !operatorController.pov(180).getAsBoolean())
// .toggleOnTrue(intake.extendToAngleAndIntake(IntakeConstants.EXTEND_POS));

// VERY IMPORTANT BECAUSE COMMAND GROUP DOESN'T MESH WITH SHOOTING DON'T COMBINE
driverController.leftTrigger(0.2).toggleOnTrue(intake.intake());
// driverController.leftTrigger(0.2).toggleOnTrue(intake.intake());
driverController.rightTrigger(0.1).toggleOnTrue(orchestrator.feedUp());
driverController.a().and(operatorController.pov(180)).onTrue(intake.resetExtendPosition());
//
// driverController.a().and(operatorController.pov(180)).onTrue(intake.resetExtendPosition());
driverController
.rightBumper()
.and(() -> !operatorController.pov(180).getAsBoolean())
Expand All @@ -374,17 +375,9 @@ private void configureButtonBindings() {
.rightTrigger(0.1)
.and(operatorController.pov(0))
.toggleOnTrue(orchestrator.spinUpShooterHub());
operatorController.leftTrigger(0.1).toggleOnTrue(orchestrator.spinUpShooterTest());
operatorController.leftTrigger(0.1).toggleOnTrue(shooter.setVoltage(12));
operatorController.y().whileTrue(indexer.reverse());
// operatorController.x().whileTrue(intake.outtake());

operatorController
.leftTrigger()
.whileTrue(
shooter.setTargetVelocityRadians(
() ->
operatorController.getLeftY()
* Units.rotationsPerMinuteToRadiansPerSecond(5600)));
}

/**
Expand Down
35 changes: 20 additions & 15 deletions src/main/java/frc/robot/Schematic.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,10 @@ public class Schematic {
public static final int backRightAbsoluteEncoderCanId;

// shooter subsystem
public static final int shooterBottomMotorCanId;
public static final int shooterTopMotorCanId;
public static final int shooterMiddleMotorCanId;
public static final int shooterTopLeftMotorCanId;
public static final int shooterTopRightMotorCanId;
public static final int shooterBottomLeftMotorCanId;
public static final int shooterBottomRightMotorCanId;
// magic carpet sub-system
public static final int magicCarpetCanId;

Expand Down Expand Up @@ -60,9 +61,10 @@ public class Schematic {
backLeftAbsoluteEncoderCanId = 20;

// Shooter (CAN Ids)
shooterBottomMotorCanId = 0;
shooterTopMotorCanId = 0;
shooterMiddleMotorCanId = 0;
shooterTopLeftMotorCanId = 0;
shooterTopRightMotorCanId = 0;
shooterBottomLeftMotorCanId = 0;
shooterBottomRightMotorCanId = 0;

// Magic Carpet (CAN Ids)
magicCarpetCanId = 0;
Expand Down Expand Up @@ -99,9 +101,10 @@ public class Schematic {
backLeftAbsoluteEncoderCanId = 21;

// Shooter (CAN Ids)
shooterTopMotorCanId = 11;
shooterMiddleMotorCanId = 12;
shooterBottomMotorCanId = 13;
shooterTopLeftMotorCanId = 11;
shooterTopRightMotorCanId = 12;
shooterBottomLeftMotorCanId = 13;
shooterBottomRightMotorCanId = 14;

// Hopper (CAN Ids)
magicCarpetCanId = 15;
Expand Down Expand Up @@ -137,9 +140,10 @@ public class Schematic {
backRightAbsoluteEncoderCanId = 0;

// Shooter (CAN Ids)
shooterBottomMotorCanId = 0;
shooterTopMotorCanId = 0;
shooterMiddleMotorCanId = 0;
shooterTopLeftMotorCanId = 8;
shooterTopRightMotorCanId = 1;
shooterBottomLeftMotorCanId = 7;
shooterBottomRightMotorCanId = 2;

// Magic Carpet (CAN Ids)
magicCarpetCanId = 0;
Expand Down Expand Up @@ -175,9 +179,10 @@ public class Schematic {
backRightAbsoluteEncoderCanId = 0;

// Shooter (CAN Ids)
shooterBottomMotorCanId = 0;
shooterTopMotorCanId = 0;
shooterMiddleMotorCanId = 0;
shooterTopLeftMotorCanId = 0;
shooterTopRightMotorCanId = 0;
shooterBottomLeftMotorCanId = 0;
shooterBottomRightMotorCanId = 0;

// Magic Carpet (CAN Ids)
magicCarpetCanId = 0;
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@ public void periodic() {

Logger.processInputs("Shooter", inputs);
Logger.recordOutput("Shooter/AtSetpoint", isAtSetpoint());
RobotState.getInstance().shooterAtSpeed = isAtSetpoint();
}

public void runCharacterization(double voltage) {
Expand Down Expand Up @@ -107,9 +108,8 @@ public Command stop() {
}

public Command setVoltage(double volts) {
return Commands.sequence(
Commands.runOnce(() -> controllerEnabled = false, this),
Commands.run(() -> io.setVoltage(volts), this));
return Commands.runOnce(() -> controllerEnabled = false, this)
.andThen(Commands.run(() -> io.setVoltage(volts), this));
}

public Command setTargetVelocityRPM(double rpm) {
Expand Down
31 changes: 20 additions & 11 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,20 +6,21 @@ public interface ShooterIO {

@AutoLog
class ShooterIOInputs {
public double middleMotorVelocityRadPerSec;
public double middleMotorAppliedVolts;
public double middleMotorCurrentAmps;
public double topLeftMotorVelocityRadPerSec;
public double topLeftMotorAppliedVolts;
public double topLeftMotorCurrentAmps;

public double bottomMotorVelocityRadPerSec;
public double bottomMotorAppliedVolts;
public double bottomMotorCurrentAmps;
public double topRightMotorVelocityRadPerSec;
public double topRightMotorAppliedVolts;
public double topRightMotorCurrentAmps;

public double topMotorVelocityRadPerSec;
public double topMotorAppliedVolts;
public double topMotorCurrentAmps;
public double bottomLeftMotorVelocityRadPerSec;
public double bottomLeftMotorAppliedVolts;
public double bottomLeftMotorCurrentAmps;

public boolean atSetpoint = false;
public double setpointRPM = 0;
public double bottomRightMotorVelocityRadPerSec;
public double bottomRightMotorAppliedVolts;
public double bottomRightMotorCurrentAmps;

public double totalAmps;

Expand All @@ -31,5 +32,13 @@ default void updateInputs(ShooterIOInputs inputs) {}

default void setVoltage(double volts) {}

default void setTopLeftVoltage(double volts) {}

default void setTopRightVoltage(double volts) {}

default void setBottomLeftVoltage(double volts) {}

default void setBottomRightVoltage(double volts) {}

default void stop() {}
}
Loading
Loading