16
16
import org .mayheminc .util .PidTunerObject ;
17
17
18
18
public class Shooter extends SubsystemBase implements PidTunerObject {
19
- private final MayhemTalonSRX shooterWheelTalon = new MayhemTalonSRX (Constants .Talon .SHOOTER_WHEEL );
19
+ private final MayhemTalonSRX shooterWheelLeft = new MayhemTalonSRX (Constants .Talon .SHOOTER_WHEEL_LEFT );
20
+ private final MayhemTalonSRX shooterWheelRight = new MayhemTalonSRX (Constants .Talon .SHOOTER_WHEEL_RIGHT );
20
21
private final MayhemTalonSRX turretTalon = new MayhemTalonSRX (Constants .Talon .SHOOTER_TURRET );
21
22
private final MayhemTalonSRX hoodTalon = new MayhemTalonSRX (Constants .Talon .SHOOTER_HOOD );
22
23
private final MayhemTalonSRX feederTalon = new MayhemTalonSRX (Constants .Talon .SHOOTER_FEEDER );
@@ -47,20 +48,24 @@ public class Shooter extends SubsystemBase implements PidTunerObject {
47
48
* Creates a new Shooter.
48
49
*/
49
50
public Shooter () {
51
+ configureWheelFalcons ();
50
52
configureTurretTalon ();
51
- configureWheelTalon ();
52
53
configureHoodTalon ();
53
54
configureFeederTalon ();
54
55
55
- shooterWheelTalon .config_kP (0 , 3.0 , 0 );
56
- shooterWheelTalon .config_kI (0 , 0.0 , 0 );
57
- shooterWheelTalon .config_kD (0 , 0.0 , 0 );
58
- shooterWheelTalon .config_kF (0 , 0.048 ); // 1023.0 / convertRpmToTicksPer100ms(5760), 0);
56
+ shooterWheelLeft .config_kP (0 , 3.0 , 0 );
57
+ shooterWheelLeft .config_kI (0 , 0.0 , 0 );
58
+ shooterWheelLeft .config_kD (0 , 0.0 , 0 );
59
+ shooterWheelLeft .config_kF (0 , 0.046 ); // 1023.0 / convertRpmToTicksPer100ms(5760), 0);
60
+
61
+ // set right Falcon to follow the left Falcon
62
+ shooterWheelRight .changeControlMode (ControlMode .Follower );
63
+ shooterWheelRight .set (shooterWheelLeft .getDeviceID ());
59
64
}
60
65
61
66
public void init () {
67
+ configureWheelFalcons ();
62
68
configureTurretTalon ();
63
- configureWheelTalon ();
64
69
configureHoodTalon ();
65
70
configureFeederTalon ();
66
71
@@ -120,11 +125,20 @@ void configureTurretTalon() {
120
125
this .setTurretVBus (0.0 );
121
126
}
122
127
123
- private void configureWheelTalon () {
124
- shooterWheelTalon .setFeedbackDevice (FeedbackDevice .IntegratedSensor );
125
- shooterWheelTalon .setNeutralMode (NeutralMode .Coast );
126
- shooterWheelTalon .configNominalOutputVoltage (+0.0f , -0.0f );
127
- shooterWheelTalon .configPeakOutputVoltage (+12.0 , 0.0 );
128
+ private void configureWheelFalcons () {
129
+ shooterWheelLeft .setFeedbackDevice (FeedbackDevice .IntegratedSensor );
130
+ shooterWheelLeft .setNeutralMode (NeutralMode .Coast );
131
+ shooterWheelLeft .configNominalOutputVoltage (+0.0f , -0.0f );
132
+ shooterWheelLeft .configPeakOutputVoltage (+12.0 , 0.0 );
133
+ shooterWheelLeft .setInverted (false );
134
+ shooterWheelLeft .setSensorPhase (false );
135
+
136
+ shooterWheelRight .setFeedbackDevice (FeedbackDevice .IntegratedSensor );
137
+ shooterWheelRight .setNeutralMode (NeutralMode .Coast );
138
+ shooterWheelRight .configNominalOutputVoltage (+0.0f , -0.0f );
139
+ shooterWheelRight .configPeakOutputVoltage (+12.0 , 0.0 );
140
+ shooterWheelRight .setInverted (true );
141
+ shooterWheelRight .setSensorPhase (true );
128
142
}
129
143
130
144
@ Override
@@ -150,15 +164,29 @@ public double getAzimuthForCapturedImage() {
150
164
}
151
165
152
166
private void UpdateDashboard () {
153
- SmartDashboard .putNumber ("Shooter Wheel pos" , shooterWheelTalon .getSelectedSensorPosition (0 ));
154
- SmartDashboard .putNumber ("Shooter Wheel speed" , shooterWheelTalon .getSelectedSensorVelocity (0 ));
167
+ SmartDashboard .putNumber ("Shooter Wheel pos" , shooterWheelLeft .getSelectedSensorPosition (0 ));
168
+ SmartDashboard .putNumber ("Shooter Wheel speed" , shooterWheelLeft .getSelectedSensorVelocity (0 ));
155
169
SmartDashboard .putNumber ("Shooter Wheel RPM" ,
156
- convertTicksPer100msToRPM (shooterWheelTalon .getSelectedSensorVelocity (0 )));
170
+ convertTicksPer100msToRPM (shooterWheelLeft .getSelectedSensorVelocity (0 )));
157
171
158
172
SmartDashboard .putNumber ("Shooter Wheel target RPM" , m_targetSpeedRPM );
159
173
SmartDashboard .putNumber ("Shooter Wheel Error" ,
160
- m_targetSpeedRPM - convertTicksPer100msToRPM (shooterWheelTalon .getSelectedSensorVelocity (0 )));
161
- SmartDashboard .putNumber ("Shooter Wheel Voltage" , shooterWheelTalon .getMotorOutputVoltage ());
174
+ m_targetSpeedRPM - convertTicksPer100msToRPM (shooterWheelLeft .getSelectedSensorVelocity (0 )));
175
+ SmartDashboard .putNumber ("Shooter Wheel Voltage" , shooterWheelLeft .getMotorOutputVoltage ());
176
+ SmartDashboard .putNumber ("Shooter Wheel Bus Voltage" , shooterWheelLeft .getBusVoltage ());
177
+ SmartDashboard .putNumber ("Shooter Wheel Current" , shooterWheelLeft .getSupplyCurrent ());
178
+
179
+ SmartDashboard .putNumber ("Shooter Wheel R-pos" , shooterWheelRight .getSelectedSensorPosition (0 ));
180
+ SmartDashboard .putNumber ("Shooter Wheel R-speed" , shooterWheelRight .getSelectedSensorVelocity (0 ));
181
+ SmartDashboard .putNumber ("Shooter Wheel R-RPM" ,
182
+ convertTicksPer100msToRPM (shooterWheelRight .getSelectedSensorVelocity (0 )));
183
+
184
+ SmartDashboard .putNumber ("Shooter Wheel R-target RPM" , m_targetSpeedRPM );
185
+ SmartDashboard .putNumber ("Shooter Wheel R-Error" ,
186
+ m_targetSpeedRPM - convertTicksPer100msToRPM (shooterWheelRight .getSelectedSensorVelocity (0 )));
187
+ SmartDashboard .putNumber ("Shooter Wheel R-Voltage" , shooterWheelRight .getMotorOutputVoltage ());
188
+ SmartDashboard .putNumber ("Shooter Wheel R-Bus Voltage" , shooterWheelRight .getBusVoltage ());
189
+ SmartDashboard .putNumber ("Shooter Wheel R-Current" , shooterWheelRight .getSupplyCurrent ());
162
190
163
191
SmartDashboard .putNumber ("Shooter turret pos" , turretTalon .getPosition ());
164
192
SmartDashboard .putNumber ("Shooter turret vbus" , turretTalon .getMotorOutputVoltage ());
@@ -235,67 +263,67 @@ public void setFeederSpeed(double pos) {
235
263
public void setShooterWheelSpeed (double rpm ) {
236
264
double ticks = convertRpmToTicksPer100ms (rpm );
237
265
m_targetSpeedRPM = rpm ;
238
- shooterWheelTalon .set (ControlMode .Velocity , ticks );
266
+ shooterWheelLeft .set (ControlMode .Velocity , ticks );
239
267
}
240
268
241
269
public void setShooterWheelSpeedVBus (double pos ) {
242
- shooterWheelTalon .set (ControlMode .PercentOutput , pos );
270
+ shooterWheelLeft .set (ControlMode .PercentOutput , pos );
243
271
}
244
272
245
273
public double getShooterWheelSpeed () {
246
- return convertTicksPer100msToRPM (shooterWheelTalon .getSelectedSensorVelocity (0 ));
274
+ return convertTicksPer100msToRPM (shooterWheelLeft .getSelectedSensorVelocity (0 ));
247
275
}
248
276
249
277
public double getShooterWheelTargetSpeed () {
250
278
return m_targetSpeedRPM ;
251
279
}
252
280
253
281
public double getShooterWheelSpeedVBus () {
254
- return shooterWheelTalon .getMotorOutputVoltage ();
282
+ return shooterWheelLeft .getMotorOutputVoltage ();
255
283
}
256
284
257
285
////////////////////////////////////////////////////
258
286
// PidTunerObject
259
287
@ Override
260
288
public double getP () {
261
- return turretTalon .getP ();
289
+ return shooterWheelLeft .getP ();
262
290
}
263
291
264
292
@ Override
265
293
public double getI () {
266
- return turretTalon .getI ();
294
+ return shooterWheelLeft .getI ();
267
295
}
268
296
269
297
@ Override
270
298
public double getD () {
271
- return turretTalon .getD ();
299
+ return shooterWheelLeft .getD ();
272
300
}
273
301
274
302
@ Override
275
303
public double getF () {
276
- return turretTalon .getF ();
304
+ return shooterWheelLeft .getF ();
277
305
278
306
}
279
307
280
308
@ Override
281
309
public void setP (double d ) {
282
- turretTalon .config_kP (0 , d , 0 );
310
+ shooterWheelLeft .config_kP (0 , d , 0 );
283
311
}
284
312
285
313
@ Override
286
314
public void setI (double d ) {
287
- turretTalon .config_kI (0 , d , 0 );
315
+ shooterWheelLeft .config_kI (0 , d , 0 );
288
316
}
289
317
290
318
@ Override
291
319
public void setD (double d ) {
292
- turretTalon .config_kD (0 , d , 0 );
320
+ shooterWheelLeft .config_kD (0 , d , 0 );
293
321
294
322
}
295
323
296
324
@ Override
297
325
public void setF (double d ) {
298
- turretTalon .config_kF (0 , d , 0 );
326
+ shooterWheelLeft .config_kF (0 , d , 0 );
299
327
}
300
328
301
329
}
0 commit comments