Skip to content

Commit 41f99ea

Browse files
authored
Merge pull request #58 from Team537/mukwonago2026
Mukwonago2026 merge into dev
2 parents 0473fb5 + fd9f669 commit 41f99ea

File tree

4 files changed

+87
-15
lines changed

4 files changed

+87
-15
lines changed

src/main/java/frc/robot/Constants.java

Lines changed: 24 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ public static class ErrorSettings {
5858
public static final int TURRET_OFFSET_DECIMAL_PLACE = 1;
5959
public static final double HOOD_OFFSET_INCREASE = 0.1;
6060
public static final int HOOD_OFFSET_DECIMAL_PLACE = 1;
61-
public static final double SHOOTER_PERCENT_INCREASE = 0.2; // Percent to increase per tick
61+
public static final double SHOOTER_PERCENT_INCREASE = .5; // Percent to increase per tick
6262
public static final int SHOOTER_PERCENT_DECIMAL_PLACE = 1;
6363

6464
public static final double SHOOTER_PERCENT_DEFAULT = 100.0;
@@ -98,6 +98,19 @@ public static class Auto {
9898
new Pose2d(7.730, 6.457, Rotation2d.fromDegrees(-160))
9999
);
100100

101+
public static final List<Pose2d> BACK_N_FORTH_RIGHT_SEQUENCE = List.of(
102+
new Pose2d(8.500, 2.1, Rotation2d.fromDegrees(-45)),
103+
new Pose2d(8.306, 6.707, Rotation2d.fromDegrees(-45)),
104+
new Pose2d(8.154, 1.349, Rotation2d.fromDegrees(-45))
105+
);
106+
107+
108+
public static final List<Pose2d> BACK_N_FORTH_LEFT_SEQUENCE = List.of(
109+
new Pose2d(8.500, 6.000, Rotation2d.fromDegrees(-45)),
110+
new Pose2d(8.154, 1.349, Rotation2d.fromDegrees(-45)),
111+
new Pose2d(8.306, 6.707, Rotation2d.fromDegrees(-45))
112+
);
113+
101114
public static final Translation2d NEUTRAL_RIGHT_SPIN_TRANSLATION = new Translation2d(
102115
7.730,
103116
7.457
@@ -120,6 +133,16 @@ public static class Auto {
120133
new Pose2d(7.829,4.051,Rotation2d.kCW_90deg)
121134
);
122135

136+
public static final List<Pose2d> RAM_SS_LEFT_SEQUENCE = List.of(
137+
new Pose2d(7.797,5.902,Rotation2d.kCW_90deg),
138+
new Pose2d(7.829,4.400,Rotation2d.kCW_90deg)
139+
);
140+
141+
public static final List<Pose2d> RAM_SS_RIGHT_SEQUENCE = List.of(
142+
new Pose2d(7.797,2.168,Rotation2d.kCW_90deg),
143+
new Pose2d(7.829,3.650,Rotation2d.kCW_90deg)
144+
);
145+
123146

124147
}
125148

src/main/java/frc/robot/RobotContainer.java

Lines changed: 44 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -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
}

src/main/java/frc/robot/commands/ShootPreloadCommand.java

Lines changed: 15 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,10 @@
55
import edu.wpi.first.math.geometry.Pose2d;
66
import edu.wpi.first.math.geometry.Translation3d;
77
import edu.wpi.first.math.kinematics.ChassisSpeeds;
8-
import edu.wpi.first.wpilibj2.command.Command;
98
import edu.wpi.first.wpilibj2.command.Commands;
9+
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
1010
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
11-
import frc.robot.Constants;
11+
import edu.wpi.first.wpilibj2.command.WaitCommand;
1212
import frc.robot.subsystems.IntakePivotSubsystem;
1313
import frc.robot.subsystems.IntakeRollerSubsystem;
1414
import frc.robot.subsystems.ShooterSubsystem;
@@ -32,12 +32,19 @@ public ShootPreloadCommand(
3232
addCommands(
3333

3434
Commands.deadline(
35-
Commands.waitSeconds(shootPreloadTime),
36-
turret.getTargetCommand(targetSupplier, robotPoseSupplier, robotVelocitySupplier),
37-
shooter.getTargetCommand(targetSupplier, robotPoseSupplier, robotVelocitySupplier),
38-
transfer.getLoadCommand(),
39-
intakePivot.deployIntakeCommand(),
40-
intakeRoller.getIntakeCommand()
35+
Commands.waitSeconds(shootPreloadTime + 2),
36+
Commands.parallel(
37+
new ParallelCommandGroup(
38+
turret.getTargetCommand(targetSupplier, robotPoseSupplier, robotVelocitySupplier),
39+
shooter.getTargetCommand(targetSupplier, robotPoseSupplier, robotVelocitySupplier),
40+
intakeRoller.getIntakeCommand(),
41+
intakePivot.deployIntakeCommand()
42+
),
43+
Commands.sequence(
44+
new WaitCommand(2),
45+
transfer.getLoadCommand()
46+
)
47+
)
4148
),
4249

4350
Commands.parallel(

src/main/java/frc/robot/util/auto/IntakeStrategy.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,10 @@ public enum IntakeStrategy {
99
RAM_LEFT,
1010
RAM_RIGHT,
1111
JUST_SHOOT,
12+
B_N_F_L,
13+
B_N_F_R,
14+
RAM_SS_L,
15+
RAM_SS_R,
1216
CUSTOM
1317

1418
}

0 commit comments

Comments
 (0)