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