Commit | Line | Data |
---|---|---|
38a404b3 KZ |
1 | package org.usfirst.frc.team3501.robot.subsystems; |
2 | ||
3 | import org.usfirst.frc.team3501.robot.Constants; | |
d0a57bd9 | 4 | import org.usfirst.frc.team3501.robot.Robot; |
5483fde9 | 5 | import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive; |
04f2cb52 | 6 | |
a1c76caf CZ |
7 | import com.ctre.CANTalon; |
8 | ||
fa4e4a97 | 9 | import edu.wpi.first.wpilibj.Encoder; |
ccbc35ae | 10 | import edu.wpi.first.wpilibj.RobotDrive; |
38a404b3 KZ |
11 | import edu.wpi.first.wpilibj.command.Subsystem; |
12 | ||
13 | public 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 | ||
d0a57bd9 | 68 | public void correctStraightness() { |
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(); | |
87 | ||
88 | // Motor values for both motors | |
89 | Double mvR = null, mvL = null; | |
90 | ||
91 | // NOTE: Make threshold. Robot tends to go haywire. | |
92 | // getting speed for both motors and exchanging them | |
93 | speedL = Robot.getDriveTrain().getLeftSpeed(); | |
94 | speedR = Robot.getDriveTrain().getRightSpeed(); | |
95 | tempSpeedR = speedR; | |
96 | speedR = speedL; | |
97 | speedL = tempSpeedR; | |
98 | ||
99 | // converting right motor speed to motor value | |
100 | if (speedR <= maxSpeedOneR) { | |
101 | mvR = speedR / maxSpeedOneR * 5; | |
102 | } else if (speedR <= maxSpeedTwoR) { | |
103 | mvR = speedR / maxSpeedTwoR * 2.5; | |
104 | } else if (speedR <= maxSpeedThreeR) { | |
105 | mvR = speedR / maxSpeedThreeR * 1.66; | |
106 | } | |
107 | ||
108 | // converting left motor speed to motor value | |
109 | if (speedL <= maxSpeedOneL) { | |
110 | mvL = speedL / maxSpeedOneL * 5; | |
111 | } else if (speedL <= maxSpeedTwoL) { | |
112 | mvL = speedL / maxSpeedTwoL * 2.5; | |
113 | } else if (speedL <= maxSpeedThreeL) { | |
114 | mvL = speedL / maxSpeedThreeL * 1.66; | |
115 | } | |
116 | ||
117 | // Setting motors at new motor values | |
118 | if (mvR != null && mvL != null) { | |
119 | Robot.getDriveTrain().setMotorValues(mvR, mvL); // we changed move to // | |
120 | } // speed | |
121 | ||
122 | } | |
123 | ||
cc42bd52 ME |
124 | public double getFrontLeftMotorVal() { |
125 | return frontLeft.get(); | |
126 | } | |
127 | ||
128 | public double getFrontRightMotorVal() { | |
129 | return frontRight.get(); | |
130 | } | |
131 | ||
132 | public double getRearLeftMotorVal() { | |
133 | return frontLeft.get(); | |
134 | } | |
135 | ||
136 | public double getRearRightMotorVal() { | |
137 | return frontLeft.get(); | |
138 | } | |
139 | ||
cc42bd52 ME |
140 | // ENCODER METHODS |
141 | ||
3a5d9ac7 | 142 | public double getLeftEncoderDistance() { |
cc42bd52 ME |
143 | return leftEncoder.getDistance(); |
144 | } | |
145 | ||
3a5d9ac7 | 146 | public double getRightEncoderDistance() { |
cc42bd52 ME |
147 | return rightEncoder.getDistance(); |
148 | } | |
149 | ||
150 | public double getAvgEncoderDistance() { | |
151 | return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2; | |
152 | } | |
153 | ||
154 | public void resetEncoders() { | |
155 | leftEncoder.reset(); | |
156 | rightEncoder.reset(); | |
157 | } | |
158 | ||
159 | public double getLeftSpeed() { | |
160 | return leftEncoder.getRate(); | |
161 | } | |
162 | ||
163 | public double getRightSpeed() { | |
164 | return rightEncoder.getRate(); | |
165 | } | |
166 | ||
167 | public double getSpeed() { | |
168 | return (getLeftSpeed() + getRightSpeed()) / 2.0; | |
169 | } | |
170 | ||
171 | @Override | |
172 | protected void initDefaultCommand() { | |
173 | setDefaultCommand(new JoystickDrive()); | |
174 | } | |
38a404b3 KZ |
175 | |
176 | } |