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