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