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