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.sensors.Lidar;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.CounterBase.EncodingType;
public class Shooter extends Subsystem {
private CANTalon shooter;
- private CANTalon angleAdjuster;
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);
+ hood = new DoubleSolenoid(Constants.Shooter.HOOD_FORWARD,
+ Constants.Shooter.HOOD_REVERSE);
punch = new DoubleSolenoid(Constants.Shooter.PUNCH_FORWARD,
Constants.Shooter.PUNCH_REVERSE);
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) {
punch.set(Constants.Shooter.retract);
}
+ public void raiseHood() {
+ hood.set(Constants.Shooter.open);
+ }
+
+ public void lowerHood() {
+ hood.set(Constants.Shooter.closed);
+ }
+
@Override
protected void initDefaultCommand() {
}