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