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