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 CZ |
16 | public static double driveP = 0.006, driveI = 0.001, driveD = -0.002; |
17 | public static double defaultGyroP = 0.004, defaultGyroI = 0.0013, | |
18 | defaultGyroD = -0.005; | |
e12d6901 CZ |
19 | private double gyroZero = 0; |
20 | ||
b634ebbc CZ |
21 | public static final double WHEEL_DIAMETER = 6; // inches |
22 | public static final int ENCODER_PULSES_PER_REVOLUTION = 256; | |
23 | public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI | |
24 | / ENCODER_PULSES_PER_REVOLUTION; | |
25 | ||
cc42bd52 ME |
26 | private static DriveTrain driveTrain; |
27 | private final CANTalon frontLeft, frontRight, rearLeft, rearRight; | |
28 | private final RobotDrive robotDrive; | |
29 | private final Encoder leftEncoder, rightEncoder; | |
73e8adbc | 30 | private final DoubleSolenoid leftGearPiston, rightGearPiston; |
cc42bd52 | 31 | |
bf921ece | 32 | private ADXRS450_Gyro imu; |
e12d6901 | 33 | |
cc42bd52 ME |
34 | private DriveTrain() { |
35 | // MOTOR CONTROLLERS | |
36 | frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); | |
37 | frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT); | |
38 | rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT); | |
39 | rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT); | |
40 | ||
41 | // ENCODERS | |
42 | leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, | |
3e2738c4 | 43 | Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X); |
cc42bd52 | 44 | rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, |
3e2738c4 | 45 | Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X); |
cc42bd52 | 46 | |
b634ebbc CZ |
47 | leftEncoder.setDistancePerPulse(INCHES_PER_PULSE); |
48 | rightEncoder.setDistancePerPulse(INCHES_PER_PULSE); | |
cc42bd52 ME |
49 | |
50 | // ROBOT DRIVE | |
51 | robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight); | |
8e4c083c | 52 | |
bf921ece | 53 | this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT); |
af4491f7 | 54 | |
ca372ce8 | 55 | // TODO: Not sure if MODULE_NUMBER should be the same for both |
a4e99721 | 56 | leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER, |
ca372ce8 AD |
57 | Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD, |
58 | Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE); | |
a4e99721 | 59 | rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER, |
ca372ce8 AD |
60 | Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD, |
61 | Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE); | |
cc42bd52 ME |
62 | } |
63 | ||
64 | public static DriveTrain getDriveTrain() { | |
65 | if (driveTrain == null) { | |
66 | driveTrain = new DriveTrain(); | |
67 | } | |
68 | return driveTrain; | |
69 | } | |
70 | ||
71 | // DRIVE METHODS | |
72 | public void setMotorValues(final double left, final double right) { | |
73 | frontLeft.set(left); | |
74 | rearLeft.set(left); | |
75 | ||
b081e34b ME |
76 | frontRight.set(-right); |
77 | rearRight.set(-right); | |
cc42bd52 ME |
78 | } |
79 | ||
80 | public void joystickDrive(final double thrust, final double twist) { | |
b081e34b | 81 | robotDrive.arcadeDrive(thrust, twist, true); |
cc42bd52 ME |
82 | } |
83 | ||
84 | public void stop() { | |
85 | setMotorValues(0, 0); | |
86 | } | |
87 | ||
f0a71840 CZ |
88 | public double getLeftMotorVal() { |
89 | return (frontLeft.get() + rearLeft.get()) / 2; | |
cc42bd52 ME |
90 | } |
91 | ||
f0a71840 CZ |
92 | public double getRightMotorVal() { |
93 | return (frontRight.get() + rearRight.get()) / 2; | |
cc42bd52 ME |
94 | } |
95 | ||
cc42bd52 ME |
96 | // ENCODER METHODS |
97 | ||
3a5d9ac7 | 98 | public double getLeftEncoderDistance() { |
cc42bd52 ME |
99 | return leftEncoder.getDistance(); |
100 | } | |
101 | ||
3a5d9ac7 | 102 | public double getRightEncoderDistance() { |
cc42bd52 ME |
103 | return rightEncoder.getDistance(); |
104 | } | |
105 | ||
8e4c083c | 106 | public void printEncoderOutput() { |
f0a71840 CZ |
107 | // System.out.println("left: " + getLeftEncoderDistance()); |
108 | // System.out.println("right: " + getRightEncoderDistance()); | |
109 | System.out.println(getAvgEncoderDistance()); | |
174f415c CZ |
110 | System.out.println("left: " + getLeftEncoderDistance()); |
111 | System.out.println("right: " + getRightEncoderDistance()); | |
8e4c083c CZ |
112 | } |
113 | ||
cc42bd52 ME |
114 | public double getAvgEncoderDistance() { |
115 | return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2; | |
116 | } | |
117 | ||
118 | public void resetEncoders() { | |
119 | leftEncoder.reset(); | |
120 | rightEncoder.reset(); | |
121 | } | |
122 | ||
123 | public double getLeftSpeed() { | |
124 | return leftEncoder.getRate(); | |
125 | } | |
126 | ||
127 | public double getRightSpeed() { | |
128 | return rightEncoder.getRate(); | |
129 | } | |
130 | ||
131 | public double getSpeed() { | |
132 | return (getLeftSpeed() + getRightSpeed()) / 2.0; | |
133 | } | |
134 | ||
e12d6901 CZ |
135 | // ------Gyro------// |
136 | public double getAngle() { | |
bf921ece | 137 | return this.imu.getAngle() - this.gyroZero; |
e12d6901 CZ |
138 | } |
139 | ||
140 | public void resetGyro() { | |
571fb5c9 | 141 | this.imu.reset(); |
e12d6901 CZ |
142 | } |
143 | ||
144 | public double getZeroAngle() { | |
145 | return this.gyroZero; | |
af4491f7 AD |
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 KZ |
190 | |
191 | } |