Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update Pneumatics Code to Use Spikes #178

Merged
merged 8 commits into from
Apr 4, 2024
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
28 changes: 17 additions & 11 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,17 +37,8 @@ public static final class Mailbox {

/** Constants for the Pneumatics system. */
public static final class MailboxPneumatics {
/** The channel on the PCM for the forward direction on the left solenoid. */
public static final int LEFT_SOLENOID_FORWARD_CHANNEL = 5;

/** The channel on the PCM for the reverse direction on the left solenoid. */
public static final int LEFT_SOLENOID_REVERSE_CHANNEL = 4;

/** The channel on the PCM for the forward direction on the right solenoid. */
public static final int RIGHT_SOLENOID_FORWARD_CHANNEL = 7;

/** The channel on the PCM for the reverse direction on the right solenoid. */
public static final int RIGHT_SOLENOID_REVERSE_CHANNEL = 6;
/** The ID for the relay that controls the mailbox's solenoids */
public static final int MAILBOX_SOLENOID_RELAY_ID = 0;
}

/** Constants for the Belts system. */
Expand Down Expand Up @@ -234,4 +225,19 @@ public static final class Camera {
/** The camera id for the intake camera. */
public static final int INTAKE_CAMERA_ID = 0;
}

/** The constants for the Compressor */
public static final class Compressor {
/** The DIO port for the pressure switch. */
public static final int PRESSURE_SWITCH_DIO_PORT = 9;

/** The relay port for the compressor */
public static final int COMPRESSOR_RELAY_PORT = 0;

/**
* How many periodic loops do we want to wait for to turn off the compressor. Used to prevent
* rapidly turning on and off the compressor.
*/
public static final int COMPRESSOR_PRESSURE_SWITCH_DEADBAND = 100; /* = 2 Seconds */
}
}
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
import frc.robot.commands.ClearPDPStickyFaults;
import frc.robot.commands.ClimbDown;
import frc.robot.commands.ClimbUp;
import frc.robot.commands.ControlCompressor;
import frc.robot.commands.DeployUrMom;
import frc.robot.commands.EnterXMode;
import frc.robot.commands.RunIntake;
Expand All @@ -45,6 +46,7 @@
import frc.robot.commands.mailbox.RunBelts;
import frc.robot.subsystems.Camera;
import frc.robot.subsystems.Climber;
import frc.robot.subsystems.Compressor;
import frc.robot.subsystems.Drive;
import frc.robot.subsystems.Intake;
import frc.robot.subsystems.Limelight;
Expand Down Expand Up @@ -99,6 +101,9 @@ public class RobotContainer {
/** Singleton instance of the intake {@link Camera} for the whole robot. */
public static Camera intakeCamera = new Camera(Constants.Camera.INTAKE_CAMERA_ID);

/** Singleton instance of the intake {@link Compressor} for the whole robot. */
public static Compressor compressor = new Compressor();
quackitsquinn marked this conversation as resolved.
Show resolved Hide resolved

/*
* ************
* * COMMANDS *
Expand Down Expand Up @@ -257,6 +262,9 @@ public class RobotContainer {
/** Singleton instance of {@link ZeroGyro} for the whole robot. */
public static ZeroGyro zeroGyro = new ZeroGyro();

/** Singleton instance of {@link ControlCompressor} for the whole robot. */
public static ControlCompressor controlCompressor = new ControlCompressor();
quackitsquinn marked this conversation as resolved.
Show resolved Hide resolved

/*
* ***********************
* * OTHER INSTANCE VARS *
Expand Down Expand Up @@ -286,6 +294,7 @@ public RobotContainer() {
startIntakeCamera.schedule();

drive.setDefaultCommand(driveFieldOrientedHeadingSnapping);
compressor.setDefaultCommand(controlCompressor);
}

private void configureAuto() {
Expand Down
60 changes: 60 additions & 0 deletions src/main/java/frc/robot/commands/ControlCompressor.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

/*
* Asimov's Laws:
* The First Law: A robot may not injure a human being or, through inaction, allow a human being to come to harm.
* The Second Law: A robot must obey the orders given it by human beings except where such orders would conflict with the First Law.
* The Third Law: A robot must protect its own existence as long as such protection does not conflict with the First or Second Law.
*/

package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.RobotContainer;
import frc.robot.subsystems.Compressor;

/** Keeps the compressor at the pressure the pressure switch looks for. */
public class ControlCompressor extends Command {
private Compressor compressor;
private int callsAtPressure = 0;

/** Create a new ControlCompressor */
public ControlCompressor() {
compressor = RobotContainer.compressor;
addRequirements(compressor);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if (compressor.isAtPressure()) {
callsAtPressure++;
} else {
callsAtPressure = Math.max(0, callsAtPressure - 1);
}
if (callsAtPressure < Constants.Compressor.COMPRESSOR_PRESSURE_SWITCH_DEADBAND) {
compressor.activateCompressor();
} else {
compressor.disableCompressor();
}
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
compressor.disableCompressor();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
64 changes: 64 additions & 0 deletions src/main/java/frc/robot/subsystems/Compressor.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

/*
* Asimov's Laws:
* The First Law: A robot may not injure a human being or, through inaction, allow a human being to come to harm.
* The Second Law: A robot must obey the orders given it by human beings except where such orders would conflict with the First Law.
* The Third Law: A robot must protect its own existence as long as such protection does not conflict with the First or Second Law.
*/

package frc.robot.subsystems;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Relay;
import edu.wpi.first.wpilibj.Relay.Value;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

/** The subsystem for the compressor */
public class Compressor extends SubsystemBase {
private Relay compressorRelay;
private DigitalInput pressureSwitch;

/** Creates a new Compressor. */
public Compressor() {
this.compressorRelay = new Relay(Constants.Compressor.COMPRESSOR_RELAY_PORT);
this.pressureSwitch = new DigitalInput(Constants.Compressor.PRESSURE_SWITCH_DIO_PORT);
}

/**
* Activates the compressor.
*
* @return If the compressor was able to be turned on.
*/
public boolean activateCompressor() {
if (!this.pressureSwitch.get()) {
this.compressorRelay.set(Value.kForward);
return true;
} else {
DriverStation.reportWarning(
"Warning: Attempted to activate compressor while pressure switch activated", false);
return false;
}
}

/** Disables the compressor. */
public void disableCompressor() {
this.compressorRelay.set(Relay.Value.kOff);
}

/**
* Returns true if the compressor is at pressure. False otherwise.
*
* @return true if the compressor is at pressure. False otherwise.
*/
public boolean isAtPressure() {
return this.pressureSwitch.get();
}

@Override
public void periodic() {}
}
26 changes: 6 additions & 20 deletions src/main/java/frc/robot/subsystems/mailbox/MailboxPneumatics.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,7 @@

package frc.robot.subsystems.mailbox;

import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.Relay;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

Expand All @@ -21,39 +20,26 @@
* our robot
*/
public class MailboxPneumatics extends SubsystemBase {
private DoubleSolenoid leftPiston;
private DoubleSolenoid rightPiston;
private Relay pneumaticsRelay;

/** Constructor for the mailbox pneumatics subsystem. */
public MailboxPneumatics() {
leftPiston =
new DoubleSolenoid(
PneumaticsModuleType.CTREPCM,
Constants.MailboxPneumatics.LEFT_SOLENOID_FORWARD_CHANNEL,
Constants.MailboxPneumatics.LEFT_SOLENOID_REVERSE_CHANNEL);
rightPiston =
new DoubleSolenoid(
PneumaticsModuleType.CTREPCM,
Constants.MailboxPneumatics.RIGHT_SOLENOID_FORWARD_CHANNEL,
Constants.MailboxPneumatics.RIGHT_SOLENOID_REVERSE_CHANNEL);
pneumaticsRelay = new Relay(Constants.MailboxPneumatics.MAILBOX_SOLENOID_RELAY_ID);
}

/** Lifts the mailbox. */
public void extend() {
leftPiston.set(DoubleSolenoid.Value.kForward);
rightPiston.set(DoubleSolenoid.Value.kForward);
pneumaticsRelay.set(Relay.Value.kForward);
}

/** Lowers the mailbox. */
public void retract() {
leftPiston.set(DoubleSolenoid.Value.kReverse);
rightPiston.set(DoubleSolenoid.Value.kReverse);
pneumaticsRelay.set(Relay.Value.kReverse);
}

/** Sets pistons to off */
public void off() {
leftPiston.set(DoubleSolenoid.Value.kOff);
rightPiston.set(DoubleSolenoid.Value.kOff);
pneumaticsRelay.set(Relay.Value.kOff);
}

@Override
Expand Down
Loading