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