implement tank drive and toggle winch
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
CommitLineData
38a404b3
KZ
1package org.usfirst.frc.team3501.robot.subsystems;
2
3import org.usfirst.frc.team3501.robot.Constants;
ac77a7b8 4import org.usfirst.frc.team3501.robot.MathLib;
5483fde9 5import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
04f2cb52 6
a1c76caf
CZ
7import com.ctre.CANTalon;
8
bf921ece 9import edu.wpi.first.wpilibj.ADXRS450_Gyro;
4a75c629 10import edu.wpi.first.wpilibj.DoubleSolenoid;
73e8adbc 11import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
fa4e4a97 12import edu.wpi.first.wpilibj.Encoder;
ccbc35ae 13import edu.wpi.first.wpilibj.RobotDrive;
38a404b3
KZ
14import edu.wpi.first.wpilibj.command.Subsystem;
15
16public class DriveTrain extends Subsystem {
9ca89e45 17 public static double driveP = 0.01, driveI = 0.00115, driveD = -0.002;
b70398a7
CZ
18 public static double smallTurnP = 0.004, smallTurnI = 0.0013,
19 smallTurnD = 0.005;
20 public static double largeTurnP = .003, largeTurnI = .0012, largeTurnD = .006;
c846487e 21 public static double driveStraightGyroP = 0.01;
e12d6901 22
ac77a7b8
CZ
23 public static final double WHEEL_DIAMETER = 4; // inches
24 public static final double ENCODER_PULSES_PER_REVOLUTION = 256;
b634ebbc
CZ
25 public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
26 / ENCODER_PULSES_PER_REVOLUTION;
9dc69158 27
cc42bd52 28 private static DriveTrain driveTrain;
b8791ca4 29
cc42bd52
ME
30 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
31 private final RobotDrive robotDrive;
32 private final Encoder leftEncoder, rightEncoder;
150f450f
CZ
33 private final DoubleSolenoid rightDriveTrainPiston;
34 // private final Solenoid leftDriveTrainPiston;
fc01fb0f 35 private final DoubleSolenoid gearManipulatorPiston;
cc42bd52 36
bf921ece 37 private ADXRS450_Gyro imu;
e12d6901 38
cc42bd52
ME
39 private DriveTrain() {
40 // MOTOR CONTROLLERS
41 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
42 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
43 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
44 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
45
46 // ENCODERS
47 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
3e2738c4 48 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
cc42bd52 49 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
3e2738c4 50 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
cc42bd52 51
b634ebbc
CZ
52 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
53 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
cc42bd52
ME
54
55 // ROBOT DRIVE
56 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
8e4c083c 57
bf921ece 58 this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
af4491f7 59
ca372ce8 60 // TODO: Not sure if MODULE_NUMBER should be the same for both
150f450f
CZ
61 // leftDriveTrainPiston = new Solenoid(Constants.DriveTrain.PISTON_MODULE,
62 // Constants.DriveTrain.LEFT_GEAR_PISTON_PORT);
fc01fb0f
CZ
63 rightDriveTrainPiston = new DoubleSolenoid(
64 Constants.DriveTrain.PISTON_MODULE,
150f450f
CZ
65 Constants.DriveTrain.DRIVETRAIN_GEAR_FORWARD,
66 Constants.DriveTrain.DRIVETRAIN_GEAR_REVERSE);
fc01fb0f
CZ
67
68 gearManipulatorPiston = new DoubleSolenoid(
69 Constants.DriveTrain.PISTON_MODULE,
70 Constants.DriveTrain.GEAR_MANIPULATOR_PISTON_FORWARD,
71 Constants.DriveTrain.GEAR_MANIPULATOR_PISTON_REVERSE);
cc42bd52
ME
72 }
73
74 public static DriveTrain getDriveTrain() {
75 if (driveTrain == null) {
76 driveTrain = new DriveTrain();
77 }
78 return driveTrain;
79 }
80
81 // DRIVE METHODS
ac77a7b8 82 public void setMotorValues(double left, double right) {
b70398a7
CZ
83 left = MathLib.restrictToRange(left, -1.0, 1.0);
84 right = MathLib.restrictToRange(right, -1.0, 1.0);
ac77a7b8 85
cc42bd52
ME
86 frontLeft.set(left);
87 rearLeft.set(left);
88
b081e34b
ME
89 frontRight.set(-right);
90 rearRight.set(-right);
cc42bd52
ME
91 }
92
93 public void joystickDrive(final double thrust, final double twist) {
9ca89e45
CZ
94 if ((thrust < 0.1 && thrust > -0.1) && (twist < 0.1 && twist > -0.1))
95 robotDrive.arcadeDrive(0, 0, true);
96 else
97 robotDrive.arcadeDrive(thrust, twist, true);
cc42bd52
ME
98 }
99
ba9f0b12
CZ
100 public void tankDrive(double left, double right) {
101 robotDrive.tankDrive(left, right);
102 }
103
cc42bd52
ME
104 public void stop() {
105 setMotorValues(0, 0);
106 }
107
f0a71840
CZ
108 public double getLeftMotorVal() {
109 return (frontLeft.get() + rearLeft.get()) / 2;
cc42bd52
ME
110 }
111
f0a71840
CZ
112 public double getRightMotorVal() {
113 return (frontRight.get() + rearRight.get()) / 2;
cc42bd52
ME
114 }
115
cc42bd52
ME
116 // ENCODER METHODS
117
3a5d9ac7 118 public double getLeftEncoderDistance() {
cc42bd52
ME
119 return leftEncoder.getDistance();
120 }
121
3a5d9ac7 122 public double getRightEncoderDistance() {
cc42bd52
ME
123 return rightEncoder.getDistance();
124 }
125
8e4c083c 126 public void printEncoderOutput() {
174f415c
CZ
127 System.out.println("left: " + getLeftEncoderDistance());
128 System.out.println("right: " + getRightEncoderDistance());
c846487e 129 // System.out.println(getAvgEncoderDistance());
8e4c083c
CZ
130 }
131
cc42bd52
ME
132 public double getAvgEncoderDistance() {
133 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
134 }
135
136 public void resetEncoders() {
137 leftEncoder.reset();
138 rightEncoder.reset();
139 }
140
141 public double getLeftSpeed() {
142 return leftEncoder.getRate();
143 }
144
145 public double getRightSpeed() {
146 return rightEncoder.getRate();
147 }
148
149 public double getSpeed() {
150 return (getLeftSpeed() + getRightSpeed()) / 2.0;
151 }
152
e12d6901
CZ
153 // ------Gyro------//
154 public double getAngle() {
c846487e 155 return this.imu.getAngle();
e12d6901
CZ
156 }
157
158 public void resetGyro() {
571fb5c9 159 this.imu.reset();
e12d6901
CZ
160 }
161
73e8adbc
AD
162 /*
163 * @return a value that is the current setpoint for the piston kReverse or
164 * KForward
165 */
150f450f
CZ
166 // public boolean getLeftDriveTrainPiston() {
167 // return leftDriveTrainPiston.get();
168 // }
73e8adbc 169
06415bd8
AD
170 /*
171 * @return a value that is the current setpoint for the piston kReverse or
172 * KForward
173 */
fc01fb0f
CZ
174 public Value getRightDriveTrainPiston() {
175 return rightDriveTrainPiston.get();
06415bd8
AD
176 }
177
73e8adbc
AD
178 /*
179 * Changes the ball shift gear assembly to high
180 */
181 public void setHighGear() {
fc01fb0f 182 changeGear(Constants.DriveTrain.FORWARD_PISTON_VALUE);
73e8adbc
AD
183 }
184
185 /*
186 * Changes the ball shift gear assembly to low
187 */
188 public void setLowGear() {
fc01fb0f 189 changeGear(Constants.DriveTrain.REVERSE_PISTON_VALUE);
73e8adbc
AD
190 }
191
192 /*
193 * Changes the gear to a DoubleSolenoid.Value
194 */
195 private void changeGear(DoubleSolenoid.Value gear) {
150f450f 196 System.out.println("shifting to " + gear);
fc01fb0f 197 rightDriveTrainPiston.set(gear);
150f450f
CZ
198 System.out.println("after: " + this.getRightDriveTrainPiston());
199
200 //
201 // if (gear == Constants.DriveTrain.FORWARD_PISTON_VALUE)
202 // leftDriveTrainPiston.set(Constants.DriveTrain.EXTEND_VALUE);
203 // else
204 // leftDriveTrainPiston.set(Constants.DriveTrain.RETRACT_VALUE);
fc01fb0f
CZ
205 }
206
207 public Value getGearManipulatorPistonValue() {
208 return gearManipulatorPiston.get();
209 }
210
211 public void extendGearManipulatorPiston() {
212 gearManipulatorPiston.set(Constants.DriveTrain.FORWARD_PISTON_VALUE);
213 }
214
215 public void retractGearManipulatorPiston() {
216 gearManipulatorPiston.set(Constants.DriveTrain.REVERSE_PISTON_VALUE);
e12d6901
CZ
217 }
218
cc42bd52
ME
219 @Override
220 protected void initDefaultCommand() {
221 setDefaultCommand(new JoystickDrive());
222 }
38a404b3 223}