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