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 edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.CounterBase.EncodingType;
import edu.wpi.first.wpilibj.DoubleSolenoid;
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);
+ angleAdjuster = new CANTalon(Constants.Shooter.ANGLE_ADJUSTER_PORT);
+ 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(Constants.Shooter.LIDAR_I2C_PORT);
}
/***
}
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() {
}
// Punch Commands
- public void punch() {
+ public void extendPunch() {
punch.set(Constants.Shooter.punch);
}
punch.set(Constants.Shooter.retract);
}
+ public boolean isHoodOpen() {
+ return hood.get() == Constants.Shooter.open;
+ }
+
+ public void openHood() {
+ hood.set(Constants.Shooter.open);
+ }
+
+ public void closeHood() {
+ hood.set(Constants.Shooter.closed);
+ }
+
@Override
protected void initDefaultCommand() {
}