-
Notifications
You must be signed in to change notification settings - Fork 12
/
Shooter.java
275 lines (227 loc) · 10.7 KB
/
Shooter.java
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
package com.team254.frc2022.subsystems;
import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.TalonFX;
import com.team254.frc2022.Constants;
import com.team254.lib.drivers.Subsystem;
import com.team254.lib.drivers.TalonFXFactory;
import com.team254.lib.drivers.TalonUtil;
import com.team254.lib.loops.ILooper;
import com.team254.lib.loops.Loop;
import com.team254.lib.util.ReflectingCSVWriter;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
public class Shooter extends Subsystem {
private static Shooter mInstance;
public static Shooter getInstance() {
if (mInstance == null) {
mInstance = new Shooter();
}
return mInstance;
}
private final TalonFX mRightMaster, mLeftMaster;
public static class PeriodicIO {
// inputs
public double timestamp;
public double left_output_voltage;
public double left_supply_current;
public double left_stator_current;
public double right_output_voltage;
public double right_supply_current;
public double right_stator_current;
public double right_velocity_ticks_per_100_ms = 0.0;
public double left_velocity_ticks_per_100_ms = 0.0;
public double right_velocity_rpm = 0.0;
public double left_velocity_rpm = 0.0;
// outputs
public double demand = 0.0;
}
public enum ShooterControlState {
OPEN_LOOP, VELOCITY
}
private final PeriodicIO mPeriodicIO = new PeriodicIO();
private ReflectingCSVWriter<PeriodicIO> mCSVWriter = null;
private ShooterControlState mControlState = ShooterControlState.OPEN_LOOP;
private Shooter() {
mRightMaster = TalonFXFactory.createDefaultTalon(Constants.kShooterRightId);
mLeftMaster = TalonFXFactory.createDefaultTalon(Constants.kShooterLeftId);
resetSettings();
// initialize encoders and set status frames
TalonUtil.checkError(mRightMaster.configSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor, 0,
Constants.kLongCANTimeoutMs), "Shooter Right Master: Could not detect encoder: ");
TalonUtil.checkError(mLeftMaster.configSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor, 0,
Constants.kLongCANTimeoutMs), "Shooter Left Master: Could not detect encoder: ");
// TODO velocity measurement windows/periods?
// set right master gains
TalonUtil.checkError(mRightMaster.config_kP(0, Constants.kShooterKp, Constants.kLongCANTimeoutMs),
"Shooter Right Master: could not set kP: ");
TalonUtil.checkError(mRightMaster.config_kI(0, Constants.kShooterKi, Constants.kLongCANTimeoutMs),
"Shooter Right Master: could not set kI: ");
TalonUtil.checkError(mRightMaster.config_kD(0, Constants.kShooterKd, Constants.kLongCANTimeoutMs),
"Shooter Right Master: could not set kD: ");
TalonUtil.checkError(mRightMaster.config_kF(0, Constants.kShooterKf, Constants.kLongCANTimeoutMs),
"Shooter Right Master: Could not set kF: ");
TalonUtil.checkError(mRightMaster.config_IntegralZone(0, rpmToNativeUnits(Constants.kShooterIZoneRPM), Constants.kLongCANTimeoutMs),
"Shooter Right Master: could not set izone: ");
// set left master gains
TalonUtil.checkError(mLeftMaster.config_kP(0, Constants.kShooterKp, Constants.kLongCANTimeoutMs),
"Shooter Left Master: could not set kP: ");
TalonUtil.checkError(mLeftMaster.config_kI(0, Constants.kShooterKi, Constants.kLongCANTimeoutMs),
"Shooter Left Master: could not set kI: ");
TalonUtil.checkError(mLeftMaster.config_kD(0, Constants.kShooterKd, Constants.kLongCANTimeoutMs),
"Shooter Left Master: could not set kD: ");
TalonUtil.checkError(mLeftMaster.config_kF(0, Constants.kShooterKf, Constants.kLongCANTimeoutMs),
"Shooter Left Master: Could not set kF: ");
TalonUtil.checkError(mLeftMaster.config_IntegralZone(0, rpmToNativeUnits(Constants.kShooterIZoneRPM), Constants.kLongCANTimeoutMs),
"Shooter Left Master: could not set izone: ");
}
public void resetSettings() {
mRightMaster.setInverted(false);
// this makes us less sensitive to battery voltage, hopefully
mRightMaster.configPeakOutputForward(0.8);
mLeftMaster.configPeakOutputForward(0.8);
mRightMaster.configPeakOutputReverse(0.8);
mLeftMaster.configPeakOutputReverse(0.8);
mRightMaster.configVoltageCompSaturation(12.0, Constants.kLongCANTimeoutMs);
mRightMaster.enableVoltageCompensation(true);
mLeftMaster.setInverted(true);
mLeftMaster.configVoltageCompSaturation(12.0, Constants.kLongCANTimeoutMs);
mLeftMaster.enableVoltageCompensation(true);
mRightMaster.setNeutralMode(NeutralMode.Brake);
mLeftMaster.setNeutralMode(NeutralMode.Brake);
mRightMaster.configPeakOutputReverse(-1);
mLeftMaster.configPeakOutputReverse(-1);
mRightMaster.configPeakOutputForward(1);
mLeftMaster.configPeakOutputForward(1);
}
@Override
public void registerEnabledLoops(ILooper mEnabledLooper) {
mEnabledLooper.register(new Loop() {
@Override
public void onStart(double timestamp) {
// NOTE: Uncomment this to debug shooter
// startLogging();
}
@Override
public void onLoop(double timestamp) {}
@Override
public void onStop(double timestamp) {
// NOTE: Uncomment this to debug shooter
// stopLogging();
stop();
}
});
}
@Override
public void readPeriodicInputs() {
mPeriodicIO.timestamp = Timer.getFPGATimestamp();
mPeriodicIO.left_output_voltage = mLeftMaster.getMotorOutputVoltage();
mPeriodicIO.left_supply_current = mLeftMaster.getSupplyCurrent();
mPeriodicIO.left_stator_current = mLeftMaster.getStatorCurrent();
mPeriodicIO.right_output_voltage = mRightMaster.getMotorOutputVoltage();
mPeriodicIO.right_supply_current = mRightMaster.getSupplyCurrent();
mPeriodicIO.right_stator_current = mRightMaster.getStatorCurrent();
mPeriodicIO.right_velocity_ticks_per_100_ms = mRightMaster.getSelectedSensorVelocity();
mPeriodicIO.left_velocity_ticks_per_100_ms = mLeftMaster.getSelectedSensorVelocity();
mPeriodicIO.right_velocity_rpm = nativeUnitsToRPM(mPeriodicIO.right_velocity_ticks_per_100_ms);
mPeriodicIO.left_velocity_rpm = nativeUnitsToRPM(mPeriodicIO.left_velocity_ticks_per_100_ms);
if (mCSVWriter != null) {
mCSVWriter.add(mPeriodicIO);
}
}
@Override
public void writePeriodicOutputs() {
if (mControlState == ShooterControlState.OPEN_LOOP) {
mRightMaster.set(ControlMode.PercentOutput, mPeriodicIO.demand);
mLeftMaster.set(ControlMode.PercentOutput, mPeriodicIO.demand);
} else if (mControlState == ShooterControlState.VELOCITY) {
mRightMaster.set(ControlMode.Velocity, mPeriodicIO.demand);
mLeftMaster.set(ControlMode.Velocity, mPeriodicIO.demand);
}
}
@Override
public void stop() {
mRightMaster.set(ControlMode.PercentOutput, 0.0);
mLeftMaster.set(ControlMode.PercentOutput, 0.0);
}
@Override
public boolean checkSystem() {
return false;
}
public synchronized void setOpenLoop(double power) {
mControlState = ShooterControlState.OPEN_LOOP;
mPeriodicIO.demand = power;
}
public synchronized void setRPM(double rpm) {
mControlState = ShooterControlState.VELOCITY;
mPeriodicIO.demand = rpmToNativeUnits(rpm);
}
public synchronized boolean isAtSetpoint() {
return getLeftRPM() / nativeUnitsToRPM(mPeriodicIO.demand) > Constants.kShooterAllowablePercentError &&
getRightRPM() / nativeUnitsToRPM(mPeriodicIO.demand) > Constants.kShooterAllowablePercentError;
}
public synchronized double getRightRPM() {
return nativeUnitsToRPM(getRightVelocityNativeUnits());
}
public synchronized double getRightVelocityNativeUnits() {
return mPeriodicIO.right_velocity_ticks_per_100_ms;
}
public synchronized double getLeftRPM() {
return nativeUnitsToRPM(getLeftVelocityNativeUnits());
}
public synchronized double getLeftVelocityNativeUnits() {
return mPeriodicIO.left_velocity_ticks_per_100_ms;
}
public synchronized double getAverageRPM() {
return (getRightRPM() + getLeftRPM()) / 2.0;
}
public synchronized double getDemandRPM() {
return nativeUnitsToRPM(mPeriodicIO.demand);
}
public synchronized double getAverageOutputVoltage() {
return (mPeriodicIO.right_output_voltage + mPeriodicIO.left_output_voltage) / 2.0;
}
public synchronized double getAverageSupplyCurrent() {
return (mPeriodicIO.right_supply_current + mPeriodicIO.left_supply_current) / 2.0;
}
public synchronized double getAverageStatorCurrent() {
return (mPeriodicIO.right_stator_current + mPeriodicIO.left_stator_current) / 2.0;
}
public synchronized void startLogging() {
if (mCSVWriter == null) {
mCSVWriter = new ReflectingCSVWriter<>("/home/lvuser/SHOOTER-LOGS.csv", PeriodicIO.class);
}
}
public synchronized void stopLogging() {
if (mCSVWriter != null) {
mCSVWriter.flush();
mCSVWriter = null;
}
}
/**
* @param ticks_per_100_ms
* @return rpm
*/
public double nativeUnitsToRPM(double ticks_per_100_ms) {
return ticks_per_100_ms * 10.0 * 60.0 / Constants.kShooterTicksPerRevolution;
}
/**
* @param rpm
* @return ticks per 100 ms
*/
public double rpmToNativeUnits(double rpm) {
return rpm / 60.0 / 10.0 * Constants.kShooterTicksPerRevolution;
}
@Override
public void outputTelemetry() {
SmartDashboard.putNumber("Shooter Right Master RPM", getRightRPM());
SmartDashboard.putNumber("Shooter Left Master RPM", getLeftRPM());
SmartDashboard.putNumber("Shooter Left Master RPM Error", getLeftRPM() - nativeUnitsToRPM(mPeriodicIO.demand));
SmartDashboard.putNumber("Shooter Demand", mControlState == ShooterControlState.OPEN_LOOP ? mPeriodicIO.demand
: (mControlState == ShooterControlState.VELOCITY ? nativeUnitsToRPM(mPeriodicIO.demand) : 0.0));
if (mCSVWriter != null) {
mCSVWriter.write();
}
}
}