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