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
*
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);
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);
}
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() {
}