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