f967217d5f6ae651e7b76777211bb5dbc5199117
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
1 package org.usfirst.frc.team3501.robot.subsystems;
2
3 import org.usfirst.frc.team3501.robot.Constants;
4 import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
5 import org.usfirst.frc.team3501.robot.utils.PIDController;
6
7 import com.ctre.CANTalon;
8
9 import edu.wpi.first.wpilibj.ADXRS450_Gyro;
10 import edu.wpi.first.wpilibj.DoubleSolenoid;
11 import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
12 import edu.wpi.first.wpilibj.Encoder;
13 import edu.wpi.first.wpilibj.RobotDrive;
14 import edu.wpi.first.wpilibj.command.Subsystem;
15
16 public class DriveTrain extends Subsystem {
17
18 public static double driveP, driveI, driveD;
19 public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
20 public static double driveStraightGyroP = 0.01;
21
22 public static final double WHEEL_DIAMETER = 6; // inches
23 public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
24 public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
25 / ENCODER_PULSES_PER_REVOLUTION;
26
27 public static final double MAINTAIN_CLIMBED_POSITION = 0;
28 public static final double TIME_TO_CLIMB_FOR = 0;
29 public static final double CLIMBER_SPEED = 0;
30
31 private static DriveTrain driveTrain;
32
33 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
34 private final RobotDrive robotDrive;
35 private final Encoder leftEncoder, rightEncoder;
36 private final DoubleSolenoid leftGearPiston, rightGearPiston;
37
38 private ADXRS450_Gyro imu;
39
40 public boolean shouldBeClimbing = false;
41
42 private PIDController driveController;
43 private PIDController gyroController;
44
45 private DriveTrain() {
46
47 driveController = new PIDController(driveP, driveI, driveD);
48
49 // MOTOR CONTROLLERS
50 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
51 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
52 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
53 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
54
55 // ENCODERS
56 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
57 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
58 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
59 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
60
61 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
62 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
63
64 // ROBOT DRIVE
65 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
66
67 this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
68
69 // TODO: Not sure if MODULE_NUMBER should be the same for both
70 leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
71 Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
72 Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
73 rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
74 Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
75 Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
76 }
77
78 public PIDController getDriveController() {
79 return this.driveController;
80 }
81
82 public PIDController getGyroController() {
83 return this.gyroController;
84 }
85
86 public static DriveTrain getDriveTrain() {
87 if (driveTrain == null) {
88 driveTrain = new DriveTrain();
89 }
90 return driveTrain;
91 }
92
93 // DRIVE METHODS
94 public void setMotorValues(final double left, final double right) {
95 frontLeft.set(left);
96 rearLeft.set(left);
97
98 frontRight.set(-right);
99 rearRight.set(-right);
100 }
101
102 public void joystickDrive(final double thrust, final double twist) {
103 robotDrive.arcadeDrive(thrust, twist, true);
104 }
105
106 public void stop() {
107 setMotorValues(0, 0);
108 }
109
110 public double getLeftMotorVal() {
111 return (frontLeft.get() + rearLeft.get()) / 2;
112 }
113
114 public double getRightMotorVal() {
115 return (frontRight.get() + rearRight.get()) / 2;
116 }
117
118 // ENCODER METHODS
119
120 public double getLeftEncoderDistance() {
121 return leftEncoder.getDistance();
122 }
123
124 public double getRightEncoderDistance() {
125 return rightEncoder.getDistance();
126 }
127
128 public void printEncoderOutput() {
129 System.out.println("left: " + getLeftEncoderDistance());
130 System.out.println("right: " + getRightEncoderDistance());
131 // System.out.println(getAvgEncoderDistance());
132 }
133
134 public double getAvgEncoderDistance() {
135 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
136 }
137
138 public void resetEncoders() {
139 leftEncoder.reset();
140 rightEncoder.reset();
141 }
142
143 public double getLeftSpeed() {
144 return leftEncoder.getRate();
145 }
146
147 public double getRightSpeed() {
148 return rightEncoder.getRate();
149 }
150
151 public double getSpeed() {
152 return (getLeftSpeed() + getRightSpeed()) / 2.0;
153 }
154
155 // ------Gyro------//
156 public double getAngle() {
157 return this.imu.getAngle();
158 }
159
160 public void resetGyro() {
161 this.imu.reset();
162 }
163
164 /*
165 * @return a value that is the current setpoint for the piston kReverse or
166 * KForward
167 */
168 public Value getLeftGearPistonValue() {
169 return leftGearPiston.get();
170 }
171
172 /*
173 * @return a value that is the current setpoint for the piston kReverse or
174 * KForward
175 */
176 public Value getRightGearPistonValue() {
177 return rightGearPiston.get();
178 }
179
180 /*
181 * Changes the ball shift gear assembly to high
182 */
183 public void setHighGear() {
184 changeGear(Constants.DriveTrain.HIGH_GEAR);
185 }
186
187 /*
188 * Changes the ball shift gear assembly to low
189 */
190 public void setLowGear() {
191 changeGear(Constants.DriveTrain.LOW_GEAR);
192 }
193
194 /*
195 * Changes the gear to a DoubleSolenoid.Value
196 */
197 private void changeGear(DoubleSolenoid.Value gear) {
198 leftGearPiston.set(gear);
199 rightGearPiston.set(gear);
200 }
201
202 @Override
203 protected void initDefaultCommand() {
204 setDefaultCommand(new JoystickDrive());
205 }
206 }