Class CommandGenericHID

java.lang.Object
edu.wpi.first.wpilibj2.command.button.CommandGenericHID
Direct Known Subclasses:
CommandJoystick, CommandPS4Controller, CommandPS5Controller, CommandStadiaController, CommandXboxController

public class CommandGenericHID
extends Object
A version of GenericHID with Trigger factories for command-based.
See Also:
GenericHID
  • Constructor Details

    • CommandGenericHID

      public CommandGenericHID​(int port)
      Construct an instance of a device.
      Parameters:
      port - The port index on the Driver Station that the device is plugged into.
  • Method Details

    • getHID

      public GenericHID getHID()
      Get the underlying GenericHID object.
      Returns:
      the wrapped GenericHID object
    • button

      public Trigger button​(int button)
      Constructs an event instance around this button's digital signal.
      Parameters:
      button - the button index
      Returns:
      an event instance representing the button's digital signal attached to the default scheduler button loop.
      See Also:
      button(int, EventLoop)
    • button

      public Trigger button​(int button, EventLoop loop)
      Constructs an event instance around this button's digital signal.
      Parameters:
      button - the button index
      loop - the event loop instance to attach the event to.
      Returns:
      an event instance representing the button's digital signal attached to the given loop.
    • pov

      public Trigger pov​(int angle)
      Constructs a Trigger instance based around this angle of the default (index 0) POV on the HID, attached to the default command scheduler button loop.

      The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, upper-left is 315).

      Parameters:
      angle - POV angle in degrees, or -1 for the center / not pressed.
      Returns:
      a Trigger instance based around this angle of a POV on the HID.
    • pov

      public Trigger pov​(int pov, int angle, EventLoop loop)
      Constructs a Trigger instance based around this angle of a POV on the HID.

      The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, upper-left is 315).

      Parameters:
      pov - index of the POV to read (starting at 0). Defaults to 0.
      angle - POV angle in degrees, or -1 for the center / not pressed.
      loop - the event loop instance to attach the event to. Defaults to the default command scheduler button loop.
      Returns:
      a Trigger instance based around this angle of a POV on the HID.
    • povUp

      public Trigger povUp()
      Constructs a Trigger instance based around the 0 degree angle (up) of the default (index 0) POV on the HID, attached to the default command scheduler button loop.
      Returns:
      a Trigger instance based around the 0 degree angle of a POV on the HID.
    • povUpRight

      public Trigger povUpRight()
      Constructs a Trigger instance based around the 45 degree angle (right up) of the default (index 0) POV on the HID, attached to the default command scheduler button loop.
      Returns:
      a Trigger instance based around the 45 degree angle of a POV on the HID.
    • povRight

      public Trigger povRight()
      Constructs a Trigger instance based around the 90 degree angle (right) of the default (index 0) POV on the HID, attached to the default command scheduler button loop.
      Returns:
      a Trigger instance based around the 90 degree angle of a POV on the HID.
    • povDownRight

      Constructs a Trigger instance based around the 135 degree angle (right down) of the default (index 0) POV on the HID, attached to the default command scheduler button loop.
      Returns:
      a Trigger instance based around the 135 degree angle of a POV on the HID.
    • povDown

      public Trigger povDown()
      Constructs a Trigger instance based around the 180 degree angle (down) of the default (index 0) POV on the HID, attached to the default command scheduler button loop.
      Returns:
      a Trigger instance based around the 180 degree angle of a POV on the HID.
    • povDownLeft

      public Trigger povDownLeft()
      Constructs a Trigger instance based around the 225 degree angle (down left) of the default (index 0) POV on the HID, attached to the default command scheduler button loop.
      Returns:
      a Trigger instance based around the 225 degree angle of a POV on the HID.
    • povLeft

      public Trigger povLeft()
      Constructs a Trigger instance based around the 270 degree angle (left) of the default (index 0) POV on the HID, attached to the default command scheduler button loop.
      Returns:
      a Trigger instance based around the 270 degree angle of a POV on the HID.
    • povUpLeft

      public Trigger povUpLeft()
      Constructs a Trigger instance based around the 315 degree angle (left up) of the default (index 0) POV on the HID, attached to the default command scheduler button loop.
      Returns:
      a Trigger instance based around the 315 degree angle of a POV on the HID.
    • povCenter

      public Trigger povCenter()
      Constructs a Trigger instance based around the center (not pressed) position of the default (index 0) POV on the HID, attached to the default command scheduler button loop.
      Returns:
      a Trigger instance based around the center position of a POV on the HID.
    • axisLessThan

      public Trigger axisLessThan​(int axis, double threshold)
      Constructs a Trigger instance that is true when the axis value is less than threshold, attached to the default command scheduler button loop.
      Parameters:
      axis - The axis to read, starting at 0
      threshold - The value below which this trigger should return true.
      Returns:
      a Trigger instance that is true when the axis value is less than the provided threshold.
    • axisLessThan

      public Trigger axisLessThan​(int axis, double threshold, EventLoop loop)
      Constructs a Trigger instance that is true when the axis value is less than threshold, attached to the given loop.
      Parameters:
      axis - The axis to read, starting at 0
      threshold - The value below which this trigger should return true.
      loop - the event loop instance to attach the trigger to
      Returns:
      a Trigger instance that is true when the axis value is less than the provided threshold.
    • axisGreaterThan

      public Trigger axisGreaterThan​(int axis, double threshold)
      Constructs a Trigger instance that is true when the axis value is less than threshold, attached to the default command scheduler button loop.
      Parameters:
      axis - The axis to read, starting at 0
      threshold - The value above which this trigger should return true.
      Returns:
      a Trigger instance that is true when the axis value is greater than the provided threshold.
    • axisGreaterThan

      public Trigger axisGreaterThan​(int axis, double threshold, EventLoop loop)
      Constructs a Trigger instance that is true when the axis value is greater than threshold, attached to the given loop.
      Parameters:
      axis - The axis to read, starting at 0
      threshold - The value above which this trigger should return true.
      loop - the event loop instance to attach the trigger to.
      Returns:
      a Trigger instance that is true when the axis value is greater than the provided threshold.
    • getRawAxis

      public double getRawAxis​(int axis)
      Get the value of the axis.
      Parameters:
      axis - The axis to read, starting at 0.
      Returns:
      The value of the axis.