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