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