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