001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj2.command.button; 006 007import edu.wpi.first.wpilibj.GenericHID; 008import edu.wpi.first.wpilibj.event.EventLoop; 009import edu.wpi.first.wpilibj2.command.CommandScheduler; 010 011/** 012 * A version of {@link GenericHID} with {@link Trigger} factories for command-based. 013 * 014 * @see GenericHID 015 */ 016public class CommandGenericHID { 017 private final GenericHID m_hid; 018 019 /** 020 * Construct an instance of a device. 021 * 022 * @param port The port index on the Driver Station that the device is plugged into. 023 */ 024 public CommandGenericHID(int port) { 025 m_hid = new GenericHID(port); 026 } 027 028 /** 029 * Get the underlying GenericHID object. 030 * 031 * @return the wrapped GenericHID object 032 */ 033 public GenericHID getHID() { 034 return m_hid; 035 } 036 037 /** 038 * Constructs an event instance around this button's digital signal. 039 * 040 * @param button the button index 041 * @return an event instance representing the button's digital signal attached to the {@link 042 * CommandScheduler#getDefaultButtonLoop() default scheduler button loop}. 043 * @see #button(int, EventLoop) 044 */ 045 public Trigger button(int button) { 046 return this.button(button, CommandScheduler.getInstance().getDefaultButtonLoop()); 047 } 048 049 /** 050 * Constructs an event instance around this button's digital signal. 051 * 052 * @param button the button index 053 * @param loop the event loop instance to attach the event to. 054 * @return an event instance representing the button's digital signal attached to the given loop. 055 */ 056 public Trigger button(int button, EventLoop loop) { 057 return new Trigger(loop, () -> m_hid.getRawButton(button)); 058 } 059 060 /** 061 * Constructs a Trigger instance based around this angle of the default (index 0) POV on the HID, 062 * attached to {@link CommandScheduler#getDefaultButtonLoop() the default command scheduler button 063 * loop}. 064 * 065 * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, 066 * upper-left is 315). 067 * 068 * @param angle POV angle in degrees, or -1 for the center / not pressed. 069 * @return a Trigger instance based around this angle of a POV on the HID. 070 */ 071 public Trigger pov(int angle) { 072 return pov(0, angle, CommandScheduler.getInstance().getDefaultButtonLoop()); 073 } 074 075 /** 076 * Constructs a Trigger instance based around this angle of a POV on the HID. 077 * 078 * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, 079 * upper-left is 315). 080 * 081 * @param pov index of the POV to read (starting at 0). Defaults to 0. 082 * @param angle POV angle in degrees, or -1 for the center / not pressed. 083 * @param loop the event loop instance to attach the event to. Defaults to {@link 084 * CommandScheduler#getDefaultButtonLoop() the default command scheduler button loop}. 085 * @return a Trigger instance based around this angle of a POV on the HID. 086 */ 087 public Trigger pov(int pov, int angle, EventLoop loop) { 088 return new Trigger(loop, () -> m_hid.getPOV(pov) == angle); 089 } 090 091 /** 092 * Constructs a Trigger instance based around the 0 degree angle (up) of the default (index 0) POV 093 * on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default command 094 * scheduler button loop}. 095 * 096 * @return a Trigger instance based around the 0 degree angle of a POV on the HID. 097 */ 098 public Trigger povUp() { 099 return pov(0); 100 } 101 102 /** 103 * Constructs a Trigger instance based around the 45 degree angle (right up) of the default (index 104 * 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default 105 * command scheduler button loop}. 106 * 107 * @return a Trigger instance based around the 45 degree angle of a POV on the HID. 108 */ 109 public Trigger povUpRight() { 110 return pov(45); 111 } 112 113 /** 114 * Constructs a Trigger instance based around the 90 degree angle (right) of the default (index 0) 115 * POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default command 116 * scheduler button loop}. 117 * 118 * @return a Trigger instance based around the 90 degree angle of a POV on the HID. 119 */ 120 public Trigger povRight() { 121 return pov(90); 122 } 123 124 /** 125 * Constructs a Trigger instance based around the 135 degree angle (right down) of the default 126 * (index 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the 127 * default command scheduler button loop}. 128 * 129 * @return a Trigger instance based around the 135 degree angle of a POV on the HID. 130 */ 131 public Trigger povDownRight() { 132 return pov(135); 133 } 134 135 /** 136 * Constructs a Trigger instance based around the 180 degree angle (down) of the default (index 0) 137 * POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default command 138 * scheduler button loop}. 139 * 140 * @return a Trigger instance based around the 180 degree angle of a POV on the HID. 141 */ 142 public Trigger povDown() { 143 return pov(180); 144 } 145 146 /** 147 * Constructs a Trigger instance based around the 225 degree angle (down left) of the default 148 * (index 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the 149 * default command scheduler button loop}. 150 * 151 * @return a Trigger instance based around the 225 degree angle of a POV on the HID. 152 */ 153 public Trigger povDownLeft() { 154 return pov(225); 155 } 156 157 /** 158 * Constructs a Trigger instance based around the 270 degree angle (left) of the default (index 0) 159 * POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default command 160 * scheduler button loop}. 161 * 162 * @return a Trigger instance based around the 270 degree angle of a POV on the HID. 163 */ 164 public Trigger povLeft() { 165 return pov(270); 166 } 167 168 /** 169 * Constructs a Trigger instance based around the 315 degree angle (left up) of the default (index 170 * 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the default 171 * command scheduler button loop}. 172 * 173 * @return a Trigger instance based around the 315 degree angle of a POV on the HID. 174 */ 175 public Trigger povUpLeft() { 176 return pov(315); 177 } 178 179 /** 180 * Constructs a Trigger instance based around the center (not pressed) position of the default 181 * (index 0) POV on the HID, attached to {@link CommandScheduler#getDefaultButtonLoop() the 182 * default command scheduler button loop}. 183 * 184 * @return a Trigger instance based around the center position of a POV on the HID. 185 */ 186 public Trigger povCenter() { 187 return pov(-1); 188 } 189 190 /** 191 * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, 192 * attached to {@link CommandScheduler#getDefaultButtonLoop() the default command scheduler button 193 * loop}. 194 * 195 * @param axis The axis to read, starting at 0 196 * @param threshold The value below which this trigger should return true. 197 * @return a Trigger instance that is true when the axis value is less than the provided 198 * threshold. 199 */ 200 public Trigger axisLessThan(int axis, double threshold) { 201 return axisLessThan(axis, threshold, CommandScheduler.getInstance().getDefaultButtonLoop()); 202 } 203 204 /** 205 * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, 206 * attached to the given loop. 207 * 208 * @param axis The axis to read, starting at 0 209 * @param threshold The value below which this trigger should return true. 210 * @param loop the event loop instance to attach the trigger to 211 * @return a Trigger instance that is true when the axis value is less than the provided 212 * threshold. 213 */ 214 public Trigger axisLessThan(int axis, double threshold, EventLoop loop) { 215 return m_hid.axisLessThan(axis, threshold, loop).castTo(Trigger::new); 216 } 217 218 /** 219 * Constructs a Trigger instance that is true when the axis value is less than {@code threshold}, 220 * attached to {@link CommandScheduler#getDefaultButtonLoop() the default command scheduler button 221 * loop}. 222 * 223 * @param axis The axis to read, starting at 0 224 * @param threshold The value above which this trigger should return true. 225 * @return a Trigger instance that is true when the axis value is greater than the provided 226 * threshold. 227 */ 228 public Trigger axisGreaterThan(int axis, double threshold) { 229 return axisGreaterThan(axis, threshold, CommandScheduler.getInstance().getDefaultButtonLoop()); 230 } 231 232 /** 233 * Constructs a Trigger instance that is true when the axis value is greater than {@code 234 * threshold}, attached to the given loop. 235 * 236 * @param axis The axis to read, starting at 0 237 * @param threshold The value above which this trigger should return true. 238 * @param loop the event loop instance to attach the trigger to. 239 * @return a Trigger instance that is true when the axis value is greater than the provided 240 * threshold. 241 */ 242 public Trigger axisGreaterThan(int axis, double threshold, EventLoop loop) { 243 return m_hid.axisGreaterThan(axis, threshold, loop).castTo(Trigger::new); 244 } 245 246 /** 247 * Get the value of the axis. 248 * 249 * @param axis The axis to read, starting at 0. 250 * @return The value of the axis. 251 */ 252 public double getRawAxis(int axis) { 253 return m_hid.getRawAxis(axis); 254 } 255}