@@ -208,6 +208,13 @@ public void update(double timestamp, SystemMode mode) {
208
208
}
209
209
210
210
if (mode == SystemMode .OPERATOR_CONTROLLED ) {
211
+ // Do hood control
212
+ if (operatorController .getY (Hand .kLeft ) >= 0.5 ) {
213
+ retractHood ();
214
+ } else {
215
+ extendHood ();
216
+ }
217
+
211
218
if (driverController .getTriggerAxis (Hand .kLeft ) >= 0.5 ) {
212
219
// Driver wants the robot to align with vision target and flywheel to get up to
213
220
// speed
@@ -234,9 +241,6 @@ public void update(double timestamp, SystemMode mode) {
234
241
driveSystem .setVisionTracking (false );
235
242
}
236
243
237
- // Extend hood
238
- extendHood ();
239
-
240
244
// Set flywheel speed
241
245
double targetHeight = limelight .getVertical ();
242
246
// double rpm = limelight.hasTarget() ? ShooterUtil.calculateRPM(targetHeight) :
@@ -259,9 +263,6 @@ public void update(double timestamp, SystemMode mode) {
259
263
260
264
wasTracking = false ;
261
265
262
- // Extend hood to mid position
263
- extendHoodMid ();
264
-
265
266
// Set flywheel speed
266
267
set (SHORT_SHOT_RPM );
267
268
@@ -281,9 +282,6 @@ public void update(double timestamp, SystemMode mode) {
281
282
// Stop feeding power cells
282
283
magazineSystem .stopFeedingPowerCells ();
283
284
284
- // Retract hood
285
- retractHood ();
286
-
287
285
// Disable flywheel
288
286
stop ();
289
287
}
@@ -349,7 +347,7 @@ public void update(double timestamp, SystemMode mode) {
349
347
break ;
350
348
case NONE :
351
349
if (hoodPosition == HoodPosition .DOWN ) {
352
- hoodMotor .set (0.02 );
350
+ hoodMotor .set (0.05 );
353
351
} else {
354
352
hoodMotor .set (0 );
355
353
}
@@ -375,10 +373,9 @@ public ShooterSystem(AluminatiMotorGroup motorGroup, AluminatiSpark hoodMotor,
375
373
376
374
this .robotFaults = robotFaults ;
377
375
378
- this .hoodPosition = HoodPosition .UNKNOWN ;
376
+ this .hoodPosition = HoodPosition .UP ;
379
377
this .hoodAction = HoodAction .NONE ;
380
378
this .hoodActionList = new ArrayList <HoodAction >();
381
- this .hoodActionList .add (HoodAction .RETRACT );
382
379
383
380
this .wasTracking = false ;
384
381
@@ -414,7 +411,7 @@ protected void update(TuningData data) {
414
411
this .motorGroup .getMasterTalon ().configContinuousCurrentLimit (SHOOTER_CURRENT_LIMIT );
415
412
this .motorGroup .getMasterTalon ().enableCurrentLimit (true );
416
413
417
- this .turnController = new AluminatiTuneablePIDController (5808 , 0.2 , 0 , 0 , 400 , 1 , 1 , 0 );
414
+ this .turnController = new AluminatiTuneablePIDController (5808 , 0.05 , 0 , 0 , 400 , 1 , 0.6 , 0 );
418
415
}
419
416
420
417
public enum HoodPosition {
0 commit comments