code review changes
[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.MathLib;
5 import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
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 = 0.012, driveI = 0.0011, driveD = -0.002;
18 public static double smallTurnP = 0.004, smallTurnI = 0.0013,
19 smallTurnD = 0.005;
20 public static double largeTurnP = .003, largeTurnI = .0012, largeTurnD = .006;
21 public static double driveStraightGyroP = 0.01;
22
23 public static final double WHEEL_DIAMETER = 4; // inches
24 public static final double 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 DriveTrain() {
44 // MOTOR CONTROLLERS
45 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
46 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
47 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
48 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
49
50 // ENCODERS
51 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
52 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
53 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
54 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
55
56 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
57 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
58
59 // ROBOT DRIVE
60 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
61
62 this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
63
64 // TODO: Not sure if MODULE_NUMBER should be the same for both
65 leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
66 Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
67 Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
68 rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
69 Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
70 Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
71 }
72
73 public static DriveTrain getDriveTrain() {
74 if (driveTrain == null) {
75 driveTrain = new DriveTrain();
76 }
77 return driveTrain;
78 }
79
80 // DRIVE METHODS
81 public void setMotorValues(double left, double right) {
82 left = MathLib.restrictToRange(left, -1.0, 1.0);
83 right = MathLib.restrictToRange(right, -1.0, 1.0);
84
85 frontLeft.set(left);
86 rearLeft.set(left);
87
88 frontRight.set(-right);
89 rearRight.set(-right);
90 }
91
92 public void joystickDrive(final double thrust, final double twist) {
93 robotDrive.arcadeDrive(thrust, twist, true);
94 }
95
96 public void stop() {
97 setMotorValues(0, 0);
98 }
99
100 public double getLeftMotorVal() {
101 return (frontLeft.get() + rearLeft.get()) / 2;
102 }
103
104 public double getRightMotorVal() {
105 return (frontRight.get() + rearRight.get()) / 2;
106 }
107
108 // ENCODER METHODS
109
110 public double getLeftEncoderDistance() {
111 return leftEncoder.getDistance();
112 }
113
114 public double getRightEncoderDistance() {
115 return rightEncoder.getDistance();
116 }
117
118 public void printEncoderOutput() {
119 System.out.println("left: " + getLeftEncoderDistance());
120 System.out.println("right: " + getRightEncoderDistance());
121 // System.out.println(getAvgEncoderDistance());
122 }
123
124 public double getAvgEncoderDistance() {
125 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
126 }
127
128 public void resetEncoders() {
129 leftEncoder.reset();
130 rightEncoder.reset();
131 }
132
133 public double getLeftSpeed() {
134 return leftEncoder.getRate();
135 }
136
137 public double getRightSpeed() {
138 return rightEncoder.getRate();
139 }
140
141 public double getSpeed() {
142 return (getLeftSpeed() + getRightSpeed()) / 2.0;
143 }
144
145 // ------Gyro------//
146 public double getAngle() {
147 return this.imu.getAngle();
148 }
149
150 public void resetGyro() {
151 this.imu.reset();
152 }
153
154 /*
155 * @return a value that is the current setpoint for the piston kReverse or
156 * KForward
157 */
158 public Value getLeftGearPistonValue() {
159 return leftGearPiston.get();
160 }
161
162 /*
163 * @return a value that is the current setpoint for the piston kReverse or
164 * KForward
165 */
166 public Value getRightGearPistonValue() {
167 return rightGearPiston.get();
168 }
169
170 /*
171 * Changes the ball shift gear assembly to high
172 */
173 public void setHighGear() {
174 changeGear(Constants.DriveTrain.HIGH_GEAR);
175 }
176
177 /*
178 * Changes the ball shift gear assembly to low
179 */
180 public void setLowGear() {
181 changeGear(Constants.DriveTrain.LOW_GEAR);
182 }
183
184 /*
185 * Changes the gear to a DoubleSolenoid.Value
186 */
187 private void changeGear(DoubleSolenoid.Value gear) {
188 System.out.println(gear);
189 leftGearPiston.set(gear);
190 rightGearPiston.set(gear);
191 }
192
193 @Override
194 protected void initDefaultCommand() {
195 setDefaultCommand(new JoystickDrive());
196 }
197 }