changed set to return
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
CommitLineData
38a404b3
KZ
1package org.usfirst.frc.team3501.robot.subsystems;
2
3import org.usfirst.frc.team3501.robot.Constants;
d0a57bd9 4import org.usfirst.frc.team3501.robot.Robot;
5483fde9 5import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
04f2cb52 6
a1c76caf
CZ
7import com.ctre.CANTalon;
8
fa4e4a97 9import edu.wpi.first.wpilibj.Encoder;
ccbc35ae 10import edu.wpi.first.wpilibj.RobotDrive;
38a404b3
KZ
11import edu.wpi.first.wpilibj.command.Subsystem;
12
13public class DriveTrain extends Subsystem {
b634ebbc
CZ
14 public static final double WHEEL_DIAMETER = 6; // inches
15 public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
16 public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
17 / ENCODER_PULSES_PER_REVOLUTION;
18
cc42bd52
ME
19 private static DriveTrain driveTrain;
20 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
21 private final RobotDrive robotDrive;
22 private final Encoder leftEncoder, rightEncoder;
23
24 private DriveTrain() {
25 // MOTOR CONTROLLERS
26 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
27 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
28 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
29 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
30
31 // ENCODERS
32 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
3e2738c4 33 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
cc42bd52 34 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
3e2738c4 35 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
cc42bd52 36
b634ebbc
CZ
37 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
38 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
cc42bd52
ME
39
40 // ROBOT DRIVE
41 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
42 }
43
44 public static DriveTrain getDriveTrain() {
45 if (driveTrain == null) {
46 driveTrain = new DriveTrain();
47 }
48 return driveTrain;
49 }
50
51 // DRIVE METHODS
52 public void setMotorValues(final double left, final double right) {
53 frontLeft.set(left);
54 rearLeft.set(left);
55
b081e34b
ME
56 frontRight.set(-right);
57 rearRight.set(-right);
cc42bd52
ME
58 }
59
60 public void joystickDrive(final double thrust, final double twist) {
b081e34b 61 robotDrive.arcadeDrive(thrust, twist, true);
cc42bd52
ME
62 }
63
64 public void stop() {
65 setMotorValues(0, 0);
66 }
67
dfd97b3c 68 public double[] correctStraightness() {
d0a57bd9 69
70 double speedL, speedR, tempSpeedR;
71
72 // Max speed at mv of 0.2 (RIGHT)
73 final double maxSpeedOneR = 16.1;
74 // Max speed at mv of 0.4 (RIGHT)
75 final double maxSpeedTwoR = 49;
76 // Max speed at mv of 0.6 (RIGHT)
77 final double maxSpeedThreeR = 75.2;
78 // Max speed at mv of 0.2 (LEFT)
79 final double maxSpeedOneL = 13.8;
80 // Max speed at mv of 0.4 (LEFT)
81 final double maxSpeedTwoL = 46.9;
82 // Max speed at mv of 0.6 (LEFT)
83 final double maxSpeedThreeL = 74;
84
85 speedL = Robot.getDriveTrain().getLeftSpeed();
86 speedR = Robot.getDriveTrain().getRightSpeed();
dfd97b3c 87 System.out.println(speedL + speedR);
d0a57bd9 88
89 // Motor values for both motors
90 Double mvR = null, mvL = null;
91
92 // NOTE: Make threshold. Robot tends to go haywire.
93 // getting speed for both motors and exchanging them
94 speedL = Robot.getDriveTrain().getLeftSpeed();
95 speedR = Robot.getDriveTrain().getRightSpeed();
96 tempSpeedR = speedR;
97 speedR = speedL;
98 speedL = tempSpeedR;
99
100 // converting right motor speed to motor value
101 if (speedR <= maxSpeedOneR) {
c5c65f7b 102 mvR = speedR / (maxSpeedOneR * 5);
d0a57bd9 103 } else if (speedR <= maxSpeedTwoR) {
c5c65f7b 104 mvR = speedR / (maxSpeedTwoR * 2.5);
d0a57bd9 105 } else if (speedR <= maxSpeedThreeR) {
c5c65f7b 106 mvR = speedR / (maxSpeedThreeR * 1.66);
d0a57bd9 107 }
108
109 // converting left motor speed to motor value
110 if (speedL <= maxSpeedOneL) {
c5c65f7b 111 mvL = speedL / (maxSpeedOneL * 5);
d0a57bd9 112 } else if (speedL <= maxSpeedTwoL) {
c5c65f7b 113 mvL = speedL / (maxSpeedTwoL * 2.5);
d0a57bd9 114 } else if (speedL <= maxSpeedThreeL) {
c5c65f7b 115 mvL = speedL / (maxSpeedThreeL * 1.66);
d0a57bd9 116 }
117
dfd97b3c 118 double[] motorValues = { mvL, mvR };
119 return motorValues;
d0a57bd9 120 }
121
cc42bd52
ME
122 public double getFrontLeftMotorVal() {
123 return frontLeft.get();
124 }
125
126 public double getFrontRightMotorVal() {
127 return frontRight.get();
128 }
129
130 public double getRearLeftMotorVal() {
131 return frontLeft.get();
132 }
133
134 public double getRearRightMotorVal() {
135 return frontLeft.get();
136 }
137
cc42bd52
ME
138 // ENCODER METHODS
139
3a5d9ac7 140 public double getLeftEncoderDistance() {
cc42bd52
ME
141 return leftEncoder.getDistance();
142 }
143
3a5d9ac7 144 public double getRightEncoderDistance() {
cc42bd52
ME
145 return rightEncoder.getDistance();
146 }
147
148 public double getAvgEncoderDistance() {
149 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
150 }
151
152 public void resetEncoders() {
153 leftEncoder.reset();
154 rightEncoder.reset();
155 }
156
157 public double getLeftSpeed() {
158 return leftEncoder.getRate();
159 }
160
161 public double getRightSpeed() {
162 return rightEncoder.getRate();
163 }
164
165 public double getSpeed() {
166 return (getLeftSpeed() + getRightSpeed()) / 2.0;
167 }
168
169 @Override
170 protected void initDefaultCommand() {
171 setDefaultCommand(new JoystickDrive());
172 }
38a404b3
KZ
173
174}