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