Skip to content

Commit

Permalink
add some triggers with HID instead (#152)
Browse files Browse the repository at this point in the history
I am Tina, Tina say yes, Tina, Yes, Tina shrimp, Tina is a shrimp. surely, then exclamation mark, like 4 of them, geese geese geese 🤓🤓🤓🤓🤓
  • Loading branch information
GalexY727 authored Feb 16, 2024
2 parents b4ef768 + bcfc184 commit 50cee8e
Show file tree
Hide file tree
Showing 2 changed files with 45 additions and 21 deletions.
9 changes: 4 additions & 5 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -150,12 +150,11 @@ public RobotContainer() {
driver::getLeftY,
driver::getLeftX,
() -> -driver.getRightX(),
() -> !driver.getHID().getYButton(),
() -> (driver.getHID().getYButton()
&& Robot.isRedAlliance())));

configureButtonBindings();
() -> !driver.getYButton(),
() -> (driver.getYButton()
&& Robot.isBlueAlliance())));

configureButtonBindings();
initializeArrays();

pathPlannerStorage = new PathPlannerStorage(driver.y());
Expand Down
57 changes: 41 additions & 16 deletions src/main/java/frc/robot/util/PatriBoxController.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package frc.robot.util;

import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Rotation2d;
Expand Down Expand Up @@ -28,6 +29,22 @@ public double getLeftX() {
return getLeftAxis().getX();
}

public boolean getAButton() {
return super.getHID().getAButton();
}

public boolean getBButton() {
return super.getHID().getBButton();
}

public boolean getXButton() {
return super.getHID().getXButton();
}

public boolean getYButton() {
return super.getHID().getYButton();
}

@Override
// This is inverted because for some reason when you
// go forward on the controller, it returns a negative value
Expand All @@ -41,36 +58,44 @@ public Translation2d getLeftAxis() {
return driverLeftAxis;
}

public Trigger leftY() {
return leftY(0.3, CommandScheduler.getInstance().getDefaultButtonLoop());
public double getLeftTriggerAxis() {
return super.getHID().getLeftTriggerAxis();
}

public double getRightTriggerAxis() {
return super.getHID().getRightTriggerAxis();
}

public boolean getStartButton() {
return super.getHID().getStartButton();
}

public Trigger leftX() {
return leftX(0.3, CommandScheduler.getInstance().getDefaultButtonLoop());
public boolean getBackButton() {
return super.getHID().getBackButton();
}

public Trigger rightY() {
return rightY(0.3, CommandScheduler.getInstance().getDefaultButtonLoop());
public boolean getPOVUp() {
return super.getHID().getPOV() == 0;
}

public Trigger rightX() {
return rightX(0.3, CommandScheduler.getInstance().getDefaultButtonLoop());
public boolean getPOVRight() {
return super.getHID().getPOV() == 90;
}

public Trigger leftY(double threshold, EventLoop loop) {
return new Trigger(loop, () -> Math.abs(getLeftY()) > threshold);
public boolean getPOVDown() {
return super.getHID().getPOV() == 180;
}

public Trigger leftX(double threshold, EventLoop loop) {
return new Trigger(loop, () -> Math.abs(getLeftX()) > threshold);
public boolean getPOVLeft() {
return super.getHID().getPOV() == 270;
}

public Trigger rightY(double threshold, EventLoop loop) {
return new Trigger(loop, () -> Math.abs(getRightY()) > threshold);
public boolean getLeftBumper() {
return super.getHID().getLeftBumper();
}

public Trigger rightX(double threshold, EventLoop loop) {
return new Trigger(loop, () -> Math.abs(getRightX()) > threshold);
public boolean getRightBumper() {
return super.getHID().getRightBumper();
}

@Override
Expand Down

0 comments on commit 50cee8e

Please sign in to comment.