231ebf52c15617f873bb49e91470fa28d1a5ba3a
[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 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
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 // 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,
72 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
73 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
74 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
75
76 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
77 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
78
79 // ROBOT DRIVE
80 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
81
82 this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
83
84 // TODO: Not sure if MODULE_NUMBER should be the same for both
85 leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
86 Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
87 Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
88 rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
89 Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
90 Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
91 }
92
93 public PIDController getDriveController() {
94 return this.driveController;
95 }
96
97 public PIDController getGyroController() {
98 return this.gyroController;
99 }
100
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
113 frontRight.set(-right);
114 rearRight.set(-right);
115 }
116
117 public void joystickDrive(final double thrust, final double twist) {
118 robotDrive.arcadeDrive(thrust, twist, true);
119 }
120
121 public void stop() {
122 setMotorValues(0, 0);
123 }
124
125 public double getLeftMotorVal() {
126 return (frontLeft.get() + rearLeft.get()) / 2;
127 }
128
129 public double getRightMotorVal() {
130 return (frontRight.get() + rearRight.get()) / 2;
131 }
132
133 // ENCODER METHODS
134
135 public double getLeftEncoderDistance() {
136 return leftEncoder.getDistance();
137 }
138
139 public double getRightEncoderDistance() {
140 return rightEncoder.getDistance();
141 }
142
143 public void printEncoderOutput() {
144 System.out.println("left: " + getLeftEncoderDistance());
145 System.out.println("right: " + getRightEncoderDistance());
146 // System.out.println(getAvgEncoderDistance());
147 }
148
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
170 // ------Gyro------//
171 public double getAngle() {
172 return this.imu.getAngle();
173 }
174
175 public void resetGyro() {
176 this.imu.reset();
177 }
178
179 /*
180 * @return a value that is the current setpoint for the piston kReverse or
181 * KForward
182 */
183 public Value getLeftGearPistonValue() {
184 return leftGearPiston.get();
185 }
186
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
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);
215 }
216
217 @Override
218 protected void initDefaultCommand() {
219 setDefaultCommand(new JoystickDrive());
220 }
221 }