From be946a46dfb3e02cb1220340c24ac8e80b1da355 Mon Sep 17 00:00:00 2001 From: Ava Edwards Date: Sat, 26 Jul 2025 15:13:20 +0800 Subject: [PATCH 1/4] added ContextfulXboxController.java and implemented in Robot.java. Probably need to implement some more things from CommandGenericHID.class but everything used in Robot.java is implemented. --- .../java/org/curtinfrc/frc2025/Robot.java | 72 +++++++--- .../util/ContextfulXboxController.java | 130 ++++++++++++++++++ 2 files changed, 181 insertions(+), 21 deletions(-) create mode 100644 src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java diff --git a/src/main/java/org/curtinfrc/frc2025/Robot.java b/src/main/java/org/curtinfrc/frc2025/Robot.java index ab597e9c..c20980a9 100644 --- a/src/main/java/org/curtinfrc/frc2025/Robot.java +++ b/src/main/java/org/curtinfrc/frc2025/Robot.java @@ -72,6 +72,7 @@ import org.littletonrobotics.junction.wpilog.WPILOGReader; import org.littletonrobotics.junction.wpilog.WPILOGWriter; import org.littletonrobotics.urcl.URCL; +import org.curtinfrc.frc2025.util.ContextfulXboxController; /** * The VM is configured to automatically run this class, and to call the functions corresponding to @@ -89,8 +90,15 @@ public class Robot extends LoggedRobot { private Ejector ejector; private Climber climber; + @AutoLogOutput(key = "Robot/Overridden") + private boolean overridden = false; + + @AutoLogOutput(key = "Robot/Overide") + private final Trigger override = new Trigger(() -> overridden); + // Controller - private final CommandXboxController controller = new CommandXboxController(0); + private final ContextfulXboxController controller = new ContextfulXboxController(0, override.negate()); + private final ContextfulXboxController manualController = new ContextfulXboxController(0, override); private final Alert controllerDisconnected = new Alert("Driver controller disconnected!", AlertType.kError); private final ButtonBoard board = new ButtonBoard(1); @@ -104,11 +112,6 @@ public class Robot extends LoggedRobot { private final List rightSetpoints; private final List algaeSetpoints; - @AutoLogOutput(key = "Robot/Overridden") - private boolean overridden = false; - - @AutoLogOutput(key = "Robot/Overide") - private final Trigger override = new Trigger(() -> overridden); public Robot() { // Record metadata @@ -352,7 +355,6 @@ public Robot() { controller .rightBumper() .or(controller.leftBumper()) - .and(override.negate()) .whileTrue( elevator .goToSetpoint(ElevatorSetpoints.L2, intake.backSensor.negate()) @@ -360,8 +362,7 @@ public Robot() { controller .rightTrigger() .or(controller.leftTrigger()) - .and(override.negate()) - .whileTrue( + .whileTrue( elevator .goToSetpoint(ElevatorSetpoints.L3, intake.backSensor.negate()) .until(ejector.backSensor.negate())); @@ -369,7 +370,6 @@ public Robot() { controller .rightBumper() .or(controller.rightTrigger()) - .and(override.negate()) .whileTrue( drive .autoAlignWithOverride( @@ -379,30 +379,25 @@ public Robot() { () -> -controller.getRightX()) .until(ejector.backSensor.negate())); - controller.leftBumper().or(controller.leftTrigger()).and(override).whileTrue(ejector.eject(30)); - controller + manualController.leftBumper().or(controller.leftTrigger()).whileTrue(ejector.eject(30)); + manualController .leftBumper() - .and(override) .whileTrue( elevator.goToSetpoint(ElevatorSetpoints.AlgaePopLow, intake.backSensor.negate())); - controller + manualController .leftTrigger() - .and(override) .whileTrue( elevator.goToSetpoint(ElevatorSetpoints.AlgaePopHigh, intake.backSensor.negate())); - controller + manualController .rightBumper() - .and(override) .whileTrue(elevator.goToSetpoint(ElevatorSetpoints.L2, intake.backSensor.negate())); - controller + manualController .rightTrigger() - .and(override) .whileTrue(elevator.goToSetpoint(ElevatorSetpoints.L3, intake.backSensor.negate())); controller .leftBumper() .or(controller.leftTrigger()) - .and(override.negate()) .whileTrue( drive .autoAlignWithOverride( @@ -447,7 +442,6 @@ public Robot() { controller .leftStick() - .and(override.negate()) .whileTrue( Commands.parallel( drive.autoAlignWithOverride( @@ -474,7 +468,13 @@ public Robot() { controller .rightStick() .whileTrue(ejector.eject(15).withInterruptBehavior(InterruptionBehavior.kCancelIncoming)); + + manualController + .rightStick() + .whileTrue(ejector.eject(15).withInterruptBehavior(InterruptionBehavior.kCancelIncoming)); + controller.povUp().whileTrue(intake.intake(-4)); + manualController.povUp().whileTrue(intake.intake(-4)); intake .backSensor @@ -518,6 +518,15 @@ public Robot() { new Pose2d(drive.getPose().getTranslation(), Rotation2d.kZero)), drive) .ignoringDisable(true)); + manualController + .y() + .onTrue( + Commands.runOnce( + () -> + drive.setPose( + new Pose2d(drive.getPose().getTranslation(), Rotation2d.kZero)), + drive) + .ignoringDisable(true)); controller .x() .onTrue( @@ -525,6 +534,13 @@ public Robot() { climber.disengage(), climber.goToSetpoint(ClimberConstants.targetPositionRotationsIn), elevator.goToSetpoint(ElevatorSetpoints.climbPrep, intake.backSensor.negate()))); + manualController + .x() + .onTrue( + Commands.sequence( + climber.disengage(), + climber.goToSetpoint(ClimberConstants.targetPositionRotationsIn), + elevator.goToSetpoint(ElevatorSetpoints.climbPrep, intake.backSensor.negate()))); controller // climb attempt .a() @@ -539,8 +555,22 @@ public Robot() { new ScheduleCommand( elevator.goToSetpoint( ElevatorSetpoints.climbPrep, intake.backSensor.negate())))); + manualController // climb attempt + .a() + .and(() -> climber.climberDeployed) + .onTrue( + elevator + .goToSetpoint(ElevatorSetpoints.climbAttempt, intake.backSensor.negate()) + .until(elevator.atSetpoint) + .andThen(climber.goToSetpoint(ClimberConstants.targetPositionRotationsOut)) + .andThen(climber.goToSetpoint(ClimberConstants.targetPositionRotationsIn)) + .andThen( + new ScheduleCommand( + elevator.goToSetpoint( + ElevatorSetpoints.climbPrep, intake.backSensor.negate())))); controller.b().onTrue(Commands.runOnce(() -> overridden = !overridden)); + manualController.b().onTrue(Commands.runOnce(() -> overridden = !overridden)); new Trigger(this::isEnabled).onTrue(climber.disengage()); } diff --git a/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java b/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java new file mode 100644 index 00000000..23aa2b6e --- /dev/null +++ b/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java @@ -0,0 +1,130 @@ +package org.curtinfrc.frc2025.util; + +import java.util.function.BooleanSupplier; + +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import edu.wpi.first.wpilibj2.command.button.Trigger; +import edu.wpi.first.wpilibj.GenericHID.RumbleType; + +public class ContextfulXboxController { + private final CommandXboxController xboxController; + private final BooleanSupplier context; + + + public ContextfulXboxController(int port, BooleanSupplier context) { + xboxController = new CommandXboxController(port); + this.context = context; + } + + public Trigger a() { + return xboxController.a().and(context); + } + + public Trigger b() { + return xboxController.b().and(context); + } + + public Trigger x() { + return xboxController.x().and(context); + } + + public Trigger y() { + return xboxController.y().and(context); + } + + public Trigger leftBumper() { + return xboxController.leftBumper().and(context); + } + + public Trigger rightBumper() { + return xboxController.rightBumper().and(context); + } + + public Trigger back() { + return xboxController.back().and(context); + } + + public Trigger start() { + return xboxController.start().and(context); + } + + public Trigger leftStick() { + return xboxController.leftStick().and(context); + } + + public Trigger rightStick() { + return xboxController.rightStick().and(context); + } + + public Trigger leftTrigger() { + return xboxController.leftTrigger().and(context); + } + + public Trigger rightTrigger() { + return xboxController.rightTrigger().and(context); + } + + public double getLeftX() { + return xboxController.getLeftX(); + } + + public double getRightX() { + return xboxController.getRightX(); + } + + public double getLeftY() { + return xboxController.getLeftY(); + } + + public double getRightY() { + return xboxController.getRightY(); + } + + public double getLeftTriggerAxis() { + return xboxController.getLeftTriggerAxis(); + } + + public double getRightTriggerAxis() { + return xboxController.getRightTriggerAxis(); + } + + public void setRumble(RumbleType type, double value) { + xboxController.setRumble(type, value); + } + + public Trigger povUp() { + return xboxController.povUp(); + } + + public Trigger povUpRight() { + return xboxController.povUpRight(); + } + + public Trigger povRight() { + return xboxController.povRight(); + } + + public Trigger povDownRight() { + return xboxController.povDownRight(); + } + + public Trigger povDown() { + return xboxController.povDown(); + } + + public Trigger povDownLeft() { + return xboxController.povDownLeft(); + } + + public Trigger povLeft() { + return xboxController.povLeft(); + } + + public Trigger povUpLeft() { + return xboxController.povUpLeft(); + } + + public boolean isConnected() { + return xboxController.isConnected(); + } +} \ No newline at end of file From c000df3abc9e9ea68dc1c9b5dc2189d57a9e96f5 Mon Sep 17 00:00:00 2001 From: Ava Edwards Date: Mon, 28 Jul 2025 17:00:02 +0800 Subject: [PATCH 2/4] finished adding features from generic hid file --- .../java/org/curtinfrc/frc2025/Constants.java | 2 +- .../java/org/curtinfrc/frc2025/Robot.java | 28 ++-- .../util/ContextfulXboxController.java | 121 ++++++++++++------ 3 files changed, 100 insertions(+), 51 deletions(-) diff --git a/src/main/java/org/curtinfrc/frc2025/Constants.java b/src/main/java/org/curtinfrc/frc2025/Constants.java index af9c4579..36862caf 100644 --- a/src/main/java/org/curtinfrc/frc2025/Constants.java +++ b/src/main/java/org/curtinfrc/frc2025/Constants.java @@ -15,7 +15,7 @@ * (log replay from a file). */ public final class Constants { - public static final RobotType robotType = RobotType.COMPBOT; + public static final RobotType robotType = RobotType.SIMBOT; public static final double ROBOT_X = 0.705; public static final double ROBOT_Y = 0.730; public static final double FIELD_LENGTH = aprilTagLayout.getFieldLength(); diff --git a/src/main/java/org/curtinfrc/frc2025/Robot.java b/src/main/java/org/curtinfrc/frc2025/Robot.java index c20980a9..1fbcc455 100644 --- a/src/main/java/org/curtinfrc/frc2025/Robot.java +++ b/src/main/java/org/curtinfrc/frc2025/Robot.java @@ -18,7 +18,6 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.ScheduleCommand; -import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.RobotModeTriggers; import edu.wpi.first.wpilibj2.command.button.Trigger; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; @@ -62,6 +61,7 @@ import org.curtinfrc.frc2025.subsystems.vision.VisionIOPhotonVisionSim; import org.curtinfrc.frc2025.util.AutoChooser; import org.curtinfrc.frc2025.util.ButtonBoard; +import org.curtinfrc.frc2025.util.ContextfulXboxController; import org.curtinfrc.frc2025.util.PhoenixUtil; import org.curtinfrc.frc2025.util.VirtualSubsystem; import org.littletonrobotics.junction.AutoLogOutput; @@ -72,7 +72,6 @@ import org.littletonrobotics.junction.wpilog.WPILOGReader; import org.littletonrobotics.junction.wpilog.WPILOGWriter; import org.littletonrobotics.urcl.URCL; -import org.curtinfrc.frc2025.util.ContextfulXboxController; /** * The VM is configured to automatically run this class, and to call the functions corresponding to @@ -97,8 +96,10 @@ public class Robot extends LoggedRobot { private final Trigger override = new Trigger(() -> overridden); // Controller - private final ContextfulXboxController controller = new ContextfulXboxController(0, override.negate()); - private final ContextfulXboxController manualController = new ContextfulXboxController(0, override); + private final ContextfulXboxController controller = + new ContextfulXboxController(0, override.negate()); + private final ContextfulXboxController manualController = + new ContextfulXboxController(0, override); private final Alert controllerDisconnected = new Alert("Driver controller disconnected!", AlertType.kError); private final ButtonBoard board = new ButtonBoard(1); @@ -112,7 +113,6 @@ public class Robot extends LoggedRobot { private final List rightSetpoints; private final List algaeSetpoints; - public Robot() { // Record metadata Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME); @@ -362,7 +362,7 @@ public Robot() { controller .rightTrigger() .or(controller.leftTrigger()) - .whileTrue( + .whileTrue( elevator .goToSetpoint(ElevatorSetpoints.L3, intake.backSensor.negate()) .until(ejector.backSensor.negate())); @@ -519,14 +519,14 @@ public Robot() { drive) .ignoringDisable(true)); manualController - .y() - .onTrue( - Commands.runOnce( - () -> - drive.setPose( - new Pose2d(drive.getPose().getTranslation(), Rotation2d.kZero)), - drive) - .ignoringDisable(true)); + .y() + .onTrue( + Commands.runOnce( + () -> + drive.setPose( + new Pose2d(drive.getPose().getTranslation(), Rotation2d.kZero)), + drive) + .ignoringDisable(true)); controller .x() .onTrue( diff --git a/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java b/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java index 23aa2b6e..82f45f22 100644 --- a/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java +++ b/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java @@ -1,21 +1,26 @@ package org.curtinfrc.frc2025.util; -import java.util.function.BooleanSupplier; - +import edu.wpi.first.wpilibj.GenericHID.RumbleType; +import edu.wpi.first.wpilibj.event.EventLoop; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.Trigger; -import edu.wpi.first.wpilibj.GenericHID.RumbleType; +import java.util.function.BooleanSupplier; public class ContextfulXboxController { private final CommandXboxController xboxController; private final BooleanSupplier context; - public ContextfulXboxController(int port, BooleanSupplier context) { xboxController = new CommandXboxController(port); this.context = context; } + /* All the Triggers as well as setRumble check for the context as they should + * activate based on the controller state. None of the methods that return a + * (non-trigger) value don't check the context as they return values from the + * physical controller which isn't dependent on the context. + */ + public Trigger a() { return xboxController.a().and(context); } @@ -64,67 +69,111 @@ public Trigger rightTrigger() { return xboxController.rightTrigger().and(context); } - public double getLeftX() { - return xboxController.getLeftX(); + public Trigger povUp() { + return xboxController.povUp().and(context); } - public double getRightX() { - return xboxController.getRightX(); + public Trigger povUpRight() { + return xboxController.povUpRight().and(context); } - public double getLeftY() { - return xboxController.getLeftY(); + public Trigger povRight() { + return xboxController.povRight().and(context); } - public double getRightY() { - return xboxController.getRightY(); + public Trigger povDownRight() { + return xboxController.povDownRight().and(context); } - public double getLeftTriggerAxis() { - return xboxController.getLeftTriggerAxis(); + public Trigger povDown() { + return xboxController.povDown().and(context); } - public double getRightTriggerAxis() { - return xboxController.getRightTriggerAxis(); + public Trigger povDownLeft() { + return xboxController.povDownLeft().and(context); } - public void setRumble(RumbleType type, double value) { - xboxController.setRumble(type, value); + public Trigger povLeft() { + return xboxController.povLeft().and(context); } - public Trigger povUp() { - return xboxController.povUp(); + public Trigger povUpLeft() { + return xboxController.povUpLeft().and(context); } - public Trigger povUpRight() { - return xboxController.povUpRight(); + public Trigger pov(int angle) { + return xboxController.pov(angle).and(context); } - public Trigger povRight() { - return xboxController.povRight(); + public Trigger pov(int pov, int angle, EventLoop loop) { + return xboxController.pov(pov, angle, loop).and(context); } - public Trigger povDownRight() { - return xboxController.povDownRight(); - } + public Trigger povCentre() { + return xboxController.povCenter().and(context); + } - public Trigger povDown() { - return xboxController.povDown(); + public Trigger povCenter() { + return xboxController.povCenter().and(context); } - public Trigger povDownLeft() { - return xboxController.povDownLeft(); + public Trigger axisLessThan(int axis, double threshold) { + return xboxController.axisLessThan(axis, threshold).and(context); } - public Trigger povLeft() { - return xboxController.povLeft(); + public Trigger axisLessThan(int axis, double threshold, EventLoop loop) { + return xboxController.axisLessThan(axis, threshold, loop).and(context); } - public Trigger povUpLeft() { - return xboxController.povUpLeft(); + public Trigger axisGreaterThan(int axis, double threshold) { + return xboxController.axisGreaterThan(axis, threshold).and(context); + } + + public Trigger axisGreaterThan(int axis, double threshold, EventLoop loop) { + return xboxController.axisGreaterThan(axis, threshold, loop).and(context); + } + + public Trigger axisMagnitudeGreaterThan(int axis, double threshold) { + return xboxController.axisMagnitudeGreaterThan(axis, threshold).and(context); + } + + public Trigger axisMagnitudeGreaterThan(int axis, double threshold, EventLoop loop) { + return xboxController.axisMagnitudeGreaterThan(axis, threshold, loop).and(context); + } + + public void setRumble(RumbleType type, double value) { + xboxController.setRumble(type, value); + } + + public double getLeftX() { + return xboxController.getLeftX(); + } + + public double getRightX() { + return xboxController.getRightX(); + } + + public double getLeftY() { + return xboxController.getLeftY(); + } + + public double getRightY() { + return xboxController.getRightY(); + } + + public double getLeftTriggerAxis() { + return xboxController.getLeftTriggerAxis(); + } + + public double getRightTriggerAxis() { + return xboxController.getRightTriggerAxis(); } public boolean isConnected() { return xboxController.isConnected(); } -} \ No newline at end of file + + public double getRawAxis(int axis) { + return xboxController.getRawAxis(axis); + } +} From 9ad77b533fa029eca840fde73fef0d1752da654a Mon Sep 17 00:00:00 2001 From: Ava Edwards Date: Mon, 28 Jul 2025 22:06:04 +0800 Subject: [PATCH 3/4] moved comment in ContextfulXboxController.java to be a class comment and corrected it. Also added raw versions of triggers and added to Robot.java to replace double ups of controller and manualController. --- .../java/org/curtinfrc/frc2025/Robot.java | 47 +------ .../util/ContextfulXboxController.java | 124 ++++++++++++++++-- 2 files changed, 122 insertions(+), 49 deletions(-) diff --git a/src/main/java/org/curtinfrc/frc2025/Robot.java b/src/main/java/org/curtinfrc/frc2025/Robot.java index 1fbcc455..5a10b3af 100644 --- a/src/main/java/org/curtinfrc/frc2025/Robot.java +++ b/src/main/java/org/curtinfrc/frc2025/Robot.java @@ -466,15 +466,10 @@ public Robot() { .withName("AlgaePop") .withInterruptBehavior(InterruptionBehavior.kCancelIncoming)); controller - .rightStick() + .rightStickRaw() .whileTrue(ejector.eject(15).withInterruptBehavior(InterruptionBehavior.kCancelIncoming)); - manualController - .rightStick() - .whileTrue(ejector.eject(15).withInterruptBehavior(InterruptionBehavior.kCancelIncoming)); - - controller.povUp().whileTrue(intake.intake(-4)); - manualController.povUp().whileTrue(intake.intake(-4)); + controller.povUpRaw().whileTrue(intake.intake(-4)); intake .backSensor @@ -510,16 +505,7 @@ public Robot() { // Reset gyro to 0° when B button is pressed controller - .y() - .onTrue( - Commands.runOnce( - () -> - drive.setPose( - new Pose2d(drive.getPose().getTranslation(), Rotation2d.kZero)), - drive) - .ignoringDisable(true)); - manualController - .y() + .yRaw() .onTrue( Commands.runOnce( () -> @@ -528,14 +514,7 @@ public Robot() { drive) .ignoringDisable(true)); controller - .x() - .onTrue( - Commands.sequence( - climber.disengage(), - climber.goToSetpoint(ClimberConstants.targetPositionRotationsIn), - elevator.goToSetpoint(ElevatorSetpoints.climbPrep, intake.backSensor.negate()))); - manualController - .x() + .xRaw() .onTrue( Commands.sequence( climber.disengage(), @@ -543,20 +522,7 @@ public Robot() { elevator.goToSetpoint(ElevatorSetpoints.climbPrep, intake.backSensor.negate()))); controller // climb attempt - .a() - .and(() -> climber.climberDeployed) - .onTrue( - elevator - .goToSetpoint(ElevatorSetpoints.climbAttempt, intake.backSensor.negate()) - .until(elevator.atSetpoint) - .andThen(climber.goToSetpoint(ClimberConstants.targetPositionRotationsOut)) - .andThen(climber.goToSetpoint(ClimberConstants.targetPositionRotationsIn)) - .andThen( - new ScheduleCommand( - elevator.goToSetpoint( - ElevatorSetpoints.climbPrep, intake.backSensor.negate())))); - manualController // climb attempt - .a() + .aRaw() .and(() -> climber.climberDeployed) .onTrue( elevator @@ -569,8 +535,7 @@ public Robot() { elevator.goToSetpoint( ElevatorSetpoints.climbPrep, intake.backSensor.negate())))); - controller.b().onTrue(Commands.runOnce(() -> overridden = !overridden)); - manualController.b().onTrue(Commands.runOnce(() -> overridden = !overridden)); + controller.bRaw().onTrue(Commands.runOnce(() -> overridden = !overridden)); new Trigger(this::isEnabled).onTrue(climber.disengage()); } diff --git a/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java b/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java index 82f45f22..4c170740 100644 --- a/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java +++ b/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java @@ -6,7 +6,13 @@ import edu.wpi.first.wpilibj2.command.button.Trigger; import java.util.function.BooleanSupplier; +/* All the Triggers check for the context as they should +* activate based on the controller state. None of the methods that return a +* (non-trigger) value don't check the context as they return values from the +* physical controller which isn't dependent on the context. +*/ public class ContextfulXboxController { + private final CommandXboxController xboxController; private final BooleanSupplier context; @@ -15,68 +21,118 @@ public ContextfulXboxController(int port, BooleanSupplier context) { this.context = context; } - /* All the Triggers as well as setRumble check for the context as they should - * activate based on the controller state. None of the methods that return a - * (non-trigger) value don't check the context as they return values from the - * physical controller which isn't dependent on the context. - */ - public Trigger a() { return xboxController.a().and(context); } + public Trigger aRaw() { + return xboxController.a(); + } + public Trigger b() { return xboxController.b().and(context); } + public Trigger bRaw() { + return xboxController.b(); + } + public Trigger x() { return xboxController.x().and(context); } + public Trigger xRaw() { + return xboxController.x(); + } + public Trigger y() { return xboxController.y().and(context); } + public Trigger yRaw() { + return xboxController.y(); + } + public Trigger leftBumper() { return xboxController.leftBumper().and(context); } + public Trigger leftBumperRaw() { + return xboxController.leftBumper(); + } + public Trigger rightBumper() { return xboxController.rightBumper().and(context); } + public Trigger rightBumperRaw() { + return xboxController.rightBumper(); + } + public Trigger back() { return xboxController.back().and(context); } + public Trigger backRaw() { + return xboxController.back(); + } + public Trigger start() { return xboxController.start().and(context); } + public Trigger startRaw() { + return xboxController.start(); + } + public Trigger leftStick() { return xboxController.leftStick().and(context); } + public Trigger leftStickRaw() { + return xboxController.leftStick(); + } + public Trigger rightStick() { return xboxController.rightStick().and(context); } + public Trigger rightStickRaw() { + return xboxController.rightStick(); + } + public Trigger leftTrigger() { return xboxController.leftTrigger().and(context); } + public Trigger leftTriggerRaw() { + return xboxController.leftTrigger(); + } + public Trigger rightTrigger() { return xboxController.rightTrigger().and(context); } + public Trigger rightTriggerRaw() { + return xboxController.rightTrigger(); + } + public Trigger povUp() { return xboxController.povUp().and(context); } + public Trigger povUpRaw() { + return xboxController.povUp(); + } + public Trigger povUpRight() { return xboxController.povUpRight().and(context); } + public Trigger povRightRaw() { + return xboxController.povRight(); + } + public Trigger povRight() { return xboxController.povRight().and(context); } @@ -85,62 +141,114 @@ public Trigger povDownRight() { return xboxController.povDownRight().and(context); } + public Trigger povDownRightRaw() { + return xboxController.povDownRight(); + } + public Trigger povDown() { return xboxController.povDown().and(context); } + public Trigger povDownRaw() { + return xboxController.povDown(); + } + public Trigger povDownLeft() { return xboxController.povDownLeft().and(context); } + public Trigger povDownLeftRaw() { + return xboxController.povDownLeft(); + } + public Trigger povLeft() { return xboxController.povLeft().and(context); } + public Trigger povLeftRaw() { + return xboxController.povLeft(); + } + public Trigger povUpLeft() { return xboxController.povUpLeft().and(context); } + public Trigger povUpLeftRaw() { + return xboxController.povUpLeft(); + } + public Trigger pov(int angle) { return xboxController.pov(angle).and(context); } + + public Trigger povRaw(int angle) { + return xboxController.pov(angle); + } public Trigger pov(int pov, int angle, EventLoop loop) { return xboxController.pov(pov, angle, loop).and(context); } - public Trigger povCentre() { - return xboxController.povCenter().and(context); + public Trigger povRaw(int pov, int angle, EventLoop loop) { + return xboxController.pov(pov, angle, loop); } public Trigger povCenter() { return xboxController.povCenter().and(context); } + public Trigger povCenterRaw() { + return xboxController.povCenter(); + } + public Trigger axisLessThan(int axis, double threshold) { return xboxController.axisLessThan(axis, threshold).and(context); } + + public Trigger axisLessThanRaw(int axis, double threshold) { + return xboxController.axisLessThan(axis, threshold); + } public Trigger axisLessThan(int axis, double threshold, EventLoop loop) { return xboxController.axisLessThan(axis, threshold, loop).and(context); } + public Trigger axisLessThanRaw(int axis, double threshold, EventLoop loop) { + return xboxController.axisLessThan(axis, threshold, loop); + } + public Trigger axisGreaterThan(int axis, double threshold) { return xboxController.axisGreaterThan(axis, threshold).and(context); } + public Trigger axisGreaterThanRaw(int axis, double threshold) { + return xboxController.axisGreaterThan(axis, threshold); + } + public Trigger axisGreaterThan(int axis, double threshold, EventLoop loop) { return xboxController.axisGreaterThan(axis, threshold, loop).and(context); } + public Trigger axisGreaterThanRaw(int axis, double threshold, EventLoop loop) { + return xboxController.axisGreaterThan(axis, threshold, loop); + } + public Trigger axisMagnitudeGreaterThan(int axis, double threshold) { return xboxController.axisMagnitudeGreaterThan(axis, threshold).and(context); } + public Trigger axisMagnitudeGreaterThanRaw(int axis, double threshold) { + return xboxController.axisMagnitudeGreaterThan(axis, threshold); + } + public Trigger axisMagnitudeGreaterThan(int axis, double threshold, EventLoop loop) { return xboxController.axisMagnitudeGreaterThan(axis, threshold, loop).and(context); } + public Trigger axisMagnitudeGreaterThanRaw(int axis, double threshold, EventLoop loop) { + return xboxController.axisMagnitudeGreaterThan(axis, threshold, loop); + } + public void setRumble(RumbleType type, double value) { xboxController.setRumble(type, value); } From 7b094aa223d34b56dce7535a98f92ee5dbaa36a4 Mon Sep 17 00:00:00 2001 From: Ava Edwards Date: Mon, 28 Jul 2025 22:22:59 +0800 Subject: [PATCH 4/4] fixed formatting --- .../frc2025/util/ContextfulXboxController.java | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java b/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java index 4c170740..7dd8a840 100644 --- a/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java +++ b/src/main/java/org/curtinfrc/frc2025/util/ContextfulXboxController.java @@ -7,10 +7,10 @@ import java.util.function.BooleanSupplier; /* All the Triggers check for the context as they should -* activate based on the controller state. None of the methods that return a -* (non-trigger) value don't check the context as they return values from the -* physical controller which isn't dependent on the context. -*/ + * activate based on the controller state. None of the methods that return a + * (non-trigger) value don't check the context as they return values from the + * physical controller which isn't dependent on the context. + */ public class ContextfulXboxController { private final CommandXboxController xboxController; @@ -180,7 +180,7 @@ public Trigger povUpLeftRaw() { public Trigger pov(int angle) { return xboxController.pov(angle).and(context); } - + public Trigger povRaw(int angle) { return xboxController.pov(angle); } @@ -204,7 +204,7 @@ public Trigger povCenterRaw() { public Trigger axisLessThan(int axis, double threshold) { return xboxController.axisLessThan(axis, threshold).and(context); } - + public Trigger axisLessThanRaw(int axis, double threshold) { return xboxController.axisLessThan(axis, threshold); } @@ -216,7 +216,7 @@ public Trigger axisLessThan(int axis, double threshold, EventLoop loop) { public Trigger axisLessThanRaw(int axis, double threshold, EventLoop loop) { return xboxController.axisLessThan(axis, threshold, loop); } - + public Trigger axisGreaterThan(int axis, double threshold) { return xboxController.axisGreaterThan(axis, threshold).and(context); }