2a4ccf7788d3f7a44b6d98a28859b3f0af1830f7
[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 }
122
123 public void joystickDrive(final double thrust, final double twist) {
124 robotDrive.arcadeDrive(thrust, twist, true);
125 }
126
127 public void stop() {
128 setMotorValues(0, 0);
129 }
130
131 public double getLeftMotorVal() {
132 return (frontLeft.get() + rearLeft.get()) / 2;
133 }
134
135 public double getRightMotorVal() {
136 return (frontRight.get() + rearRight.get()) / 2;
137 }
138
139 // ENCODER METHODS
140
141 public double getLeftEncoderDistance() {
142 return leftEncoder.getDistance();
143 }
144
145 public double getRightEncoderDistance() {
146 return rightEncoder.getDistance();
147 }
148
149 public void printEncoderOutput() {
150 System.out.println("left: " + getLeftEncoderDistance());
151 System.out.println("right: " + getRightEncoderDistance());
152 // System.out.println(getAvgEncoderDistance());
153 }
154
155 public double getAvgEncoderDistance() {
156 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
157 }
158
159 public void resetEncoders() {
160 leftEncoder.reset();
161 rightEncoder.reset();
162 }
163
164 public double getLeftSpeed() {
165 return leftEncoder.getRate();
166 }
167
168 public double getRightSpeed() {
169 return rightEncoder.getRate();
170 }
171
172 public double getSpeed() {
173 return (getLeftSpeed() + getRightSpeed()) / 2.0;
174 }
175
176 // ------Gyro------//
177 public double getAngle() {
178 return this.imu.getAngle();
179 }
180
181 public void resetGyro() {
182 this.imu.reset();
183 }
184
185 /*
186 * @return a value that is the current setpoint for the piston kReverse or
187 * KForward
188 */
189 public Value getLeftGearPistonValue() {
190 return leftGearPiston.get();
191 }
192
193 /*
194 * @return a value that is the current setpoint for the piston kReverse or
195 * KForward
196 */
197 public Value getRightGearPistonValue() {
198 return rightGearPiston.get();
199 }
200
201 /*
202 * Changes the ball shift gear assembly to high
203 */
204 public void setHighGear() {
205 changeGear(Constants.DriveTrain.HIGH_GEAR);
206 }
207
208 /*
209 * Changes the ball shift gear assembly to low
210 */
211 public void setLowGear() {
212 changeGear(Constants.DriveTrain.LOW_GEAR);
213 }
214
215 /*
216 * Changes the gear to a DoubleSolenoid.Value
217 */
218 private void changeGear(DoubleSolenoid.Value gear) {
219 leftGearPiston.set(gear);
220 rightGearPiston.set(gear);
221 }
222
223 @Override
224 protected void initDefaultCommand() {
225 setDefaultCommand(new JoystickDrive());
226 }
227
228 public boolean isClimbing() {
229 return this.isClimbing;
230 }
231
232 public double getClimbingSpeed() {
233 return this.CLIMBER_SPEED;
234 }
235
236 }