competition fixes
[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.01, driveI = 0.00115, 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 boolean BRAKE_MODE = true;
29 public static final boolean COAST_MODE = false;
30
31 private static DriveTrain driveTrain;
32
33 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
34 private final RobotDrive robotDrive;
35 private final Encoder leftEncoder, rightEncoder;
36 private final DoubleSolenoid rightDriveTrainPiston;
37 // private final Solenoid leftDriveTrainPiston;
38 private final DoubleSolenoid gearManipulatorPiston;
39
40 private ADXRS450_Gyro imu;
41
42 private DriveTrain() {
43 // MOTOR CONTROLLERS
44 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
45 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
46 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
47 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
48
49 // ENCODERS
50 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
51 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
52 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
53 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
54
55 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
56 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
57
58 // ROBOT DRIVE
59 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
60
61 this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
62
63 // TODO: Not sure if MODULE_NUMBER should be the same for both
64 // leftDriveTrainPiston = new Solenoid(Constants.DriveTrain.PISTON_MODULE,
65 // Constants.DriveTrain.LEFT_GEAR_PISTON_PORT);
66 rightDriveTrainPiston = new DoubleSolenoid(
67 Constants.DriveTrain.PISTON_MODULE,
68 Constants.DriveTrain.DRIVETRAIN_GEAR_FORWARD,
69 Constants.DriveTrain.DRIVETRAIN_GEAR_REVERSE);
70
71 gearManipulatorPiston = new DoubleSolenoid(
72 Constants.DriveTrain.PISTON_MODULE,
73 Constants.DriveTrain.GEAR_MANIPULATOR_PISTON_FORWARD,
74 Constants.DriveTrain.GEAR_MANIPULATOR_PISTON_REVERSE);
75 }
76
77 public static DriveTrain getDriveTrain() {
78 if (driveTrain == null) {
79 driveTrain = new DriveTrain();
80 }
81 return driveTrain;
82 }
83
84 // DRIVE METHODS
85 public void setMotorValues(double left, double right) {
86 left = MathLib.restrictToRange(left, -1.0, 1.0);
87 right = MathLib.restrictToRange(right, -1.0, 1.0);
88
89 frontLeft.set(left);
90 rearLeft.set(left);
91
92 frontRight.set(-right);
93 rearRight.set(-right);
94 }
95
96 public void setCANTalonsBrakeMode(boolean mode) {
97 frontLeft.enableBrakeMode(mode);
98 frontRight.enableBrakeMode(mode);
99 rearLeft.enableBrakeMode(mode);
100 rearRight.enableBrakeMode(mode);
101 }
102
103 public void joystickDrive(final double thrust, final double twist) {
104 if ((thrust < 0.1 && thrust > -0.1) && (twist < 0.1 && twist > -0.1))
105 robotDrive.arcadeDrive(0, 0, true);
106 else
107 robotDrive.arcadeDrive(thrust, twist, true);
108 System.out.println(thrust + " " + twist);
109 }
110
111 public void tankDrive(double left, double right) {
112 robotDrive.tankDrive(left, right);
113 }
114
115 public void stop() {
116 setMotorValues(0, 0);
117 }
118
119 public double getLeftMotorVal() {
120 return (frontLeft.get() + rearLeft.get()) / 2;
121 }
122
123 public double getRightMotorVal() {
124 return (frontRight.get() + rearRight.get()) / 2;
125 }
126
127 // ENCODER METHODS
128
129 public double getLeftEncoderDistance() {
130 return leftEncoder.getDistance();
131 }
132
133 public double getRightEncoderDistance() {
134 return rightEncoder.getDistance();
135 }
136
137 public void printEncoderOutput() {
138 System.out.println("left: " + getLeftEncoderDistance());
139 System.out.println("right: " + getRightEncoderDistance());
140 // System.out.println(getAvgEncoderDistance());
141 }
142
143 public double getAvgEncoderDistance() {
144 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
145 }
146
147 public void resetEncoders() {
148 leftEncoder.reset();
149 rightEncoder.reset();
150 }
151
152 public double getLeftSpeed() {
153 return leftEncoder.getRate();
154 }
155
156 public double getRightSpeed() {
157 return rightEncoder.getRate();
158 }
159
160 public double getSpeed() {
161 return (getLeftSpeed() + getRightSpeed()) / 2.0;
162 }
163
164 // ------Gyro------//
165 public double getAngle() {
166 return this.imu.getAngle();
167 }
168
169 public void resetGyro() {
170 this.imu.reset();
171 }
172
173 /*
174 * @return a value that is the current setpoint for the piston kReverse or
175 * KForward
176 */
177 // public boolean getLeftDriveTrainPiston() {
178 // return leftDriveTrainPiston.get();
179 // }
180
181 /*
182 * @return a value that is the current setpoint for the piston kReverse or
183 * KForward
184 */
185 public Value getRightDriveTrainPiston() {
186 return rightDriveTrainPiston.get();
187 }
188
189 /*
190 * Changes the ball shift gear assembly to high
191 */
192 public void setHighGear() {
193 changeGear(Constants.DriveTrain.FORWARD_PISTON_VALUE);
194 }
195
196 /*
197 * Changes the ball shift gear assembly to low
198 */
199 public void setLowGear() {
200 changeGear(Constants.DriveTrain.REVERSE_PISTON_VALUE);
201 }
202
203 /*
204 * Changes the gear to a DoubleSolenoid.Value
205 */
206 private void changeGear(DoubleSolenoid.Value gear) {
207 System.out.println("shifting to " + gear);
208 rightDriveTrainPiston.set(gear);
209 System.out.println("after: " + this.getRightDriveTrainPiston());
210
211 //
212 // if (gear == Constants.DriveTrain.FORWARD_PISTON_VALUE)
213 // leftDriveTrainPiston.set(Constants.DriveTrain.EXTEND_VALUE);
214 // else
215 // leftDriveTrainPiston.set(Constants.DriveTrain.RETRACT_VALUE);
216 }
217
218 public Value getGearManipulatorPistonValue() {
219 return gearManipulatorPiston.get();
220 }
221
222 public void extendGearManipulatorPiston() {
223 gearManipulatorPiston.set(Constants.DriveTrain.FORWARD_PISTON_VALUE);
224 }
225
226 public void retractGearManipulatorPiston() {
227 gearManipulatorPiston.set(Constants.DriveTrain.REVERSE_PISTON_VALUE);
228 }
229
230 @Override
231 protected void initDefaultCommand() {
232 setDefaultCommand(new JoystickDrive());
233 }
234 }