1 package org
.usfirst
.frc
.team3501
.robot
.subsystems
;
3 import org
.usfirst
.frc
.team3501
.robot
.Constants
;
5 import edu
.wpi
.first
.wpilibj
.CANTalon
;
6 import edu
.wpi
.first
.wpilibj
.DoubleSolenoid
;
7 import edu
.wpi
.first
.wpilibj
.command
.Subsystem
;
9 public class Shooter
extends Subsystem
{
10 private CANTalon shooter
;
11 private CANTalon angleAdjuster
;
12 private DoubleSolenoid punch
;
15 shooter
= new CANTalon(Constants
.Shooter
.PORT
);
16 punch
= new DoubleSolenoid(Constants
.Shooter
.FORWARD_PORT
,
17 Constants
.Shooter
.REVERSE_PORT
);
20 public double getCurrentSetPoint() {
24 public void setSpeed(double speed
) {
27 else if (speed
< -1.0)
37 // Use negative # for decrement. Positive for increment.
38 public void changeSpeed(double change
) {
39 double newSpeed
= getCurrentSetPoint() + change
;
42 else if (newSpeed
< -1.0)
51 punch
.set(Constants
.Shooter
.punch
);
54 public void resetPunch() {
55 punch
.set(Constants
.Shooter
.retract
);
59 protected void initDefaultCommand() {