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