@@ -284,7 +284,7 @@ public void configureBindings() {
284284 Trigger reverseTransferTrigger = new Trigger (() -> driverController .getXButton ());
285285
286286 // Driver X button: hold to lock robot pose (X-lock)
287- Trigger xLockTrigger = new Trigger (() -> operatorController .getXButton ());
287+ Trigger xLockTrigger = new Trigger (() -> driverController .getXButton ());
288288 xLockTrigger .whileTrue (driveSubsystem .getLockPoseCommand ());
289289
290290 /* Shooter runs while button held */
@@ -322,7 +322,7 @@ public void configureBindings() {
322322 intakeRoller .getStopCommand ()));
323323
324324 reverseTransferTrigger .whileTrue (
325- transferSubsystem .getSetPowerCommand (-1 )).onFalse (transferSubsystem .getSetPowerCommand (0 ));
325+ transferSubsystem .getSetPowerCommand (-1 )).onFalse (transferSubsystem .getSetPowerCommand (0 ));
326326
327327 // =========================
328328 // Turret Offset Adjustment (POV Left / Right)
@@ -388,6 +388,26 @@ public void configureBindings() {
388388 shooterPercent .getHeldIntervalCommand (Constants .Operator .ErrorSettings .SHOOTER_PERCENT_INCREASE ,
389389 Constants .Operator .ErrorSettings .SETTINGS_DELAY_TIME ));
390390
391+ // ==============================
392+ // Turret / Hood Offset Reset (Left Stick Click / Right Stick Click)
393+ // ==============================
394+
395+ // Left Stick Click : Reset turret offset to zero
396+ new Trigger (() -> operatorController .getLeftStickButton ())
397+ .onTrue (new InstantCommand (() -> turretOffsetDegrees .set (0.0 )));
398+
399+ // Right Stick Click : Reset hood offset to zero
400+ new Trigger (() -> operatorController .getRightStickButton ())
401+ .onTrue (new InstantCommand (() -> hoodOffsetDegrees .set (0.0 )));
402+
403+ // ==============================
404+ // Shooter Percent Reset (Left Trigger / Right Trigger)
405+ // ==============================
406+
407+ // Either Trigger : Reset shooter percent to default
408+ new Trigger (() -> operatorController .getLeftTriggerAxis () > 0.5
409+ || operatorController .getRightTriggerAxis () > 0.5 )
410+ .onTrue (new InstantCommand (() -> shooterPercent .set (Constants .Operator .ErrorSettings .SHOOTER_PERCENT_DEFAULT )));
391411 new Trigger (
392412 () -> operatorController .getAButton ()).onTrue (
393413 new InstantCommand (() -> selectedFixedTarget = FixedTarget .A ));
@@ -587,8 +607,8 @@ private Command getIntakeStrategyCommand() {
587607 turretSubsystem ,
588608 transferSubsystem ,
589609 () -> FieldUtil .flipIfRed (Constants .Field .BLUE_HUB_TRANSLATION ),
590- Constants .Operator .Auto .DEPOT_READY_INTAKE_POSE ,
591- Constants .Operator .Auto .DEPOT_INTAKE_POSE ,
610+ FieldUtil . flipIfRed ( Constants .Operator .Auto .DEPOT_READY_INTAKE_POSE ) ,
611+ FieldUtil . flipIfRed ( Constants .Operator .Auto .DEPOT_INTAKE_POSE ) ,
592612 false ,
593613 Constants .Operator .Auto .AUTO_INTAKE_MAX_SPEED ,
594614 SmartDashboard .getNumber ("Auto/IntakeShootTime" , Constants .Operator .Auto .DEFAULT_INTAKE_SHOOT_TIME ));
@@ -602,8 +622,8 @@ private Command getIntakeStrategyCommand() {
602622 turretSubsystem ,
603623 transferSubsystem ,
604624 () -> FieldUtil .flipIfRed (Constants .Field .BLUE_HUB_TRANSLATION ),
605- Constants .Operator .Auto .OUTPOST_READY_INTAKE_POSE ,
606- Constants .Operator .Auto .OUTPOST_INTAKE_POSE ,
625+ FieldUtil . flipIfRed ( Constants .Operator .Auto .OUTPOST_READY_INTAKE_POSE ) ,
626+ FieldUtil . flipIfRed ( Constants .Operator .Auto .OUTPOST_INTAKE_POSE ) ,
607627 false ,
608628 Constants .Operator .Auto .AUTO_INTAKE_MAX_SPEED ,
609629 SmartDashboard .getNumber ("Auto/IntakeShootTime" , Constants .Operator .Auto .DEFAULT_INTAKE_SHOOT_TIME ));
@@ -662,6 +682,16 @@ private Command getIntakeStrategyCommand() {
662682 .map (FieldUtil ::flipIfRed )
663683 .toList ());
664684
685+ case RAM_SS_L :
686+ return new DriveToSequenceCommand (driveSubsystem , Constants .Operator .Auto .RAM_SS_LEFT_SEQUENCE .stream ()
687+ .map (FieldUtil ::flipIfRed )
688+ .toList ());
689+
690+ case RAM_SS_R :
691+ return new DriveToSequenceCommand (driveSubsystem , Constants .Operator .Auto .RAM_SS_RIGHT_SEQUENCE .stream ()
692+ .map (FieldUtil ::flipIfRed )
693+ .toList ());
694+
665695 case CUSTOM :
666696
667697 Pose2d ready = getDashboardPose ("Auto/CustomReadyPose" );
@@ -684,6 +714,14 @@ private Command getIntakeStrategyCommand() {
684714 Constants .Operator .Auto .AUTO_INTAKE_MAX_SPEED ,
685715 SmartDashboard .getNumber ("Auto/IntakeShootTime" , Constants .Operator .Auto .DEFAULT_INTAKE_SHOOT_TIME ));
686716
717+ case B_N_F_R :
718+ return new DriveToSequenceCommand (driveSubsystem , Constants .Operator .Auto .BACK_N_FORTH_RIGHT_SEQUENCE .stream ()
719+ .map (FieldUtil ::flipIfRed )
720+ .toList ());
721+ case B_N_F_L :
722+ return new DriveToSequenceCommand (driveSubsystem , Constants .Operator .Auto .BACK_N_FORTH_LEFT_SEQUENCE .stream ()
723+ .map (FieldUtil ::flipIfRed )
724+ .toList ());
687725 default :
688726 return Commands .none ();
689727 }
0 commit comments