diff --git a/wpilibj/src/generate/hid.java.jinja b/wpilibj/src/generate/hid.java.jinja index 84dbd8c3e83..aaf8ba2b160 100644 --- a/wpilibj/src/generate/hid.java.jinja +++ b/wpilibj/src/generate/hid.java.jinja @@ -131,7 +131,7 @@ public class {{ ConsoleName }}Controller extends GenericHID { * threshold, attached to the given event loop */ public BooleanEvent {{ trigger.name }}(double threshold, EventLoop loop) { - return new BooleanEvent(loop, () -> get{{ capitalize_first(trigger.name) }}Axis() > threshold); + return axisGreaterThan(Axis.k{{ capitalize_first(trigger.name) }}.value, threshold, loop); } /** @@ -183,7 +183,7 @@ public class {{ ConsoleName }}Controller extends GenericHID { * attached to the given loop. */ public BooleanEvent {{ button.name }}(EventLoop loop) { - return new BooleanEvent(loop, this::get{{ capitalize_first(button.name) }}Button); + return button(Button.k{{ capitalize_first(button.name) }}.value, loop); } {% endfor -%} {% if ConsoleName == "Xbox" or ConsoleName == "Stadia" %} diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java index 3195c5122b0..9d11cc68dc5 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java @@ -217,7 +217,7 @@ public boolean getSquareButtonReleased() { * attached to the given loop. */ public BooleanEvent square(EventLoop loop) { - return new BooleanEvent(loop, this::getSquareButton); + return button(Button.kSquare.value, loop); } /** @@ -255,7 +255,7 @@ public boolean getCrossButtonReleased() { * attached to the given loop. */ public BooleanEvent cross(EventLoop loop) { - return new BooleanEvent(loop, this::getCrossButton); + return button(Button.kCross.value, loop); } /** @@ -293,7 +293,7 @@ public boolean getCircleButtonReleased() { * attached to the given loop. */ public BooleanEvent circle(EventLoop loop) { - return new BooleanEvent(loop, this::getCircleButton); + return button(Button.kCircle.value, loop); } /** @@ -331,7 +331,7 @@ public boolean getTriangleButtonReleased() { * attached to the given loop. */ public BooleanEvent triangle(EventLoop loop) { - return new BooleanEvent(loop, this::getTriangleButton); + return button(Button.kTriangle.value, loop); } /** @@ -369,7 +369,7 @@ public boolean getL1ButtonReleased() { * attached to the given loop. */ public BooleanEvent L1(EventLoop loop) { - return new BooleanEvent(loop, this::getL1Button); + return button(Button.kL1.value, loop); } /** @@ -407,7 +407,7 @@ public boolean getR1ButtonReleased() { * attached to the given loop. */ public BooleanEvent R1(EventLoop loop) { - return new BooleanEvent(loop, this::getR1Button); + return button(Button.kR1.value, loop); } /** @@ -445,7 +445,7 @@ public boolean getL2ButtonReleased() { * attached to the given loop. */ public BooleanEvent L2(EventLoop loop) { - return new BooleanEvent(loop, this::getL2Button); + return button(Button.kL2.value, loop); } /** @@ -483,7 +483,7 @@ public boolean getR2ButtonReleased() { * attached to the given loop. */ public BooleanEvent R2(EventLoop loop) { - return new BooleanEvent(loop, this::getR2Button); + return button(Button.kR2.value, loop); } /** @@ -521,7 +521,7 @@ public boolean getShareButtonReleased() { * attached to the given loop. */ public BooleanEvent share(EventLoop loop) { - return new BooleanEvent(loop, this::getShareButton); + return button(Button.kShare.value, loop); } /** @@ -559,7 +559,7 @@ public boolean getOptionsButtonReleased() { * attached to the given loop. */ public BooleanEvent options(EventLoop loop) { - return new BooleanEvent(loop, this::getOptionsButton); + return button(Button.kOptions.value, loop); } /** @@ -597,7 +597,7 @@ public boolean getL3ButtonReleased() { * attached to the given loop. */ public BooleanEvent L3(EventLoop loop) { - return new BooleanEvent(loop, this::getL3Button); + return button(Button.kL3.value, loop); } /** @@ -635,7 +635,7 @@ public boolean getR3ButtonReleased() { * attached to the given loop. */ public BooleanEvent R3(EventLoop loop) { - return new BooleanEvent(loop, this::getR3Button); + return button(Button.kR3.value, loop); } /** @@ -673,7 +673,7 @@ public boolean getPSButtonReleased() { * attached to the given loop. */ public BooleanEvent PS(EventLoop loop) { - return new BooleanEvent(loop, this::getPSButton); + return button(Button.kPS.value, loop); } /** @@ -711,7 +711,7 @@ public boolean getTouchpadButtonReleased() { * attached to the given loop. */ public BooleanEvent touchpad(EventLoop loop) { - return new BooleanEvent(loop, this::getTouchpadButton); + return button(Button.kTouchpad.value, loop); } /** diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java index 7b0e3083aba..d1c44576d02 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java @@ -217,7 +217,7 @@ public boolean getSquareButtonReleased() { * attached to the given loop. */ public BooleanEvent square(EventLoop loop) { - return new BooleanEvent(loop, this::getSquareButton); + return button(Button.kSquare.value, loop); } /** @@ -255,7 +255,7 @@ public boolean getCrossButtonReleased() { * attached to the given loop. */ public BooleanEvent cross(EventLoop loop) { - return new BooleanEvent(loop, this::getCrossButton); + return button(Button.kCross.value, loop); } /** @@ -293,7 +293,7 @@ public boolean getCircleButtonReleased() { * attached to the given loop. */ public BooleanEvent circle(EventLoop loop) { - return new BooleanEvent(loop, this::getCircleButton); + return button(Button.kCircle.value, loop); } /** @@ -331,7 +331,7 @@ public boolean getTriangleButtonReleased() { * attached to the given loop. */ public BooleanEvent triangle(EventLoop loop) { - return new BooleanEvent(loop, this::getTriangleButton); + return button(Button.kTriangle.value, loop); } /** @@ -369,7 +369,7 @@ public boolean getL1ButtonReleased() { * attached to the given loop. */ public BooleanEvent L1(EventLoop loop) { - return new BooleanEvent(loop, this::getL1Button); + return button(Button.kL1.value, loop); } /** @@ -407,7 +407,7 @@ public boolean getR1ButtonReleased() { * attached to the given loop. */ public BooleanEvent R1(EventLoop loop) { - return new BooleanEvent(loop, this::getR1Button); + return button(Button.kR1.value, loop); } /** @@ -445,7 +445,7 @@ public boolean getL2ButtonReleased() { * attached to the given loop. */ public BooleanEvent L2(EventLoop loop) { - return new BooleanEvent(loop, this::getL2Button); + return button(Button.kL2.value, loop); } /** @@ -483,7 +483,7 @@ public boolean getR2ButtonReleased() { * attached to the given loop. */ public BooleanEvent R2(EventLoop loop) { - return new BooleanEvent(loop, this::getR2Button); + return button(Button.kR2.value, loop); } /** @@ -521,7 +521,7 @@ public boolean getCreateButtonReleased() { * attached to the given loop. */ public BooleanEvent create(EventLoop loop) { - return new BooleanEvent(loop, this::getCreateButton); + return button(Button.kCreate.value, loop); } /** @@ -559,7 +559,7 @@ public boolean getOptionsButtonReleased() { * attached to the given loop. */ public BooleanEvent options(EventLoop loop) { - return new BooleanEvent(loop, this::getOptionsButton); + return button(Button.kOptions.value, loop); } /** @@ -597,7 +597,7 @@ public boolean getL3ButtonReleased() { * attached to the given loop. */ public BooleanEvent L3(EventLoop loop) { - return new BooleanEvent(loop, this::getL3Button); + return button(Button.kL3.value, loop); } /** @@ -635,7 +635,7 @@ public boolean getR3ButtonReleased() { * attached to the given loop. */ public BooleanEvent R3(EventLoop loop) { - return new BooleanEvent(loop, this::getR3Button); + return button(Button.kR3.value, loop); } /** @@ -673,7 +673,7 @@ public boolean getPSButtonReleased() { * attached to the given loop. */ public BooleanEvent PS(EventLoop loop) { - return new BooleanEvent(loop, this::getPSButton); + return button(Button.kPS.value, loop); } /** @@ -711,7 +711,7 @@ public boolean getTouchpadButtonReleased() { * attached to the given loop. */ public BooleanEvent touchpad(EventLoop loop) { - return new BooleanEvent(loop, this::getTouchpadButton); + return button(Button.kTouchpad.value, loop); } /** diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java index 916ab3979dc..ca8cbffa1f1 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java @@ -195,7 +195,7 @@ public boolean getAButtonReleased() { * attached to the given loop. */ public BooleanEvent a(EventLoop loop) { - return new BooleanEvent(loop, this::getAButton); + return button(Button.kA.value, loop); } /** @@ -233,7 +233,7 @@ public boolean getBButtonReleased() { * attached to the given loop. */ public BooleanEvent b(EventLoop loop) { - return new BooleanEvent(loop, this::getBButton); + return button(Button.kB.value, loop); } /** @@ -271,7 +271,7 @@ public boolean getXButtonReleased() { * attached to the given loop. */ public BooleanEvent x(EventLoop loop) { - return new BooleanEvent(loop, this::getXButton); + return button(Button.kX.value, loop); } /** @@ -309,7 +309,7 @@ public boolean getYButtonReleased() { * attached to the given loop. */ public BooleanEvent y(EventLoop loop) { - return new BooleanEvent(loop, this::getYButton); + return button(Button.kY.value, loop); } /** @@ -347,7 +347,7 @@ public boolean getLeftBumperButtonReleased() { * attached to the given loop. */ public BooleanEvent leftBumper(EventLoop loop) { - return new BooleanEvent(loop, this::getLeftBumperButton); + return button(Button.kLeftBumper.value, loop); } /** @@ -385,7 +385,7 @@ public boolean getRightBumperButtonReleased() { * attached to the given loop. */ public BooleanEvent rightBumper(EventLoop loop) { - return new BooleanEvent(loop, this::getRightBumperButton); + return button(Button.kRightBumper.value, loop); } /** @@ -423,7 +423,7 @@ public boolean getLeftStickButtonReleased() { * attached to the given loop. */ public BooleanEvent leftStick(EventLoop loop) { - return new BooleanEvent(loop, this::getLeftStickButton); + return button(Button.kLeftStick.value, loop); } /** @@ -461,7 +461,7 @@ public boolean getRightStickButtonReleased() { * attached to the given loop. */ public BooleanEvent rightStick(EventLoop loop) { - return new BooleanEvent(loop, this::getRightStickButton); + return button(Button.kRightStick.value, loop); } /** @@ -499,7 +499,7 @@ public boolean getEllipsesButtonReleased() { * attached to the given loop. */ public BooleanEvent ellipses(EventLoop loop) { - return new BooleanEvent(loop, this::getEllipsesButton); + return button(Button.kEllipses.value, loop); } /** @@ -537,7 +537,7 @@ public boolean getHamburgerButtonReleased() { * attached to the given loop. */ public BooleanEvent hamburger(EventLoop loop) { - return new BooleanEvent(loop, this::getHamburgerButton); + return button(Button.kHamburger.value, loop); } /** @@ -575,7 +575,7 @@ public boolean getStadiaButtonReleased() { * attached to the given loop. */ public BooleanEvent stadia(EventLoop loop) { - return new BooleanEvent(loop, this::getStadiaButton); + return button(Button.kStadia.value, loop); } /** @@ -613,7 +613,7 @@ public boolean getRightTriggerButtonReleased() { * attached to the given loop. */ public BooleanEvent rightTrigger(EventLoop loop) { - return new BooleanEvent(loop, this::getRightTriggerButton); + return button(Button.kRightTrigger.value, loop); } /** @@ -651,7 +651,7 @@ public boolean getLeftTriggerButtonReleased() { * attached to the given loop. */ public BooleanEvent leftTrigger(EventLoop loop) { - return new BooleanEvent(loop, this::getLeftTriggerButton); + return button(Button.kLeftTrigger.value, loop); } /** @@ -689,7 +689,7 @@ public boolean getGoogleButtonReleased() { * attached to the given loop. */ public BooleanEvent google(EventLoop loop) { - return new BooleanEvent(loop, this::getGoogleButton); + return button(Button.kGoogle.value, loop); } /** @@ -727,7 +727,7 @@ public boolean getFrameButtonReleased() { * attached to the given loop. */ public BooleanEvent frame(EventLoop loop) { - return new BooleanEvent(loop, this::getFrameButton); + return button(Button.kFrame.value, loop); } /** diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java index 3bf77e11f61..93e9a92b9a9 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java @@ -175,7 +175,7 @@ public double getLeftTriggerAxis() { * threshold, attached to the given event loop */ public BooleanEvent leftTrigger(double threshold, EventLoop loop) { - return new BooleanEvent(loop, () -> getLeftTriggerAxis() > threshold); + return axisGreaterThan(Axis.kLeftTrigger.value, threshold, loop); } /** @@ -211,7 +211,7 @@ public double getRightTriggerAxis() { * threshold, attached to the given event loop */ public BooleanEvent rightTrigger(double threshold, EventLoop loop) { - return new BooleanEvent(loop, () -> getRightTriggerAxis() > threshold); + return axisGreaterThan(Axis.kRightTrigger.value, threshold, loop); } /** @@ -261,7 +261,7 @@ public boolean getAButtonReleased() { * attached to the given loop. */ public BooleanEvent a(EventLoop loop) { - return new BooleanEvent(loop, this::getAButton); + return button(Button.kA.value, loop); } /** @@ -299,7 +299,7 @@ public boolean getBButtonReleased() { * attached to the given loop. */ public BooleanEvent b(EventLoop loop) { - return new BooleanEvent(loop, this::getBButton); + return button(Button.kB.value, loop); } /** @@ -337,7 +337,7 @@ public boolean getXButtonReleased() { * attached to the given loop. */ public BooleanEvent x(EventLoop loop) { - return new BooleanEvent(loop, this::getXButton); + return button(Button.kX.value, loop); } /** @@ -375,7 +375,7 @@ public boolean getYButtonReleased() { * attached to the given loop. */ public BooleanEvent y(EventLoop loop) { - return new BooleanEvent(loop, this::getYButton); + return button(Button.kY.value, loop); } /** @@ -413,7 +413,7 @@ public boolean getLeftBumperButtonReleased() { * attached to the given loop. */ public BooleanEvent leftBumper(EventLoop loop) { - return new BooleanEvent(loop, this::getLeftBumperButton); + return button(Button.kLeftBumper.value, loop); } /** @@ -451,7 +451,7 @@ public boolean getRightBumperButtonReleased() { * attached to the given loop. */ public BooleanEvent rightBumper(EventLoop loop) { - return new BooleanEvent(loop, this::getRightBumperButton); + return button(Button.kRightBumper.value, loop); } /** @@ -489,7 +489,7 @@ public boolean getBackButtonReleased() { * attached to the given loop. */ public BooleanEvent back(EventLoop loop) { - return new BooleanEvent(loop, this::getBackButton); + return button(Button.kBack.value, loop); } /** @@ -527,7 +527,7 @@ public boolean getStartButtonReleased() { * attached to the given loop. */ public BooleanEvent start(EventLoop loop) { - return new BooleanEvent(loop, this::getStartButton); + return button(Button.kStart.value, loop); } /** @@ -565,7 +565,7 @@ public boolean getLeftStickButtonReleased() { * attached to the given loop. */ public BooleanEvent leftStick(EventLoop loop) { - return new BooleanEvent(loop, this::getLeftStickButton); + return button(Button.kLeftStick.value, loop); } /** @@ -603,7 +603,7 @@ public boolean getRightStickButtonReleased() { * attached to the given loop. */ public BooleanEvent rightStick(EventLoop loop) { - return new BooleanEvent(loop, this::getRightStickButton); + return button(Button.kRightStick.value, loop); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java index ceb00a780b2..dccbc14a5f9 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java @@ -97,6 +97,9 @@ public static HIDType of(int value) { private int m_outputs; private int m_leftRumble; private int m_rightRumble; + private final Map> m_buttonCache = new HashMap<>(); + private final Map> m_axisCache = new HashMap<>(); + private final Map> m_povCache = new HashMap<>(); /** * Construct an instance of a device. @@ -159,7 +162,8 @@ public boolean getRawButtonReleased(int button) { * @return an event instance representing the button's digital signal attached to the given loop. */ public BooleanEvent button(int button, EventLoop loop) { - return new BooleanEvent(loop, () -> getRawButton(button)); + var cache = m_buttonCache.computeIfAbsent(loop, k -> new HashMap<>()); + return cache.computeIfAbsent(button, k -> new BooleanEvent(loop, () -> getRawButton(k))); } /** @@ -223,7 +227,10 @@ public BooleanEvent pov(int angle, EventLoop loop) { * @return a BooleanEvent instance based around this angle of a POV on the HID. */ public BooleanEvent pov(int pov, int angle, EventLoop loop) { - return new BooleanEvent(loop, () -> getPOV(pov) == angle); + var cache = m_povCache.computeIfAbsent(loop, k -> new HashMap<>()); + // angle can be -1, so use 3600 instead of 360 + return cache.computeIfAbsent( + pov * 3600 + angle, k -> new BooleanEvent(loop, () -> getPOV(pov) == angle)); } /** @@ -335,7 +342,9 @@ public BooleanEvent povCenter(EventLoop loop) { * @return an event instance that is true when the axis value is less than the provided threshold. */ public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) { - return new BooleanEvent(loop, () -> getRawAxis(axis) < threshold); + var cache = m_axisCache.computeIfAbsent(loop, k -> new HashMap<>()); + return cache.computeIfAbsent( + axis * 100 - threshold, k -> new BooleanEvent(loop, () -> getRawAxis(axis) < threshold)); } /** @@ -349,7 +358,9 @@ public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) { * threshold. */ public BooleanEvent axisGreaterThan(int axis, double threshold, EventLoop loop) { - return new BooleanEvent(loop, () -> getRawAxis(axis) > threshold); + var cache = m_axisCache.computeIfAbsent(loop, k -> new HashMap<>()); + return cache.computeIfAbsent( + axis * 100 + threshold, k -> new BooleanEvent(loop, () -> getRawAxis(axis) > threshold)); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java index 5536009e320..08eebeef7df 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java @@ -261,7 +261,7 @@ public boolean getTriggerReleased() { * given loop. */ public BooleanEvent trigger(EventLoop loop) { - return new BooleanEvent(loop, this::getTrigger); + return button(ButtonType.kTrigger.value, loop); } /** @@ -299,7 +299,7 @@ public boolean getTopReleased() { * loop. */ public BooleanEvent top(EventLoop loop) { - return new BooleanEvent(loop, this::getTop); + return button(ButtonType.kTop.value, loop); } /**