X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FShooter.java;h=e54ca7269297423eaa89db06463b8c4118298b21;hb=cc72c5b29b7239f0eae0c52f395de8da31ed5109;hp=26763d0ed497c848e1565834993c1dfe7301e691;hpb=f5c9f335c504a7b2dd38b8b6e3f1f362211d40d6;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 26763d0e..e54ca726 100755 --- a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java @@ -1,19 +1,20 @@ package org.usfirst.frc.team3501.robot.subsystems; import org.usfirst.frc.team3501.robot.Constants; +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.DoubleSolenoid.Value; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.command.Subsystem; /*** - * The Shooter consists of a platform and wheel, each controlled by - * separate motors. The piston controlling the platform pushes the ball onto the - * wheel. The wheel is controlled by a motor, which is running before the ball - * is pushed - * onto the wheel. The spinning wheel propels the ball. + * The Shooter consists of a platform and wheel, each controlled by separate + * motors. The piston controlling the platform pushes the ball onto the wheel. + * The wheel is controlled by a motor, which is running before the ball is + * pushed onto the wheel. The spinning wheel propels the ball. * * @author superuser * @@ -21,15 +22,16 @@ import edu.wpi.first.wpilibj.command.Subsystem; public class Shooter extends Subsystem { private CANTalon shooter; - private CANTalon angleAdjuster; - private DoubleSolenoid punch; + private DoubleSolenoid hood, punch; private Encoder encoder; + private Lidar lidar; public Shooter() { shooter = new CANTalon(Constants.Shooter.PORT); - angleAdjuster = new CANTalon(Constants.Shooter.ANGLE_ADJUSTER_PORT); - punch = new DoubleSolenoid(Constants.Shooter.PUNCH_FORWARD_PORT, - Constants.Shooter.PUNCH_REVERSE_PORT); + hood = 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); @@ -64,10 +66,21 @@ 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) { - double newSpeed = getCurrentSetPoint() + change; + double newSpeed = getSpeed() + change; setSpeed(newSpeed); } @@ -80,6 +93,20 @@ public class Shooter extends Subsystem { punch.set(Constants.Shooter.retract); } + public void raiseHood() { + hood.set(Constants.Shooter.open); + } + + public void lowerHood() { + hood.set(Constants.Shooter.closed); + } + + public boolean isHoodDown() { + if (hood.get() == Value.kReverse) + return true; + return false; + } + @Override protected void initDefaultCommand() { }