X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FShooter.java;h=3633c04ca10e2fea9e5c63a656427a86642eaea1;hb=ee31518f357dbc4d63f2790938c0c71dcad088af;hp=f01d8c2743c1ef50c89f09da92cadf1ddb39989d;hpb=06fda04bacae40be4392d54b6d4644fafffa0706;p=3501%2Fstronghold-2016 diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java index f01d8c27..3633c04c 100755 --- a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java @@ -1,14 +1,12 @@ package org.usfirst.frc.team3501.robot.subsystems; import org.usfirst.frc.team3501.robot.Constants; -import org.usfirst.frc.team3501.robot.Lidar; -import org.usfirst.frc.team3501.robot.MathLib; +import org.usfirst.frc.team3501.robot.sensors.Lidar; import edu.wpi.first.wpilibj.CANTalon; import edu.wpi.first.wpilibj.CounterBase.EncodingType; import edu.wpi.first.wpilibj.DoubleSolenoid; import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.I2C; import edu.wpi.first.wpilibj.command.Subsystem; /*** @@ -23,21 +21,21 @@ import edu.wpi.first.wpilibj.command.Subsystem; public class Shooter extends Subsystem { private CANTalon shooter; - private DoubleSolenoid hood, punch; + private DoubleSolenoid hood1, hood2, punch; private Encoder encoder; private Lidar lidar; public Shooter() { shooter = new CANTalon(Constants.Shooter.PORT); - hood = new DoubleSolenoid(Constants.Shooter.HOOD_FORWARD, + hood1 = new DoubleSolenoid(Constants.Shooter.HOOD_FORWARD, + Constants.Shooter.HOOD_REVERSE); + hood2 = new DoubleSolenoid(Constants.Shooter.HOOD_FORWARD, Constants.Shooter.HOOD_REVERSE); punch = new DoubleSolenoid(Constants.Shooter.PUNCH_FORWARD, Constants.Shooter.PUNCH_REVERSE); encoder = new Encoder(Constants.Shooter.ENCODER_PORT_A, Constants.Shooter.ENCODER_PORT_B, false, EncodingType.k4X); - - lidar = new Lidar(I2C.Port.kMXP); } /*** @@ -53,8 +51,12 @@ public class Shooter extends Subsystem { } public void setSpeed(double speed) { - speed = MathLib.constrain(speed, -1, 1); - shooter.set(speed); + if (speed > 1.0) + shooter.set(1.0); + else if (speed < -1.0) + shooter.set(-1.0); + else + shooter.set(speed); } public void stop() { @@ -65,6 +67,17 @@ public class Shooter extends Subsystem { return encoder.getRate(); } + /* + * We are going to map a lidar distance to a shooter speed that will be set to + * the shooter. This function does not yet exist so we will just use y=x but + * when testing commences we shall create the function + */ + public double getShooterSpeed() { + double distanceToGoal = lidar.getDistance(); + double shooterSpeed = distanceToGoal; // Function to be determined + return shooterSpeed; + } + // Use negative # for decrement. Positive for increment. public void changeSpeed(double change) { @@ -73,7 +86,7 @@ public class Shooter extends Subsystem { } // Punch Commands - public void punch() { + public void extendPunch() { punch.set(Constants.Shooter.punch); } @@ -81,16 +94,21 @@ public class Shooter extends Subsystem { punch.set(Constants.Shooter.retract); } - public boolean isHoodOpen() { - return hood.get() == Constants.Shooter.open; + public void raiseHood() { + hood1.set(Constants.Shooter.open); + hood2.set(Constants.Shooter.open); } - public void openHood() { - hood.set(Constants.Shooter.open); + public void lowerHood() { + hood1.set(Constants.Shooter.closed); + hood2.set(Constants.Shooter.closed); } - public void closeHood() { - hood.set(Constants.Shooter.closed); + public boolean isHoodDown() { + if (hood1.get() == Constants.Shooter.open + && hood2.get() == Constants.Shooter.open) + return true; + return false; } @Override