Commit | Line | Data |
---|---|---|
38a404b3 KZ |
1 | package org.usfirst.frc.team3501.robot.subsystems; |
2 | ||
3 | import org.usfirst.frc.team3501.robot.Constants; | |
5483fde9 | 4 | import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive; |
06df4cd4 | 5 | import org.usfirst.frc.team3501.robot.utils.PIDController; |
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 { | |
34ffcd03 ES |
17 | |
18 | public static double driveP, driveI, driveD; | |
1479f285 | 19 | |
542234fe | 20 | public static double turnP, turnI, turnD; |
1479f285 | 21 | |
c846487e | 22 | public static double driveStraightGyroP = 0.01; |
e12d6901 | 23 | |
b634ebbc CZ |
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; | |
9dc69158 CZ |
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 | ||
cc42bd52 | 33 | private static DriveTrain driveTrain; |
b8791ca4 | 34 | |
cc42bd52 ME |
35 | private final CANTalon frontLeft, frontRight, rearLeft, rearRight; |
36 | private final RobotDrive robotDrive; | |
37 | private final Encoder leftEncoder, rightEncoder; | |
73e8adbc | 38 | private final DoubleSolenoid leftGearPiston, rightGearPiston; |
cc42bd52 | 39 | |
bf921ece | 40 | private ADXRS450_Gyro imu; |
e12d6901 | 41 | |
366f1cfd | 42 | public boolean shouldBeClimbing = false; |
cef1f36d | 43 | |
06df4cd4 | 44 | private PIDController driveController; |
01ea2879 | 45 | private PIDController gyroController; |
06df4cd4 | 46 | |
cc42bd52 | 47 | private DriveTrain() { |
06df4cd4 | 48 | |
9ffd117a | 49 | driveController = new PIDController(driveP, driveI, driveD); |
542234fe | 50 | gyroController = new PIDController(turnP, turnI, turnD); |
06df4cd4 | 51 | |
cc42bd52 ME |
52 | // MOTOR CONTROLLERS |
53 | frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); | |
54 | frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT); | |
55 | rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT); | |
56 | rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT); | |
57 | ||
58 | // ENCODERS | |
59 | leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, | |
3e2738c4 | 60 | Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X); |
cc42bd52 | 61 | rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, |
3e2738c4 | 62 | Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X); |
cc42bd52 | 63 | |
b634ebbc CZ |
64 | leftEncoder.setDistancePerPulse(INCHES_PER_PULSE); |
65 | rightEncoder.setDistancePerPulse(INCHES_PER_PULSE); | |
cc42bd52 ME |
66 | |
67 | // ROBOT DRIVE | |
68 | robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight); | |
8e4c083c | 69 | |
bf921ece | 70 | this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT); |
af4491f7 | 71 | |
ca372ce8 | 72 | // TODO: Not sure if MODULE_NUMBER should be the same for both |
58bcc21d | 73 | leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE, |
ca372ce8 AD |
74 | Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD, |
75 | Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE); | |
58bcc21d | 76 | rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE, |
ca372ce8 AD |
77 | Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD, |
78 | Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE); | |
cc42bd52 ME |
79 | } |
80 | ||
06df4cd4 E |
81 | public PIDController getDriveController() { |
82 | return this.driveController; | |
83 | } | |
84 | ||
90b435ce ES |
85 | public PIDController getGyroController() { |
86 | return this.gyroController; | |
87 | } | |
88 | ||
cc42bd52 ME |
89 | public static DriveTrain getDriveTrain() { |
90 | if (driveTrain == null) { | |
91 | driveTrain = new DriveTrain(); | |
92 | } | |
93 | return driveTrain; | |
94 | } | |
95 | ||
96 | // DRIVE METHODS | |
97 | public void setMotorValues(final double left, final double right) { | |
98 | frontLeft.set(left); | |
99 | rearLeft.set(left); | |
100 | ||
b081e34b ME |
101 | frontRight.set(-right); |
102 | rearRight.set(-right); | |
cc42bd52 ME |
103 | } |
104 | ||
105 | public void joystickDrive(final double thrust, final double twist) { | |
b081e34b | 106 | robotDrive.arcadeDrive(thrust, twist, true); |
cc42bd52 ME |
107 | } |
108 | ||
109 | public void stop() { | |
110 | setMotorValues(0, 0); | |
111 | } | |
112 | ||
f0a71840 CZ |
113 | public double getLeftMotorVal() { |
114 | return (frontLeft.get() + rearLeft.get()) / 2; | |
cc42bd52 ME |
115 | } |
116 | ||
f0a71840 CZ |
117 | public double getRightMotorVal() { |
118 | return (frontRight.get() + rearRight.get()) / 2; | |
cc42bd52 ME |
119 | } |
120 | ||
cc42bd52 ME |
121 | // ENCODER METHODS |
122 | ||
3a5d9ac7 | 123 | public double getLeftEncoderDistance() { |
cc42bd52 ME |
124 | return leftEncoder.getDistance(); |
125 | } | |
126 | ||
3a5d9ac7 | 127 | public double getRightEncoderDistance() { |
cc42bd52 ME |
128 | return rightEncoder.getDistance(); |
129 | } | |
130 | ||
8e4c083c | 131 | public void printEncoderOutput() { |
174f415c CZ |
132 | System.out.println("left: " + getLeftEncoderDistance()); |
133 | System.out.println("right: " + getRightEncoderDistance()); | |
c846487e | 134 | // System.out.println(getAvgEncoderDistance()); |
8e4c083c CZ |
135 | } |
136 | ||
cc42bd52 ME |
137 | public double getAvgEncoderDistance() { |
138 | return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2; | |
139 | } | |
140 | ||
141 | public void resetEncoders() { | |
142 | leftEncoder.reset(); | |
143 | rightEncoder.reset(); | |
144 | } | |
145 | ||
146 | public double getLeftSpeed() { | |
147 | return leftEncoder.getRate(); | |
148 | } | |
149 | ||
150 | public double getRightSpeed() { | |
151 | return rightEncoder.getRate(); | |
152 | } | |
153 | ||
154 | public double getSpeed() { | |
155 | return (getLeftSpeed() + getRightSpeed()) / 2.0; | |
156 | } | |
157 | ||
e12d6901 CZ |
158 | // ------Gyro------// |
159 | public double getAngle() { | |
c846487e | 160 | return this.imu.getAngle(); |
e12d6901 CZ |
161 | } |
162 | ||
163 | public void resetGyro() { | |
571fb5c9 | 164 | this.imu.reset(); |
e12d6901 CZ |
165 | } |
166 | ||
73e8adbc AD |
167 | /* |
168 | * @return a value that is the current setpoint for the piston kReverse or | |
169 | * KForward | |
170 | */ | |
06415bd8 | 171 | public Value getLeftGearPistonValue() { |
73e8adbc AD |
172 | return leftGearPiston.get(); |
173 | } | |
174 | ||
06415bd8 AD |
175 | /* |
176 | * @return a value that is the current setpoint for the piston kReverse or | |
177 | * KForward | |
178 | */ | |
179 | public Value getRightGearPistonValue() { | |
180 | return rightGearPiston.get(); | |
181 | } | |
182 | ||
73e8adbc AD |
183 | /* |
184 | * Changes the ball shift gear assembly to high | |
185 | */ | |
186 | public void setHighGear() { | |
187 | changeGear(Constants.DriveTrain.HIGH_GEAR); | |
188 | } | |
189 | ||
190 | /* | |
191 | * Changes the ball shift gear assembly to low | |
192 | */ | |
193 | public void setLowGear() { | |
194 | changeGear(Constants.DriveTrain.LOW_GEAR); | |
195 | } | |
196 | ||
197 | /* | |
198 | * Changes the gear to a DoubleSolenoid.Value | |
199 | */ | |
200 | private void changeGear(DoubleSolenoid.Value gear) { | |
201 | leftGearPiston.set(gear); | |
202 | rightGearPiston.set(gear); | |
e12d6901 CZ |
203 | } |
204 | ||
cc42bd52 ME |
205 | @Override |
206 | protected void initDefaultCommand() { | |
207 | setDefaultCommand(new JoystickDrive()); | |
208 | } | |
38a404b3 | 209 | } |