Skip to content
Open
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
20 changes: 10 additions & 10 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -103,10 +103,11 @@ public RobotContainer() {
// rollerSubsystem = new RollerSubsystem(RollerSubsystem.createRealIo());
// tiltSubsystem = new TiltSubsystem(TiltSubsystem.createRealIo());
anglerSubsystem = new AnglerSubsystem(AnglerSubsystem.createRealIo());
intakeDeployer = new IntakeDeployerSubsystem(IntakeDeployerSubsystem.createRealIo());
intakeSubsystem = new IntakeSubsystem(IntakeSubsystem.createRealIo(),
IntakeSubsystem.createRealDeploymentSwitch());
intakeDeployer);
hopperSubsystem = new HopperSubsystem(HopperSubsystem.createRealIo());
intakeDeployer = new IntakeDeployerSubsystem(IntakeDeployerSubsystem.createRealIo());


climberSubsystem = new ClimberSubsystem(ClimberSubsystem.createRealIo());
feederSubsystem = new FeederSubsystem(FeederSubsystem.createRealIo());
Expand All @@ -124,14 +125,15 @@ public RobotContainer() {
// rollerSubsystem = new RollerSubsystem(RollerSubsystem.createMockIo());
// tiltSubsystem = new TiltSubsystem(TiltSubsystem.createMockIo());
anglerSubsystem = new AnglerSubsystem(AnglerSubsystem.createMockIo());
intakeDeployer = new IntakeDeployerSubsystem(IntakeDeployerSubsystem.createMockIo());
intakeSubsystem = new IntakeSubsystem(IntakeSubsystem.createMockIo(),
IntakeSubsystem.createMockDeploymentSwitch());
intakeDeployer);
hopperSubsystem = new HopperSubsystem(HopperSubsystem.createMockIo());
climberSubsystem = new ClimberSubsystem(ClimberSubsystem.createMockIo());
feederSubsystem = new FeederSubsystem(FeederSubsystem.createMockIo());
apriltagSubsystem = new ApriltagSubsystem(ApriltagSubsystem.createMockIo());
shooterSubsystem = new ShooterSubsystem(ShooterSubsystem.createMockIo());
intakeDeployer = new IntakeDeployerSubsystem(IntakeDeployerSubsystem.createMockIo());

// No GyroSubsystem in REPLAY for now
// create the drive subsystem with null gyro (use default json)
drivebase = !Constants.TESTBED ? new SwerveSubsystem(
Expand All @@ -144,14 +146,15 @@ public RobotContainer() {
// tiltSubsystem = new
// TiltSubsystem(TiltSubsystem.createSimIo(robotVisualizer));
anglerSubsystem = new AnglerSubsystem(AnglerSubsystem.createSimIo(robotVisualizer));
intakeDeployer = new IntakeDeployerSubsystem(IntakeDeployerSubsystem.createSimIo(robotVisualizer));
intakeSubsystem = new IntakeSubsystem(IntakeSubsystem.createSimIo(robotVisualizer),
IntakeSubsystem.createSimDeploymentSwitch());
intakeDeployer);
hopperSubsystem = new HopperSubsystem(HopperSubsystem.createSimIo(robotVisualizer));
climberSubsystem = new ClimberSubsystem(ClimberSubsystem.createSimIo(robotVisualizer));
feederSubsystem = new FeederSubsystem(FeederSubsystem.createSimIo(robotVisualizer));
apriltagSubsystem = new ApriltagSubsystem(ApriltagSubsystem.createSimIo());
shooterSubsystem = new ShooterSubsystem(ShooterSubsystem.createSimIo(robotVisualizer));
intakeDeployer = new IntakeDeployerSubsystem(IntakeDeployerSubsystem.createSimIo(robotVisualizer));


// No GyroSubsystem in REPLAY for now
// create the drive subsystem with null gyro (use default json)
Expand Down Expand Up @@ -295,7 +298,7 @@ public void putShuffleboardCommands() {

SmartDashboard.putData(
"Spin Intake",
new SpinIntake(intakeSubsystem));
new SpinIntake(intakeSubsystem, intakeDeployer));

SmartDashboard.putData(
"Start Hopper",
Expand All @@ -304,9 +307,6 @@ public void putShuffleboardCommands() {
SmartDashboard.putData(
"Spin Feeder",
new SpinFeeder(feederSubsystem));
SmartDashboard.putData(
"Spin Intake",
new SpinIntake(intakeSubsystem));

SmartDashboard.putData(
"Start Hopper",
Expand Down
8 changes: 6 additions & 2 deletions src/main/java/frc/robot/commands/intake/SpinIntake.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,16 +3,20 @@
import javax.lang.model.util.ElementScanner14;

import frc.robot.constants.Constants;
import frc.robot.constants.enums.DeploymentState;
import frc.robot.subsystems.IntakeDeployerSubsystem;
import frc.robot.subsystems.IntakeSubsystem;
import frc.robot.utils.logging.commands.LoggableCommand;

public class SpinIntake extends LoggableCommand {

private final IntakeSubsystem subsystem;
private final IntakeDeployerSubsystem deployer;

public SpinIntake(IntakeSubsystem subsystem) {
public SpinIntake(IntakeSubsystem subsystem, IntakeDeployerSubsystem deployer) {
this.subsystem = subsystem;
addRequirements(subsystem);
this.deployer = deployer;
}

@Override
Expand All @@ -21,7 +25,7 @@ public void initialize() {

@Override
public void execute() {
if (subsystem.isDeployed()) {
if (deployer.deploymentState == DeploymentState.DOWN) {
subsystem.setSpeed(Constants.INTAKE_SPEED);
} else {
subsystem.setSpeed(0);
Expand Down
46 changes: 4 additions & 42 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,18 +7,12 @@
import com.revrobotics.spark.config.SparkBaseConfig;
import com.revrobotics.spark.config.SparkMaxConfig;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.commands.intake.SpinIntake;
import frc.robot.constants.Constants;
import frc.robot.utils.logging.input.DigitalInputLoggableInputs;
import frc.robot.utils.logging.input.MotorLoggableInputs;
import frc.robot.utils.logging.io.motor.DigitalInputIo;
import frc.robot.utils.logging.io.motor.MockDigitalInputIo;
import frc.robot.utils.logging.io.motor.MockSparkMaxIo;
import frc.robot.utils.logging.io.motor.RealDigitalInputIo;
import frc.robot.utils.logging.io.motor.RealSparkMaxIo;
import frc.robot.utils.logging.io.motor.SimDigitalInputIo;
import frc.robot.utils.logging.io.motor.SimSparkMaxIo;
import frc.robot.utils.logging.io.motor.SparkMaxIo;
import frc.robot.utils.simulation.MotorSimulator;
Expand All @@ -28,12 +22,12 @@ public class IntakeSubsystem extends SubsystemBase {

public static final String LOGGING_NAME = "IntakeSubsystem";
private final SparkMaxIo io;
private final DigitalInputIo intakeDeploymentSwitch;
private final IntakeDeployerSubsystem deployer;

public IntakeSubsystem(SparkMaxIo io, DigitalInputIo intakeDeploymentSwitch) {
public IntakeSubsystem(SparkMaxIo io, IntakeDeployerSubsystem deployer) {
this.io = io;
this.intakeDeploymentSwitch = intakeDeploymentSwitch;
setDefaultCommand(new SpinIntake(this));
this.deployer = deployer;
setDefaultCommand(new SpinIntake(this, deployer));
}

public void setSpeed(double speed) {
Expand All @@ -47,11 +41,6 @@ public void stopMotors() {
@Override
public void periodic() {
io.periodic();
intakeDeploymentSwitch.periodic();
}

public boolean isDeployed() {
return intakeDeploymentSwitch.isPressed();
}

public static SparkMaxIo createMockIo() {
Expand All @@ -66,30 +55,6 @@ public static SparkMaxIo createSimIo(RobotVisualizer visualizer) {
new MotorSimulator(motor, visualizer.getIntakeLigament()));
}

public static DigitalInputIo createMockDeploymentSwitch() {
return new MockDigitalInputIo(
LOGGING_NAME + "/DeploymentSwitch",
new DigitalInputLoggableInputs()
);
}

public static DigitalInputIo createRealDeploymentSwitch() {
return new RealDigitalInputIo(
LOGGING_NAME + "/DeploymentSwitch",
new DigitalInput(Constants.INTAKE_DIGITAL_INPUT_CHANNEL),
new DigitalInputLoggableInputs()
);

}

public static DigitalInputIo createSimDeploymentSwitch() {
return new SimDigitalInputIo(
LOGGING_NAME + "/DeploymentSwitch",
new DigitalInput(Constants.INTAKE_DIGITAL_INPUT_CHANNEL),
new DigitalInputLoggableInputs()
);
}

private static SparkMax createMotor() {
SparkMax motor = new SparkMax(Constants.INTAKE_MOTOR_ID, SparkLowLevel.MotorType.kBrushless);
SparkMaxConfig motorConfig = new SparkMaxConfig();
Expand All @@ -102,7 +67,4 @@ private static SparkMax createMotor() {
return motor;
}

public DigitalInputIo getDeploymentSwitchIo() {
return intakeDeploymentSwitch;
}
}
2 changes: 0 additions & 2 deletions src/main/java/frc/robot/subsystems/RollerSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,6 @@
import frc.robot.utils.simulation.MotorSimulator;
import frc.robot.utils.simulation.RobotVisualizer;

// The Roller subsystem spins the wheel that releases the algae.

public class RollerSubsystem extends SubsystemBase {
public static final String LOGGING_NAME = "RollerSubsystem";
private final SparkMaxIo io;
Expand Down
2 changes: 0 additions & 2 deletions src/main/java/frc/robot/subsystems/TiltSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@
import frc.robot.utils.simulation.ArmSimulator;
import frc.robot.utils.simulation.RobotVisualizer;

// The Tilt subsystem extends and retracts the Algae-Go-Bye-Bye mechanism.

public class TiltSubsystem extends SubsystemBase {
public static final String LOGGING_NAME = "TiltSubsystem";
private final SparkMaxIo io;
Expand Down