Skip to content

Commit

Permalink
Merge pull request #7 from OakvilleDynamics/Dump
Browse files Browse the repository at this point in the history
New Dump Code
  • Loading branch information
Kendialouge authored Jan 28, 2024
2 parents 057f33b + 869fe00 commit febe278
Show file tree
Hide file tree
Showing 3 changed files with 113 additions and 0 deletions.
19 changes: 19 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,13 +32,32 @@ public static final class Auton {
public static final double MAX_ACCELERATION = 2;
}

public static final class PneumaticsConstants {

public static final int PneumaticsMoudleID = 30;

public static final class DumpConstants {

// Upy Downy solonoid
public static final int OUT = 0;
public static final int IN = 1;
}

public static final class ElevatorConstants {
// upy downy chain lift thing

}
}

public static final class Drivebase {

// Hold time on motor brakes when disabled
public static final double WHEEL_LOCK_TIME = 10; // seconds
}

public static class OperatorConstants {
public static final int DRIVER_CONTROLLER = 0;
public static final int COPILOT_CONTROLLER = 1;

// Joystick Deadband
public static final double LEFT_X_DEADBAND = 0.01;
Expand Down
48 changes: 48 additions & 0 deletions src/main/java/frc/robot/commands/DumpControl.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
// 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.

package frc.robot.commands;

import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants.OperatorConstants;
import frc.robot.subsystems.Dump;

public class DumpControl extends Command {

private static Dump DumpSubsystem;

private static Joystick Controller = new Joystick(OperatorConstants.COPILOT_CONTROLLER);

/** Creates a new PneumaticsControl. */
public DumpControl(Dump subsystem) {
DumpSubsystem = subsystem;
addRequirements(subsystem);
// Use addRequirements() here to declare subsystem dependencies.
}

// 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 (Controller.getRawButton(1)) {
DumpSubsystem.open();
} else if (Controller.getRawButton(2)) {
DumpSubsystem.close();
}
}

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

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

package frc.robot.subsystems;

import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.PneumaticsConstants;
import frc.robot.Constants.PneumaticsConstants.DumpConstants;

public class Dump extends SubsystemBase {

// The double solenoid that controls the piston
private DoubleSolenoid doubleSolenoid =
new DoubleSolenoid(
PneumaticsConstants.PneumaticsMoudleID,
PneumaticsModuleType.REVPH,
DumpConstants.IN,
DumpConstants.OUT);

/** Creates a new Pneumatics subsystem. */
public Dump() {
System.out.println("Pneumatics initialized");
SmartDashboard.putBoolean(getName(), false);
}

/** Opens the piston */
public void open() {
doubleSolenoid.set(DoubleSolenoid.Value.kForward);
SmartDashboard.putBoolean(getName(), true);
}

/** Closes the piston */
public void close() {
doubleSolenoid.set(DoubleSolenoid.Value.kReverse);
SmartDashboard.putBoolean(getName(), false);
}

@Override
public void periodic() {
// This method will be called once per scheduler run
}
}

0 comments on commit febe278

Please sign in to comment.