6d09477325061cb9eff162b14cd9882e8ed03a13
[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 public static double driveP, driveI, driveD;
18 public static double turnP, turnI, turnD;
19 public static double driveStraightGyroP = 0.01;
20
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 MAX_TIME_OUT = "MaxTimeOut";
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
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;
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
42 private static DriveTrain driveTrain;
43
44 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
45 private final RobotDrive robotDrive;
46 private final Encoder leftEncoder, rightEncoder;
47 private final DoubleSolenoid leftGearPiston, rightGearPiston;
48
49 private ADXRS450_Gyro imu;
50
51 public boolean shouldBeClimbing = false;
52
53 private PIDController driveController;
54 private PIDController gyroController;
55
56 private boolean isClimbing;
57
58 private DriveTrain() {
59
60 // PID TUNING
61 driveController = new PIDController(driveP, driveI, driveD);
62 gyroController = new PIDController(turnP, turnI, turnD);
63
64 // PID TUNING
65
66 // MOTOR CONTROLLERS
67 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
68 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
69 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
70 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
71
72 // ENCODERS
73 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
74 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
75 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
76 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
77
78 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
79 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
80
81 // ROBOT DRIVE
82 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
83
84 this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
85
86 // TODO: Not sure if MODULE_NUMBER should be the same for both
87 leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
88 Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
89 Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
90 rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
91 Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
92 Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
93 }
94
95 public PIDController getDriveController() {
96 return this.driveController;
97 }
98
99 public PIDController getGyroController() {
100 return this.gyroController;
101 }
102
103 public static DriveTrain getDriveTrain() {
104 if (driveTrain == null) {
105 driveTrain = new DriveTrain();
106 }
107 return driveTrain;
108 }
109
110 // DRIVE METHODS
111 public void setMotorValues(final double left, final double right) {
112 frontLeft.set(left);
113 rearLeft.set(left);
114
115 frontRight.set(-right);
116 rearRight.set(-right);
117 }
118
119 public void joystickDrive(final double thrust, final double twist) {
120 robotDrive.arcadeDrive(thrust, twist, true);
121 }
122
123 public void stop() {
124 setMotorValues(0, 0);
125 }
126
127 public double getLeftMotorVal() {
128 return (frontLeft.get() + rearLeft.get()) / 2;
129 }
130
131 public double getRightMotorVal() {
132 return (frontRight.get() + rearRight.get()) / 2;
133 }
134
135 // ENCODER METHODS
136
137 public double getLeftEncoderDistance() {
138 return leftEncoder.getDistance();
139 }
140
141 public double getRightEncoderDistance() {
142 return rightEncoder.getDistance();
143 }
144
145 public void printEncoderOutput() {
146 System.out.println("left: " + getLeftEncoderDistance());
147 System.out.println("right: " + getRightEncoderDistance());
148 // System.out.println(getAvgEncoderDistance());
149 }
150
151 public double getAvgEncoderDistance() {
152 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
153 }
154
155 public void resetEncoders() {
156 leftEncoder.reset();
157 rightEncoder.reset();
158 }
159
160 public double getLeftSpeed() {
161 return leftEncoder.getRate();
162 }
163
164 public double getRightSpeed() {
165 return rightEncoder.getRate();
166 }
167
168 public double getSpeed() {
169 return (getLeftSpeed() + getRightSpeed()) / 2.0;
170 }
171
172 // ------Gyro------//
173 public double getAngle() {
174 return this.imu.getAngle();
175 }
176
177 public void resetGyro() {
178 this.imu.reset();
179 }
180
181 /*
182 * @return a value that is the current setpoint for the piston kReverse or
183 * KForward
184 */
185 public Value getLeftGearPistonValue() {
186 return leftGearPiston.get();
187 }
188
189 /*
190 * @return a value that is the current setpoint for the piston kReverse or
191 * KForward
192 */
193 public Value getRightGearPistonValue() {
194 return rightGearPiston.get();
195 }
196
197 /*
198 * Changes the ball shift gear assembly to high
199 */
200 public void setHighGear() {
201 changeGear(Constants.DriveTrain.HIGH_GEAR);
202 }
203
204 /*
205 * Changes the ball shift gear assembly to low
206 */
207 public void setLowGear() {
208 changeGear(Constants.DriveTrain.LOW_GEAR);
209 }
210
211 /*
212 * Changes the gear to a DoubleSolenoid.Value
213 */
214 private void changeGear(DoubleSolenoid.Value gear) {
215 leftGearPiston.set(gear);
216 rightGearPiston.set(gear);
217 }
218
219 @Override
220 protected void initDefaultCommand() {
221 setDefaultCommand(new JoystickDrive());
222 }
223 }