From 3f55c7b2b844d2e80513ce180066e5288c3d9a64 Mon Sep 17 00:00:00 2001 From: Adam Long Date: Mon, 12 Sep 2016 20:04:15 +0000 Subject: [PATCH] added compressor code --- src/org/usfirst/frc/team2059/robot/Robot.java | 3 ++ .../team2059/robot/commands/CommandBase.java | 3 ++ .../team2059/robot/subsystems/Pneumatics.java | 43 +++++++++++++++++++ 3 files changed, 49 insertions(+) create mode 100644 src/org/usfirst/frc/team2059/robot/subsystems/Pneumatics.java diff --git a/src/org/usfirst/frc/team2059/robot/Robot.java b/src/org/usfirst/frc/team2059/robot/Robot.java index 11a2942..7487212 100644 --- a/src/org/usfirst/frc/team2059/robot/Robot.java +++ b/src/org/usfirst/frc/team2059/robot/Robot.java @@ -16,6 +16,7 @@ public class Robot extends IterativeRobot { chooser = new SendableChooser(); SmartDashboard.putData("Auto mode", chooser); SmartDashboard.putData("MainArm",CommandBase.mainArm.getPIDController()); + SmartDashboard.putBoolean("CompressorEnabled",true); } public void disabledInit() { } @@ -35,11 +36,13 @@ public class Robot extends IterativeRobot { if (autonomousCommand != null) { autonomousCommand.cancel(); } + CommandBase.pneumatics.setCompressorEnabled(true); } public void teleopPeriodic() { Scheduler.getInstance().run(); SmartDashboard.putNumber("ArmAngleRaw",CommandBase.mainArm.getRaw()); SmartDashboard.putNumber("ArmAngleDegrees",CommandBase.mainArm.getDegrees()); + CommandBase.pneumatics.setCompressorEnabled(SmartDashboard.getBoolean("CompressorEnabled")); System.out.println(CommandBase.mainArm.getDegrees()); } public void testPeriodic() { diff --git a/src/org/usfirst/frc/team2059/robot/commands/CommandBase.java b/src/org/usfirst/frc/team2059/robot/commands/CommandBase.java index e7bd8d5..8677a4b 100644 --- a/src/org/usfirst/frc/team2059/robot/commands/CommandBase.java +++ b/src/org/usfirst/frc/team2059/robot/commands/CommandBase.java @@ -2,15 +2,18 @@ package org.usfirst.frc.team2059.robot.commands; import org.usfirst.frc.team2059.robot.subsystems.DriveBase; import org.usfirst.frc.team2059.robot.subsystems.EncoderBase; import org.usfirst.frc.team2059.robot.subsystems.MainArm; +import org.usfirst.frc.team2059.robot.subsystems.Pneumatics; import edu.wpi.first.wpilibj.command.Command; public abstract class CommandBase extends Command { public static EncoderBase encoderBase; public static DriveBase driveBase; public static MainArm mainArm; + public static Pneumatics pneumatics; public static void init() { encoderBase = new EncoderBase(); driveBase = new DriveBase(); mainArm = new MainArm(); + pneumatics = new Pneumatics(); } } // vim: sw=2:ts=2:sts=2 diff --git a/src/org/usfirst/frc/team2059/robot/subsystems/Pneumatics.java b/src/org/usfirst/frc/team2059/robot/subsystems/Pneumatics.java new file mode 100644 index 0000000..cf4cc22 --- /dev/null +++ b/src/org/usfirst/frc/team2059/robot/subsystems/Pneumatics.java @@ -0,0 +1,43 @@ +package org.usfirst.frc.team2059.robot.subsystems; +import org.usfirst.frc.team2059.robot.RobotMap; +import org.usfirst.frc.team2059.robot.commands.Drive; +import edu.wpi.first.wpilibj.command.Subsystem; +import edu.wpi.first.wpilibj.Compressor; +import edu.wpi.first.wpilibj.DoubleSolenoid; +public class Pneumatics extends Subsystem { + Compressor compressor = new Compressor(RobotMap.pcmID); + DoubleSolenoid shooterSolenoid = new DoubleSolenoid(RobotMap.shooterSolenoidOne, RobotMap.shooterSolenoidTwo); + DoubleSolenoid armStopSolenoid = new DoubleSolenoid(RobotMap.armStopSolenoidOne, RobotMap.armStopSolenoidTwo); + boolean shooterState, armStopState; + public void initDefaultCommand() { + } + public void setCompressorEnabled(boolean state){ + compressor.setClosedLoopControl(state); + } + public void setShooterState(boolean state){ + if(state){ + shooterSolenoid.set(DoubleSolenoid.Value.kForward); + }else{ + shooterSolenoid.set(DoubleSolenoid.Value.kReverse); + } + shooterState=state; + } + public void setArmStopState(boolean state){ + if(state){ + armStopSolenoid.set(DoubleSolenoid.Value.kForward); + }else{ + armStopSolenoid.set(DoubleSolenoid.Value.kReverse); + } + armStopState=state; + } + public boolean getShooterState(){ + return shooterState; + } + public boolean getArmStopState(){ + return armStopState; + } + public boolean getCompressorEnabled(){ + return compressor.enabled(); + } +} +// vim: sw=2:ts=2:sts=2