Add command group for ToggleWinch
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
1 package org.usfirst.frc.team3501.robot.subsystems;
2
3 import org.usfirst.frc.team3501.robot.Constants;
4 import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
5 import org.usfirst.frc.team3501.robot.utils.PIDController;
6
7 import com.ctre.CANTalon;
8
9 import edu.wpi.first.wpilibj.ADXRS450_Gyro;
10 import edu.wpi.first.wpilibj.DoubleSolenoid;
11 import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
12 import edu.wpi.first.wpilibj.Encoder;
13 import edu.wpi.first.wpilibj.RobotDrive;
14 import edu.wpi.first.wpilibj.command.Subsystem;
15
16 public class DriveTrain extends Subsystem {
17
18 public static double driveP, driveI, driveD;
19 public static double turnP, turnI, turnD;
20
21 public static double driveStraightGyroP = 0.01;
22
23 public static final String DRIVE_P_Val = "DriveP";
24 public static final String DRIVE_I_Val = "DriveI";
25 public static final String DRIVE_D_Val = "DriveD";
26 public static final String DRIVE_TARGET_DIST = "SET_DIST";
27 public static final String DRIVE_MOTOR_VAL = "SPEED";
28 public static final String GYRO_P_Val = "GyroP";
29 public static final String GYRO_I_Val = "GyroI";
30 public static final String GYRO_D_Val = "GyroD";
31 public static final String GYRO_TARGET_ANGLE = "SET_ANGLE";
32 public static final int PID_ERROR = -1;
33 public static final int TARGET_DISTANCE_ERROR = -1;
34
35 public static final double WHEEL_DIAMETER = 6; // inches
36 public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
37 public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
38 / ENCODER_PULSES_PER_REVOLUTION;
39
40 public static final double MAINTAIN_CLIMBED_POSITION = 0;
41 public static final double TIME_TO_CLIMB_FOR = 0;
42 public static final double CLIMBER_SPEED = 0;
43
44 private static DriveTrain driveTrain;
45
46 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
47 private final RobotDrive robotDrive;
48 private final Encoder leftEncoder, rightEncoder;
49 private final DoubleSolenoid leftGearPiston, rightGearPiston;
50
51 private ADXRS450_Gyro imu;
52
53 public boolean shouldBeClimbing = false;
54
55 private PIDController driveController;
56 private PIDController gyroController;
57
58 private boolean isClimbing;
59 private static double CLIMBER_SPEED;;
60
61 private DriveTrain() {
62
63 driveController = new PIDController(driveP, driveI, driveD);
64 gyroController = new PIDController(turnP, turnI, turnD);
65
66 // PID TUNING
67
68 // MOTOR CONTROLLERS
69 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
70 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
71 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
72 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
73
74 // ENCODERS
75 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
76 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
77 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
78 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
79
80 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
81 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
82
83 // ROBOT DRIVE
84 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
85
86 this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
87
88 // TODO: Not sure if MODULE_NUMBER should be the same for both
89 leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
90 Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
91 Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
92 rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
93 Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
94 Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
95
96 CLIMBER_SPEED = Constants.DriveTrain.CLIMBER_SPEED;
97 }
98
99 public PIDController getDriveController() {
100 return this.driveController;
101 }
102
103 public PIDController getGyroController() {
104 return this.gyroController;
105 }
106
107 public static DriveTrain getDriveTrain() {
108 if (driveTrain == null) {
109 driveTrain = new DriveTrain();
110 }
111 return driveTrain;
112 }
113
114 // DRIVE METHODS
115 public void setMotorValues(final double left, final double right) {
116 frontLeft.set(left);
117 rearLeft.set(left);
118
119 frontRight.set(-right);
120 rearRight.set(-right);
121 this.isClimbing = true;
122 }
123
124 public void joystickDrive(final double thrust, final double twist) {
125 robotDrive.arcadeDrive(thrust, twist, true);
126 }
127
128 public void stop() {
129 setMotorValues(0, 0);
130 this.isClimbing = false;
131 }
132
133 public double getLeftMotorVal() {
134 return (frontLeft.get() + rearLeft.get()) / 2;
135 }
136
137 public double getRightMotorVal() {
138 return (frontRight.get() + rearRight.get()) / 2;
139 }
140
141 // ENCODER METHODS
142
143 public double getLeftEncoderDistance() {
144 return leftEncoder.getDistance();
145 }
146
147 public double getRightEncoderDistance() {
148 return rightEncoder.getDistance();
149 }
150
151 public void printEncoderOutput() {
152 System.out.println("left: " + getLeftEncoderDistance());
153 System.out.println("right: " + getRightEncoderDistance());
154 // System.out.println(getAvgEncoderDistance());
155 }
156
157 public double getAvgEncoderDistance() {
158 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
159 }
160
161 public void resetEncoders() {
162 leftEncoder.reset();
163 rightEncoder.reset();
164 }
165
166 public double getLeftSpeed() {
167 return leftEncoder.getRate();
168 }
169
170 public double getRightSpeed() {
171 return rightEncoder.getRate();
172 }
173
174 public double getSpeed() {
175 return (getLeftSpeed() + getRightSpeed()) / 2.0;
176 }
177
178 // ------Gyro------//
179 public double getAngle() {
180 return this.imu.getAngle();
181 }
182
183 public void resetGyro() {
184 this.imu.reset();
185 }
186
187 /*
188 * @return a value that is the current setpoint for the piston kReverse or
189 * KForward
190 */
191 public Value getLeftGearPistonValue() {
192 return leftGearPiston.get();
193 }
194
195 /*
196 * @return a value that is the current setpoint for the piston kReverse or
197 * KForward
198 */
199 public Value getRightGearPistonValue() {
200 return rightGearPiston.get();
201 }
202
203 /*
204 * Changes the ball shift gear assembly to high
205 */
206 public void setHighGear() {
207 changeGear(Constants.DriveTrain.HIGH_GEAR);
208 }
209
210 /*
211 * Changes the ball shift gear assembly to low
212 */
213 public void setLowGear() {
214 changeGear(Constants.DriveTrain.LOW_GEAR);
215 }
216
217 /*
218 * Changes the gear to a DoubleSolenoid.Value
219 */
220 private void changeGear(DoubleSolenoid.Value gear) {
221 leftGearPiston.set(gear);
222 rightGearPiston.set(gear);
223 }
224
225 @Override
226 protected void initDefaultCommand() {
227 setDefaultCommand(new JoystickDrive());
228 }
229
230 public boolean isClimbing() {
231 return this.isClimbing;
232 }
233
234 public void setClimbing(boolean isClimbing) {
235 this.isClimbing = isClimbing;
236 }
237
238 public double getClimbingSpeed() {
239 return this.CLIMBER_SPEED;
240 }
241
242 }