1
|
|
|
package org.usfirst.frc.team3695.robot.subsystems;
|
2
|
|
|
|
3
|
|
|
import com.ctre.phoenix.motorcontrol.ControlMode;
|
4
|
|
|
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
|
5
|
|
|
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
|
6
|
|
|
import edu.wpi.first.wpilibj.BuiltInAccelerometer;
|
7
|
|
|
import edu.wpi.first.wpilibj.Joystick;
|
8
|
|
|
import edu.wpi.first.wpilibj.command.Subsystem;
|
9
|
|
|
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
|
10
|
|
|
import org.usfirst.frc.team3695.robot.Constants;
|
11
|
|
|
import org.usfirst.frc.team3695.robot.Robot;
|
12
|
|
|
import org.usfirst.frc.team3695.robot.commands.ManualCommandDrive;
|
13
|
|
|
import org.usfirst.frc.team3695.robot.enumeration.Bot;
|
14
|
|
|
import org.usfirst.frc.team3695.robot.enumeration.Drivetrain;
|
15
|
|
|
import org.usfirst.frc.team3695.robot.util.Xbox;
|
16
|
|
|
|
17
|
|
|
/** VROOM VROOM */
|
18
|
|
|
public class SubsystemDrive extends Subsystem {
|
19
|
|
|
|
20
|
|
|
|
21
|
|
|
private TalonSRX leftMaster;
|
22
|
|
|
private TalonSRX leftSlave;
|
23
|
|
|
private TalonSRX rightMaster;
|
24
|
|
|
private TalonSRX rightSlave;
|
25
|
|
|
|
26
|
|
|
public Drivetrain drivetrain;
|
27
|
|
|
|
28
|
|
|
public static boolean reversing;
|
|
|
|
|
29
|
|
|
|
30
|
|
|
public static boolean docking;
|
|
|
|
|
31
|
|
|
private static double dockInhibitor;
|
32
|
|
|
|
33
|
|
|
public static boolean override;
|
|
|
|
|
34
|
|
|
|
35
|
|
|
private Accelerometer accel;
|
36
|
|
|
|
37
|
|
|
/**
|
38
|
|
|
* Allowable tolerance to be considered in range when driving a distance, in rotations
|
39
|
|
|
*/
|
40
|
|
|
public static final double DISTANCE_ALLOWABLE_ERROR = SubsystemDrive.in2rot(2.0);
|
41
|
|
|
|
42
|
|
|
/**
|
43
|
|
|
* runs at robot boot
|
44
|
|
|
*/
|
45
|
|
|
public void initDefaultCommand() {
|
46
|
|
|
setDefaultCommand(new ManualCommandDrive());
|
47
|
|
|
}
|
48
|
|
|
|
49
|
|
|
|
50
|
|
|
/**
|
51
|
|
|
* converts left magnetic encoder's magic units to inches
|
52
|
|
|
*/
|
53
|
|
|
public static final double leftMag2in(double leftMag) {
|
54
|
|
|
return leftMag / Constants.LEFT_MAGIC_PER_INCHES;
|
55
|
|
|
}
|
56
|
|
|
|
57
|
|
|
/**
|
58
|
|
|
* converts right magnetic encoder's magic units to inches
|
59
|
|
|
*/
|
60
|
|
|
public static final double rightMag2in(double rightMag) {
|
61
|
|
|
return rightMag / Constants.RIGHT_MAGIC_PER_INCHES;
|
62
|
|
|
}
|
63
|
|
|
|
64
|
|
|
/**
|
65
|
|
|
* converts RPM to inches per second
|
66
|
|
|
*/
|
67
|
|
|
public static final double rpm2ips(double rpm) {
|
68
|
|
|
return rpm / 60.0 * Constants.WHEEL_DIAMETER * Math.PI;
|
|
|
|
|
69
|
|
|
}
|
70
|
|
|
|
71
|
|
|
/**
|
72
|
|
|
* converts an inches per second number to RPM
|
73
|
|
|
*/
|
74
|
|
|
public static final double ips2rpm(double ips) {
|
75
|
|
|
return ips * 60.0 / Constants.WHEEL_DIAMETER / Math.PI;
|
|
|
|
|
76
|
|
|
}
|
77
|
|
|
|
78
|
|
|
/**
|
79
|
|
|
* converts rotations to distance traveled in inches
|
80
|
|
|
*/
|
81
|
|
|
public static final double rot2in(double rot) {
|
82
|
|
|
return rot * Constants.WHEEL_DIAMETER * Math.PI;
|
83
|
|
|
}
|
84
|
|
|
|
85
|
|
|
/**
|
86
|
|
|
* converts distance traveled in inches to rotations
|
87
|
|
|
*/
|
88
|
|
|
public static final double in2rot(double in) {
|
89
|
|
|
return in / Constants.WHEEL_DIAMETER / Math.PI;
|
90
|
|
|
}
|
91
|
|
|
|
92
|
|
|
|
93
|
|
|
/**
|
94
|
|
|
* apply left motor invert
|
95
|
|
|
*/
|
96
|
|
|
public static final double leftify(double left) {
|
97
|
|
|
left = (left > 1.0 ? 1.0 : (left < -1.0 ? -1.0 : left));
|
98
|
|
|
Boolean invert = Robot.bot == Bot.OOF ? Constants.OOF.LEFT_MOTOR_INVERT : Constants.SWISS.LEFT_MOTOR_INVERT;
|
99
|
|
|
return left * (invert ? -1.0 : 1.0) * (docking ? dockInhibitor : 1);
|
100
|
|
|
}
|
101
|
|
|
|
102
|
|
|
/**
|
103
|
|
|
* apply right motor invert
|
104
|
|
|
*/
|
105
|
|
|
public static final double rightify(double right) {
|
106
|
|
|
right = (right > 1.0 ? 1.0 : (right < -1.0 ? -1.0 : right));
|
107
|
|
|
Boolean invert = Robot.bot == Bot.OOF ? Constants.OOF.RIGHT_MOTOR_INVERT : Constants.SWISS.RIGHT_MOTOR_INVERT;
|
108
|
|
|
return right * (invert ? -1.0 : 1.0) * (docking ? dockInhibitor : 1);
|
109
|
|
|
}
|
110
|
|
|
|
111
|
|
|
/**
|
112
|
|
|
* gives birth to the CANTalons
|
113
|
|
|
*/
|
114
|
|
|
public SubsystemDrive() {
|
115
|
|
|
|
116
|
|
|
accel = new BuiltInAccelerometer();
|
117
|
|
|
|
118
|
|
|
drivetrain = Drivetrain.ROCKET_LEAGUE;
|
119
|
|
|
|
120
|
|
|
reversing = false;
|
121
|
|
|
|
122
|
|
|
docking = false;
|
123
|
|
|
dockInhibitor = 0.5d;
|
|
|
|
|
124
|
|
|
|
125
|
|
|
override = false;
|
126
|
|
|
|
127
|
|
|
// masters
|
128
|
|
|
leftMaster = new TalonSRX(Constants.LEFT_MASTER);
|
129
|
|
|
leftMaster.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, Constants.LEFT_PID, Constants.TIMEOUT_PID);
|
130
|
|
|
rightMaster = new TalonSRX(Constants.RIGHT_MASTER);
|
131
|
|
|
rightMaster.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative, Constants.RIGHT_PID, Constants.TIMEOUT_PID);
|
132
|
|
|
|
133
|
|
|
// slaves
|
134
|
|
|
leftSlave = new TalonSRX(Constants.LEFT_SLAVE);
|
135
|
|
|
leftSlave.follow(leftMaster);
|
136
|
|
|
rightSlave = new TalonSRX(Constants.RIGHT_SLAVE);
|
137
|
|
|
rightSlave.follow(rightMaster);
|
138
|
|
|
}
|
139
|
|
|
|
140
|
|
|
public void setDrivetrain(Drivetrain drivetrain) {
|
141
|
|
|
this.drivetrain = drivetrain;
|
142
|
|
|
}
|
143
|
|
|
|
144
|
|
|
public double getYAngle() {
|
145
|
|
|
//http://www.hobbytronics.co.uk/accelerometer-info
|
146
|
|
|
//Formula for getting the angle through the accelerometer
|
147
|
|
|
//arctan returns in radians so we convert to degrees.
|
148
|
|
|
return Math.atan(accel.getY() / Math.sqrt(Math.pow(accel.getX(), 2) + Math.pow(accel.getZ(), 2))) * 180 / Math.PI;
|
|
|
|
|
149
|
|
|
}
|
150
|
|
|
|
151
|
|
|
public void isDocking(boolean docking, double dockInhibitor) {
|
152
|
|
|
this.docking = docking;
|
|
|
|
|
153
|
|
|
this.dockInhibitor = dockInhibitor;
|
|
|
|
|
154
|
|
|
}
|
155
|
|
|
|
156
|
|
|
public void isReversing(boolean reversing) {
|
157
|
|
|
this.reversing = reversing;
|
|
|
|
|
158
|
|
|
}
|
159
|
|
|
|
160
|
|
|
/**
|
161
|
|
|
* simple rocket league drive code
|
162
|
|
|
* independent rotation and acceleration
|
163
|
|
|
*/
|
164
|
|
|
|
165
|
|
|
public void driveRLTank(Joystick joy, double ramp, double inhibitor) {
|
166
|
|
|
double adder = Xbox.RT(joy) - Xbox.LT(joy);
|
167
|
|
|
double left = adder + (Xbox.LEFT_X(joy) / 1.333333);
|
|
|
|
|
168
|
|
|
double right = adder - (Xbox.LEFT_X(joy) / 1.333333);
|
|
|
|
|
169
|
|
|
|
170
|
|
|
setRamps(ramp);
|
171
|
|
|
|
172
|
|
|
// if (getYAngle() > Constants.TILT_ANGLE ) {
|
173
|
|
|
// leftMaster.set(ControlMode.PercentOutput, -1*Constants.RECOVERY_SPEED);
|
174
|
|
|
// rightMaster.set(ControlMode.PercentOutput, -1*Constants.RECOVERY_SPEED);
|
175
|
|
|
// } else if (getYAngle() < -1*Constants.TILT_ANGLE){
|
176
|
|
|
// leftMaster.set(ControlMode.PercentOutput, Constants.RECOVERY_SPEED);
|
177
|
|
|
// rightMaster.set(ControlMode.PercentOutput, Constants.RECOVERY_SPEED);
|
178
|
|
|
// } else {
|
179
|
|
|
leftMaster.set(ControlMode.PercentOutput, leftify(left)* (reversing ? -1.0 : 1.0));
|
180
|
|
|
rightMaster.set(ControlMode.PercentOutput, rightify(right)* (reversing ? -1.0 : 1.0));
|
181
|
|
|
// }
|
182
|
|
|
|
183
|
|
|
}
|
184
|
|
|
|
185
|
|
|
/**
|
186
|
|
|
* drive code where rotation is dependent on acceleration
|
187
|
|
|
*
|
188
|
|
|
* @param radius 0.00-1.00, 1 being zero radius and 0 being driving in a line
|
189
|
|
|
*/
|
190
|
|
|
public void driveForza(Joystick joy, double ramp, double radius, double inhibitor) {
|
191
|
|
|
double left = 0,
|
192
|
|
|
right = 0;
|
|
|
|
|
193
|
|
|
double acceleration = Xbox.RT(joy) - Xbox.LT(joy);
|
194
|
|
|
|
195
|
|
|
setRamps(ramp);
|
196
|
|
|
// if (getYAngle() > Constants.TILT_ANGLE ) {
|
197
|
|
|
// leftMaster.set(ControlMode.PercentOutput, -1 * Constants.RECOVERY_SPEED);
|
198
|
|
|
// rightMaster.set(ControlMode.PercentOutput, -1 * Constants.RECOVERY_SPEED);
|
199
|
|
|
// } else if (getYAngle() < -1 * Constants.TILT_ANGLE){
|
200
|
|
|
// leftMaster.set(ControlMode.PercentOutput, Constants.RECOVERY_SPEED);
|
201
|
|
|
// rightMaster.set(ControlMode.PercentOutput, Constants.RECOVERY_SPEED);
|
202
|
|
|
// } else {
|
203
|
|
|
|
204
|
|
|
if (Xbox.LEFT_X(joy) < 0) {
|
205
|
|
|
right = acceleration;
|
206
|
|
|
left = (acceleration * ((2 * (1 - Math.abs(Xbox.LEFT_X(joy)))) - 1)) / radius;
|
|
|
|
|
207
|
|
|
} else if (Xbox.LEFT_X(joy) > 0) {
|
208
|
|
|
left = acceleration;
|
209
|
|
|
right = (acceleration * ((2 * (1 - Math.abs(Xbox.LEFT_X(joy)))) - 1)) / radius;
|
|
|
|
|
210
|
|
|
} else {
|
211
|
|
|
left = acceleration;
|
212
|
|
|
right = acceleration;
|
213
|
|
|
}
|
214
|
|
|
// }
|
215
|
|
|
|
216
|
|
|
leftMaster.set(ControlMode.PercentOutput, leftify(left) * inhibitor * (reversing ? -1.0 : 1.0));
|
217
|
|
|
rightMaster.set(ControlMode.PercentOutput, rightify(right) * inhibitor * (reversing ? -1.0 : 1.0));
|
218
|
|
|
}
|
219
|
|
|
|
220
|
|
|
public void setRamps(double ramp) {
|
221
|
|
|
leftMaster.configOpenloopRamp(ramp, 10);
|
|
|
|
|
222
|
|
|
leftSlave.configOpenloopRamp(ramp, 10);
|
|
|
|
|
223
|
|
|
rightMaster.configOpenloopRamp(ramp, 10);
|
|
|
|
|
224
|
|
|
rightSlave.configOpenloopRamp(ramp, 10);
|
|
|
|
|
225
|
|
|
}
|
226
|
|
|
|
227
|
|
|
|
228
|
|
|
public void setOverride(boolean override){
|
229
|
|
|
this.override = override;
|
|
|
|
|
230
|
|
|
}
|
231
|
|
|
|
232
|
|
|
public double getError() {
|
233
|
|
|
return (leftify(leftMaster.getErrorDerivative(Constants.LEFT_PID)) + rightify(rightMaster.getErrorDerivative(Constants.RIGHT_PID))) / 2.0;
|
|
|
|
|
234
|
|
|
}
|
235
|
|
|
|
236
|
|
|
public double getRightPos() {
|
237
|
|
|
return rightMag2in(rightMaster.getSelectedSensorPosition(Constants.RIGHT_PID));
|
238
|
|
|
}
|
239
|
|
|
|
240
|
|
|
public double getLeftPos() {
|
241
|
|
|
return leftMag2in(leftMaster.getSelectedSensorPosition(Constants.LEFT_PID));
|
242
|
|
|
}
|
243
|
|
|
|
244
|
|
|
public boolean driveDistance(double leftIn, double rightIn) {
|
245
|
|
|
double leftGoal = in2rot(leftIn);
|
246
|
|
|
double rightGoal = in2rot(rightIn);
|
247
|
|
|
|
248
|
|
|
leftMaster.set(ControlMode.MotionMagic, leftGoal);
|
249
|
|
|
rightMaster.set(ControlMode.MotionMagic, rightGoal);
|
250
|
|
|
|
251
|
|
|
boolean leftInRange =
|
252
|
|
|
getLeftPos() > leftify(leftGoal) - DISTANCE_ALLOWABLE_ERROR &&
|
253
|
|
|
getLeftPos() < leftify(leftGoal) + DISTANCE_ALLOWABLE_ERROR;
|
254
|
|
|
boolean rightInRange =
|
255
|
|
|
getRightPos() > rightify(rightGoal) - DISTANCE_ALLOWABLE_ERROR &&
|
256
|
|
|
getRightPos() < rightify(rightGoal) + DISTANCE_ALLOWABLE_ERROR;
|
257
|
|
|
|
258
|
|
|
return leftInRange && rightInRange;
|
259
|
|
|
}
|
260
|
|
|
|
261
|
|
|
public void driveDirect(double left, double right) {
|
262
|
|
|
leftMaster.set(ControlMode.PercentOutput, left);
|
263
|
|
|
rightMaster.set(ControlMode.PercentOutput, right);
|
264
|
|
|
}
|
265
|
|
|
|
266
|
|
|
public void setPIDF(TalonSRX talon, double p, double i, double d, double f) {
|
267
|
|
|
talon.selectProfileSlot(0, 0);
|
268
|
|
|
talon.config_kF(0, f, Constants.TIMEOUT_PID);
|
269
|
|
|
talon.config_kP(0, p, Constants.TIMEOUT_PID);
|
270
|
|
|
talon.config_kI(0, i, Constants.TIMEOUT_PID);
|
271
|
|
|
talon.config_kD(0, d, Constants.TIMEOUT_PID);
|
272
|
|
|
}
|
273
|
|
|
|
274
|
|
|
public void reset() {
|
275
|
|
|
leftMaster.setSelectedSensorPosition(0, Constants.LEFT_PID, Constants.TIMEOUT_PID);
|
276
|
|
|
rightMaster.setSelectedSensorPosition(0, Constants.RIGHT_PID, Constants.TIMEOUT_PID);
|
277
|
|
|
}
|
278
|
|
|
}
|
279
|
|
|
|
See this CWE advisory on why this is a security issue.