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