fd6530e5404d26a08985c7abe5df66f555e69af6
[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.BNO055;
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.006, driveI = 0.001, driveD = -0.002;
18 public static double defaultGyroP = 0.004, defaultGyroI = 0.0013,
19 defaultGyroD = -0.005;
20 public static double driveP = 0.008, driveI = 0.001, driveD = -0.002;
21 public static double defaultGyroP = 0.009, defaultGyroI = 0.00000,
22 defaultGyroD = -0.000;
23 private double gyroZero = 0;
24
25 public static final double WHEEL_DIAMETER = 6; // inches
26 public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
27 public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
28 / ENCODER_PULSES_PER_REVOLUTION;
29
30 private static DriveTrain driveTrain;
31 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
32 private final RobotDrive robotDrive;
33 private final Encoder leftEncoder, rightEncoder;
34 private final DoubleSolenoid leftGearPiston, rightGearPiston;
35
36 private ADXRS450_Gyro imu;
37 private BNO055 imu;
38
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,
48 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
49 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
50 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
51
52 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
53 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
54
55 // ROBOT DRIVE
56 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
57
58 this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
59 shifter = DoubleSolenoid(10, Constants.DriveTrain.SHIFTER_FORWARD,
60 Constants.DriveTrain.SHIFTER_REVERSE);
61 leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER,
62 Constants.DriveTrain.LEFT_FORWARD, Constants.DriveTrain.LEFT_REVERSE);
63 rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER,
64 Constants.DriveTrain.RIGHT_FORWARD, Constants.DriveTrain.RIGHT_REVERSE);
65 }
66
67 public static DriveTrain getDriveTrain() {
68 if (driveTrain == null) {
69 driveTrain = new DriveTrain();
70 }
71 return driveTrain;
72 }
73
74 // DRIVE METHODS
75 public void setMotorValues(final double left, final double right) {
76 frontLeft.set(left);
77 rearLeft.set(left);
78
79 frontRight.set(-right);
80 rearRight.set(-right);
81 }
82
83 public void joystickDrive(final double thrust, final double twist) {
84 robotDrive.arcadeDrive(thrust, twist, true);
85 }
86
87 public void stop() {
88 setMotorValues(0, 0);
89 }
90
91 public double getLeftMotorVal() {
92 return (frontLeft.get() + rearLeft.get()) / 2;
93 }
94
95 public double getRightMotorVal() {
96 return (frontRight.get() + rearRight.get()) / 2;
97 }
98
99 // ENCODER METHODS
100
101 public double getLeftEncoderDistance() {
102 return leftEncoder.getDistance();
103 }
104
105 public double getRightEncoderDistance() {
106 return rightEncoder.getDistance();
107 }
108
109 public void printEncoderOutput() {
110 // System.out.println("left: " + getLeftEncoderDistance());
111 // System.out.println("right: " + getRightEncoderDistance());
112 System.out.println(getAvgEncoderDistance());
113 }
114
115 public double getAvgEncoderDistance() {
116 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
117 }
118
119 public void resetEncoders() {
120 leftEncoder.reset();
121 rightEncoder.reset();
122 }
123
124 public double getLeftSpeed() {
125 return leftEncoder.getRate();
126 }
127
128 public double getRightSpeed() {
129 return rightEncoder.getRate();
130 }
131
132 public double getSpeed() {
133 return (getLeftSpeed() + getRightSpeed()) / 2.0;
134 }
135
136 // ------Gyro------//
137 public double getAngle() {
138 return this.imu.getAngle() - this.gyroZero;
139 }
140
141 public void resetGyro() {
142 this.imu.reset();
143 }
144
145 public double getZeroAngle() {
146 return this.gyroZero;
147 /*
148 * @return a value that is the current setpoint for the piston kReverse or
149 * KForward
150 */
151 public Value getLeftGearPistonValue() {
152 return leftGearPiston.get();
153 }
154
155 /*
156 * @return a value that is the current setppoint for the piston kReverse or
157 * kForward
158 */
159 public Value getRightGearPistonValue() {
160 return rightGearPiston.get();
161 }
162
163 /*
164 * Changes the ball shift gear assembly to high
165 */
166 public void setHighGear() {
167 changeGear(Constants.DriveTrain.HIGH_GEAR);
168 }
169
170 /*
171 * Changes the ball shift gear assembly to low
172 */
173 public void setLowGear() {
174 changeGear(Constants.DriveTrain.LOW_GEAR);
175 }
176
177 /*
178 * Changes the gear to a DoubleSolenoid.Value
179 */
180 private void changeGear(DoubleSolenoid.Value gear) {
181 leftGearPiston.set(gear);
182 rightGearPiston.set(gear);
183 }
184
185 public double getAngle() {
186 if (!this.imu.isInitialized())
187 return -1;
188 return this.imu.getHeading() - this.gyroZero;
189 }
190
191 public void resetGyro() {
192 this.gyroZero = this.getAngle();
193
194 }
195
196 public double getZeroAngle() {
197 return this.gyroZero;
198 }
199
200 @Override
201 protected void initDefaultCommand() {
202 setDefaultCommand(new JoystickDrive());
203 }
204
205 }