bb7ef453b1e2944ebdfec1aa953a12d7f3247c00
[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, turnI, turnD;
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 gyroController = new PIDController(turnP, turnI, turnD);
49
50 // MOTOR CONTROLLERS
51 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
52 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
53 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
54 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
55
56 // ENCODERS
57 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
58 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
59 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
60 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
61
62 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
63 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
64
65 // ROBOT DRIVE
66 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
67
68 this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
69
70 // TODO: Not sure if MODULE_NUMBER should be the same for both
71 leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
72 Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
73 Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
74 rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
75 Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
76 Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
77 }
78
79 public PIDController getDriveController() {
80 return this.driveController;
81 }
82
83 public PIDController getGyroController() {
84 return this.gyroController;
85 }
86
87 public static DriveTrain getDriveTrain() {
88 if (driveTrain == null) {
89 driveTrain = new DriveTrain();
90 }
91 return driveTrain;
92 }
93
94 // DRIVE METHODS
95 public void setMotorValues(final double left, final double right) {
96 frontLeft.set(left);
97 rearLeft.set(left);
98
99 frontRight.set(-right);
100 rearRight.set(-right);
101 }
102
103 public void joystickDrive(final double thrust, final double twist) {
104 robotDrive.arcadeDrive(thrust, twist, true);
105 }
106
107 public void stop() {
108 setMotorValues(0, 0);
109 }
110
111 public double getLeftMotorVal() {
112 return (frontLeft.get() + rearLeft.get()) / 2;
113 }
114
115 public double getRightMotorVal() {
116 return (frontRight.get() + rearRight.get()) / 2;
117 }
118
119 // ENCODER METHODS
120
121 public double getLeftEncoderDistance() {
122 return leftEncoder.getDistance();
123 }
124
125 public double getRightEncoderDistance() {
126 return rightEncoder.getDistance();
127 }
128
129 public void printEncoderOutput() {
130 System.out.println("left: " + getLeftEncoderDistance());
131 System.out.println("right: " + getRightEncoderDistance());
132 // System.out.println(getAvgEncoderDistance());
133 }
134
135 public double getAvgEncoderDistance() {
136 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
137 }
138
139 public void resetEncoders() {
140 leftEncoder.reset();
141 rightEncoder.reset();
142 }
143
144 public double getLeftSpeed() {
145 return leftEncoder.getRate();
146 }
147
148 public double getRightSpeed() {
149 return rightEncoder.getRate();
150 }
151
152 public double getSpeed() {
153 return (getLeftSpeed() + getRightSpeed()) / 2.0;
154 }
155
156 // ------Gyro------//
157 public double getAngle() {
158 return this.imu.getAngle();
159 }
160
161 public void resetGyro() {
162 this.imu.reset();
163 }
164
165 /*
166 * @return a value that is the current setpoint for the piston kReverse or
167 * KForward
168 */
169 public Value getLeftGearPistonValue() {
170 return leftGearPiston.get();
171 }
172
173 /*
174 * @return a value that is the current setpoint for the piston kReverse or
175 * KForward
176 */
177 public Value getRightGearPistonValue() {
178 return rightGearPiston.get();
179 }
180
181 /*
182 * Changes the ball shift gear assembly to high
183 */
184 public void setHighGear() {
185 changeGear(Constants.DriveTrain.HIGH_GEAR);
186 }
187
188 /*
189 * Changes the ball shift gear assembly to low
190 */
191 public void setLowGear() {
192 changeGear(Constants.DriveTrain.LOW_GEAR);
193 }
194
195 /*
196 * Changes the gear to a DoubleSolenoid.Value
197 */
198 private void changeGear(DoubleSolenoid.Value gear) {
199 leftGearPiston.set(gear);
200 rightGearPiston.set(gear);
201 }
202
203 @Override
204 protected void initDefaultCommand() {
205 setDefaultCommand(new JoystickDrive());
206 }
207 }