add getter methods for gear piston values
[3501/stronghold-2016] / 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;
33141cdd
KZ
4import org.usfirst.frc.team3501.robot.GyroLib;
5import org.usfirst.frc.team3501.robot.MathLib;
6import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
111dc444 7
38a404b3 8import edu.wpi.first.wpilibj.CANTalon;
111dc444 9import edu.wpi.first.wpilibj.CounterBase.EncodingType;
d9c04720 10import edu.wpi.first.wpilibj.DoubleSolenoid;
2aea5cc2 11import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
111dc444 12import edu.wpi.first.wpilibj.Encoder;
b54ad73b 13import edu.wpi.first.wpilibj.I2C;
33141cdd
KZ
14import edu.wpi.first.wpilibj.RobotDrive;
15import edu.wpi.first.wpilibj.command.PIDSubsystem;
16
17public class DriveTrain extends PIDSubsystem {
18 private static double pidOutput = 0;
19 private static double encoderTolerance = 8.0, gyroTolerance = 5.0;
20 private int DRIVE_MODE = 1;
21
22 private static final int MANUAL_MODE = 1, ENCODER_MODE = 2, GYRO_MODE = 3;
38a404b3 23
1884c3cf 24 private Encoder leftEncoder, rightEncoder;
d7bf2340 25 private CANTalon frontLeft, frontRight, rearLeft, rearRight;
33141cdd
KZ
26 private RobotDrive robotDrive;
27
28 private GyroLib gyro;
d9c04720
SC
29 private DoubleSolenoid leftGearPiston, rightGearPiston;
30 // Drivetrain specific constants that relate to the inches per pulse value for
31 // the encoders
32 private final static double WHEEL_DIAMETER = 6.0; // in inches
33 private final static double PULSES_PER_ROTATION = 256; // in pulses
34 private final static double OUTPUT_SPROCKET_DIAMETER = 2.0; // in inches
35 private final static double WHEEL_SPROCKET_DIAMETER = 3.5; // in inches
36 public final static double INCHES_PER_PULSE = (((Math.PI)
37 * OUTPUT_SPROCKET_DIAMETER / PULSES_PER_ROTATION)
38 / WHEEL_SPROCKET_DIAMETER) * WHEEL_DIAMETER;
39
40 // Drivetrain specific constants that relate to the PID controllers
41 private final static double Kp = 1.0, Ki = 0.0,
42 Kd = 0.0 * (OUTPUT_SPROCKET_DIAMETER / PULSES_PER_ROTATION)
2aea5cc2 43 / (WHEEL_SPROCKET_DIAMETER) * WHEEL_DIAMETER;
71d73690 44
d7bf2340 45 public DriveTrain() {
33141cdd
KZ
46 super(kp, ki, kd);
47
d7bf2340
KZ
48 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
49 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
50 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
51 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
1884c3cf 52
33141cdd 53 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
d7bf2340
KZ
54 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
55 Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X);
56 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
57 Constants.DriveTrain.ENCODER_RIGHT_B, false, EncodingType.k4X);
45bdf5b9
KZ
58 leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
59 rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
33141cdd
KZ
60
61 leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
62 rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
63
64 gyro = new GyroLib(I2C.Port.kOnboard, false);
65
66 DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE;
67 setEncoderPID();
68 this.disable();
69 gyro.start();
d004deee 70
d9c04720
SC
71 leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.LEFT_FORWARD,
72 +Constants.DriveTrain.LEFT_REVERSE);
73 rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.RIGHT_FORWARD,
74 Constants.DriveTrain.RIGHT_REVERSE);
d7bf2340
KZ
75 }
76
77 @Override
78 protected void initDefaultCommand() {
33141cdd
KZ
79 setDefaultCommand(new JoystickDrive());
80 }
81
82 public void printOutput() {
83 System.out.println("PIDOutput: " + pidOutput);
84 }
85
86 private double getAvgEncoderDistance() {
87 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
88 }
89
90 public boolean reachedTarget() {
91 if (this.onTarget()) {
92 this.disable();
93 return true;
94 } else {
95 return false;
96 }
97 }
98
99 public void stop() {
100 drive(0, 0);
d7bf2340
KZ
101 }
102
103 public void resetEncoders() {
104 leftEncoder.reset();
105 rightEncoder.reset();
106 }
107
2aea5cc2
SC
108 public Value getLeftGearPistonValue() {
109 return leftGearPiston.get();
110 }
111
112 public Value getRightGearPistonValue() {
113 return rightGearPiston.get();
114 }
115
d7bf2340 116 public double getRightSpeed() {
6833a887 117 return rightEncoder.getRate(); // in inches per second
d7bf2340
KZ
118 }
119
120 public double getLeftSpeed() {
6833a887 121 return leftEncoder.getRate(); // in inches per second
d7bf2340
KZ
122 }
123
124 public double getSpeed() {
6833a887 125 return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second
d7bf2340
KZ
126 }
127
d7bf2340 128 public double getRightDistance() {
6833a887 129 return rightEncoder.getDistance(); // in inches
d7bf2340
KZ
130 }
131
d7bf2340 132 public double getLeftDistance() {
6833a887 133 return leftEncoder.getDistance(); // in inches
d7bf2340
KZ
134 }
135
33141cdd
KZ
136 public double getError() {
137 if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE)
138 return Math.abs(this.getSetpoint() - getAvgEncoderDistance());
139 else
140 return Math.abs(this.getSetpoint() + getGyroAngle());
d7bf2340
KZ
141 }
142
33141cdd
KZ
143 public double getGyroAngle() {
144 return gyro.getRotationZ().getAngle();
145 }
146
147 public void resetGyro() {
148 gyro.reset();
149 }
150
151 public void printEncoder(int i, int n) {
152 if (i % n == 0) {
153 System.out.println("Left: " + this.getLeftDistance());
154 System.out.println("Right: " + this.getRightDistance());
155
156 }
157 }
158
159 public void printGyroOutput() {
160 System.out.println("Gyro Angle" + -this.getGyroAngle());
161 }
162
163 public double getOutput() {
164 return pidOutput;
165 }
166
167 public void updatePID() {
168 if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE)
169 this.getPIDController().setPID(kp, ki, kd);
170 else
171 this.getPIDController().setPID(gp, gd, gi);
172 }
173
174 public CANTalon getFrontLeft() {
175 return frontLeft;
176 }
177
178 public CANTalon getFrontRight() {
179 return frontRight;
180 }
181
182 public CANTalon getRearLeft() {
183 return rearLeft;
184 }
185
186 public CANTalon getRearRight() {
187 return rearRight;
188 }
189
190 public int getMode() {
191 return DRIVE_MODE;
192 }
193
194 @Override
195 protected void usePIDOutput(double output) {
196 double left = 0;
197 double right = 0;
198 if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) {
199 double drift = this.getLeftDistance() - this.getRightDistance();
200 if (Math.abs(output) > 0 && Math.abs(output) < 0.3)
201 output = Math.signum(output) * 0.3;
202 left = output;
203 right = output + drift * kp / 10;
204 }
205 else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE) {
206 left = output;
207 right = -output;
208 }
209 drive(left, right);
210 pidOutput = output;
d7bf2340
KZ
211 }
212
33141cdd
KZ
213 @Override
214 protected double returnPIDInput() {
215 return sensorFeedback();
d7bf2340 216 }
33141cdd
KZ
217
218 private double sensorFeedback() {
219 if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE)
220 return getAvgEncoderDistance();
221 else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE)
222 return -this.getGyroAngle();
223 // counterclockwise is positive on joystick but we want it to be negative
224 else
225 return 0;
226 }
227
228 public void drive(double left, double right) {
229 robotDrive.tankDrive(-left, -right);
230 // dunno why but inverted drive (- values is forward)
231 }
232
233 public void driveDistance(double dist, double maxTimeOut) {
234 dist = MathLib.constrain(dist, -100, 100);
235 setEncoderPID();
236 setSetpoint(dist);
237 }
238
239 public void setEncoderPID() {
240 DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE;
241 this.updatePID();
242 this.setAbsoluteTolerance(encoderTolerance);
243 this.setOutputRange(-1.0, 1.0);
244 this.setInputRange(-200.0, 200.0);
245 this.enable();
246 }
247
248 private void setGyroPID() {
249 DRIVE_MODE = Constants.DriveTrain.GYRO_MODE;
250 this.updatePID();
251 this.getPIDController().setPID(gp, gi, gd);
252
253 this.setAbsoluteTolerance(gyroTolerance);
254 this.setOutputRange(-1.0, 1.0);
255 this.setInputRange(-360.0, 360.0);
256 this.enable();
257 }
258
259 public void turnAngle(double angle) {
260 angle = MathLib.constrain(angle, -360, 360);
261 setGyroPID();
262 setSetpoint(angle);
263 }
264
265 public void setMotorSpeeds(double left, double right) {
266 // positive setpoint to left side makes it go backwards
267 // positive setpoint to right side makes it go forwards.
268 frontLeft.set(-left);
269 rearLeft.set(-left);
270 frontRight.set(right);
271 rearRight.set(right);
272 }
273
274 private static double kp = 0.013, ki = 0.000015, kd = -0.002;
275 private static double gp = 0.018, gi = 0.000015, gd = 0;
38a404b3 276}