Commit | Line | Data |
---|---|---|
38a404b3 KZ |
1 | package org.usfirst.frc.team3501.robot.subsystems; |
2 | ||
3 | import org.usfirst.frc.team3501.robot.Constants; | |
ac77a7b8 | 4 | import org.usfirst.frc.team3501.robot.MathLib; |
5483fde9 | 5 | import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive; |
04f2cb52 | 6 | |
a1c76caf CZ |
7 | import com.ctre.CANTalon; |
8 | ||
bf921ece | 9 | import edu.wpi.first.wpilibj.ADXRS450_Gyro; |
4a75c629 | 10 | import edu.wpi.first.wpilibj.DoubleSolenoid; |
73e8adbc | 11 | import edu.wpi.first.wpilibj.DoubleSolenoid.Value; |
fa4e4a97 | 12 | import edu.wpi.first.wpilibj.Encoder; |
ccbc35ae | 13 | import edu.wpi.first.wpilibj.RobotDrive; |
38a404b3 KZ |
14 | import edu.wpi.first.wpilibj.command.Subsystem; |
15 | ||
16 | public class DriveTrain extends Subsystem { | |
9ca89e45 | 17 | public static double driveP = 0.01, driveI = 0.00115, driveD = -0.002; |
b70398a7 CZ |
18 | public static double smallTurnP = 0.004, smallTurnI = 0.0013, |
19 | smallTurnD = 0.005; | |
20 | public static double largeTurnP = .003, largeTurnI = .0012, largeTurnD = .006; | |
c846487e | 21 | public static double driveStraightGyroP = 0.01; |
e12d6901 | 22 | |
ac77a7b8 CZ |
23 | public static final double WHEEL_DIAMETER = 4; // inches |
24 | public static final double ENCODER_PULSES_PER_REVOLUTION = 256; | |
b634ebbc CZ |
25 | public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI |
26 | / ENCODER_PULSES_PER_REVOLUTION; | |
9dc69158 | 27 | |
f74d236d CZ |
28 | public static final boolean BRAKE_MODE = true; |
29 | public static final boolean COAST_MODE = false; | |
30 | ||
cc42bd52 | 31 | private static DriveTrain driveTrain; |
b8791ca4 | 32 | |
cc42bd52 ME |
33 | private final CANTalon frontLeft, frontRight, rearLeft, rearRight; |
34 | private final RobotDrive robotDrive; | |
35 | private final Encoder leftEncoder, rightEncoder; | |
150f450f CZ |
36 | private final DoubleSolenoid rightDriveTrainPiston; |
37 | // private final Solenoid leftDriveTrainPiston; | |
fc01fb0f | 38 | private final DoubleSolenoid gearManipulatorPiston; |
cc42bd52 | 39 | |
bf921ece | 40 | private ADXRS450_Gyro imu; |
e12d6901 | 41 | |
cc42bd52 ME |
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, | |
3e2738c4 | 51 | Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X); |
cc42bd52 | 52 | rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, |
3e2738c4 | 53 | Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X); |
cc42bd52 | 54 | |
b634ebbc CZ |
55 | leftEncoder.setDistancePerPulse(INCHES_PER_PULSE); |
56 | rightEncoder.setDistancePerPulse(INCHES_PER_PULSE); | |
cc42bd52 ME |
57 | |
58 | // ROBOT DRIVE | |
59 | robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight); | |
8e4c083c | 60 | |
bf921ece | 61 | this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT); |
af4491f7 | 62 | |
ca372ce8 | 63 | // TODO: Not sure if MODULE_NUMBER should be the same for both |
150f450f CZ |
64 | // leftDriveTrainPiston = new Solenoid(Constants.DriveTrain.PISTON_MODULE, |
65 | // Constants.DriveTrain.LEFT_GEAR_PISTON_PORT); | |
fc01fb0f CZ |
66 | rightDriveTrainPiston = new DoubleSolenoid( |
67 | Constants.DriveTrain.PISTON_MODULE, | |
150f450f CZ |
68 | Constants.DriveTrain.DRIVETRAIN_GEAR_FORWARD, |
69 | Constants.DriveTrain.DRIVETRAIN_GEAR_REVERSE); | |
fc01fb0f CZ |
70 | |
71 | gearManipulatorPiston = new DoubleSolenoid( | |
72 | Constants.DriveTrain.PISTON_MODULE, | |
73 | Constants.DriveTrain.GEAR_MANIPULATOR_PISTON_FORWARD, | |
74 | Constants.DriveTrain.GEAR_MANIPULATOR_PISTON_REVERSE); | |
cc42bd52 ME |
75 | } |
76 | ||
77 | public static DriveTrain getDriveTrain() { | |
78 | if (driveTrain == null) { | |
79 | driveTrain = new DriveTrain(); | |
80 | } | |
81 | return driveTrain; | |
82 | } | |
83 | ||
84 | // DRIVE METHODS | |
ac77a7b8 | 85 | public void setMotorValues(double left, double right) { |
b70398a7 CZ |
86 | left = MathLib.restrictToRange(left, -1.0, 1.0); |
87 | right = MathLib.restrictToRange(right, -1.0, 1.0); | |
ac77a7b8 | 88 | |
cc42bd52 ME |
89 | frontLeft.set(left); |
90 | rearLeft.set(left); | |
91 | ||
b081e34b ME |
92 | frontRight.set(-right); |
93 | rearRight.set(-right); | |
cc42bd52 ME |
94 | } |
95 | ||
f74d236d CZ |
96 | public void setCANTalonsBrakeMode(boolean mode) { |
97 | frontLeft.enableBrakeMode(mode); | |
98 | frontRight.enableBrakeMode(mode); | |
99 | rearLeft.enableBrakeMode(mode); | |
100 | rearRight.enableBrakeMode(mode); | |
101 | } | |
102 | ||
cc42bd52 | 103 | public void joystickDrive(final double thrust, final double twist) { |
9ca89e45 CZ |
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); | |
f74d236d | 108 | System.out.println(thrust + " " + twist); |
cc42bd52 ME |
109 | } |
110 | ||
ba9f0b12 CZ |
111 | public void tankDrive(double left, double right) { |
112 | robotDrive.tankDrive(left, right); | |
113 | } | |
114 | ||
cc42bd52 ME |
115 | public void stop() { |
116 | setMotorValues(0, 0); | |
117 | } | |
118 | ||
f0a71840 CZ |
119 | public double getLeftMotorVal() { |
120 | return (frontLeft.get() + rearLeft.get()) / 2; | |
cc42bd52 ME |
121 | } |
122 | ||
f0a71840 CZ |
123 | public double getRightMotorVal() { |
124 | return (frontRight.get() + rearRight.get()) / 2; | |
cc42bd52 ME |
125 | } |
126 | ||
cc42bd52 ME |
127 | // ENCODER METHODS |
128 | ||
3a5d9ac7 | 129 | public double getLeftEncoderDistance() { |
cc42bd52 ME |
130 | return leftEncoder.getDistance(); |
131 | } | |
132 | ||
3a5d9ac7 | 133 | public double getRightEncoderDistance() { |
cc42bd52 ME |
134 | return rightEncoder.getDistance(); |
135 | } | |
136 | ||
8e4c083c | 137 | public void printEncoderOutput() { |
174f415c CZ |
138 | System.out.println("left: " + getLeftEncoderDistance()); |
139 | System.out.println("right: " + getRightEncoderDistance()); | |
c846487e | 140 | // System.out.println(getAvgEncoderDistance()); |
8e4c083c CZ |
141 | } |
142 | ||
cc42bd52 ME |
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 | ||
e12d6901 CZ |
164 | // ------Gyro------// |
165 | public double getAngle() { | |
c846487e | 166 | return this.imu.getAngle(); |
e12d6901 CZ |
167 | } |
168 | ||
169 | public void resetGyro() { | |
571fb5c9 | 170 | this.imu.reset(); |
e12d6901 CZ |
171 | } |
172 | ||
73e8adbc AD |
173 | /* |
174 | * @return a value that is the current setpoint for the piston kReverse or | |
175 | * KForward | |
176 | */ | |
150f450f CZ |
177 | // public boolean getLeftDriveTrainPiston() { |
178 | // return leftDriveTrainPiston.get(); | |
179 | // } | |
73e8adbc | 180 | |
06415bd8 AD |
181 | /* |
182 | * @return a value that is the current setpoint for the piston kReverse or | |
183 | * KForward | |
184 | */ | |
fc01fb0f CZ |
185 | public Value getRightDriveTrainPiston() { |
186 | return rightDriveTrainPiston.get(); | |
06415bd8 AD |
187 | } |
188 | ||
73e8adbc AD |
189 | /* |
190 | * Changes the ball shift gear assembly to high | |
191 | */ | |
192 | public void setHighGear() { | |
fc01fb0f | 193 | changeGear(Constants.DriveTrain.FORWARD_PISTON_VALUE); |
73e8adbc AD |
194 | } |
195 | ||
196 | /* | |
197 | * Changes the ball shift gear assembly to low | |
198 | */ | |
199 | public void setLowGear() { | |
fc01fb0f | 200 | changeGear(Constants.DriveTrain.REVERSE_PISTON_VALUE); |
73e8adbc AD |
201 | } |
202 | ||
203 | /* | |
204 | * Changes the gear to a DoubleSolenoid.Value | |
205 | */ | |
206 | private void changeGear(DoubleSolenoid.Value gear) { | |
150f450f | 207 | System.out.println("shifting to " + gear); |
fc01fb0f | 208 | rightDriveTrainPiston.set(gear); |
150f450f CZ |
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); | |
fc01fb0f CZ |
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); | |
e12d6901 CZ |
228 | } |
229 | ||
cc42bd52 ME |
230 | @Override |
231 | protected void initDefaultCommand() { | |
232 | setDefaultCommand(new JoystickDrive()); | |
233 | } | |
38a404b3 | 234 | } |