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