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