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 static edu.wpi.first.util.ErrorMessages.requireNonNullParam; 008 009import edu.wpi.first.math.filter.Debouncer; 010import edu.wpi.first.wpilibj.event.EventLoop; 011import edu.wpi.first.wpilibj2.command.Command; 012import edu.wpi.first.wpilibj2.command.CommandScheduler; 013import java.util.function.BooleanSupplier; 014 015/** 016 * This class provides an easy way to link commands to conditions. 017 * 018 * <p>It is very easy to link a button to a command. For instance, you could link the trigger button 019 * of a joystick to a "score" command. 020 * 021 * <p>Triggers can easily be composed for advanced functionality using the {@link 022 * #and(BooleanSupplier)}, {@link #or(BooleanSupplier)}, {@link #negate()} operators. 023 * 024 * <p>This class is provided by the NewCommands VendorDep 025 */ 026public class Trigger implements BooleanSupplier { 027 private final BooleanSupplier m_condition; 028 private final EventLoop m_loop; 029 030 /** 031 * Creates a new trigger based on the given condition. 032 * 033 * @param loop The loop instance that polls this trigger. 034 * @param condition the condition represented by this trigger 035 */ 036 public Trigger(EventLoop loop, BooleanSupplier condition) { 037 m_loop = requireNonNullParam(loop, "loop", "Trigger"); 038 m_condition = requireNonNullParam(condition, "condition", "Trigger"); 039 } 040 041 /** 042 * Creates a new trigger based on the given condition. 043 * 044 * <p>Polled by the default scheduler button loop. 045 * 046 * @param condition the condition represented by this trigger 047 */ 048 public Trigger(BooleanSupplier condition) { 049 this(CommandScheduler.getInstance().getDefaultButtonLoop(), condition); 050 } 051 052 /** 053 * Starts the given command whenever the condition changes from `false` to `true`. 054 * 055 * @param command the command to start 056 * @return this trigger, so calls can be chained 057 */ 058 public Trigger onTrue(Command command) { 059 requireNonNullParam(command, "command", "onTrue"); 060 m_loop.bind( 061 new Runnable() { 062 private boolean m_pressedLast = m_condition.getAsBoolean(); 063 064 @Override 065 public void run() { 066 boolean pressed = m_condition.getAsBoolean(); 067 068 if (!m_pressedLast && pressed) { 069 command.schedule(); 070 } 071 072 m_pressedLast = pressed; 073 } 074 }); 075 return this; 076 } 077 078 /** 079 * Starts the given command whenever the condition changes from `true` to `false`. 080 * 081 * @param command the command to start 082 * @return this trigger, so calls can be chained 083 */ 084 public Trigger onFalse(Command command) { 085 requireNonNullParam(command, "command", "onFalse"); 086 m_loop.bind( 087 new Runnable() { 088 private boolean m_pressedLast = m_condition.getAsBoolean(); 089 090 @Override 091 public void run() { 092 boolean pressed = m_condition.getAsBoolean(); 093 094 if (m_pressedLast && !pressed) { 095 command.schedule(); 096 } 097 098 m_pressedLast = pressed; 099 } 100 }); 101 return this; 102 } 103 104 /** 105 * Starts the given command when the condition changes to `true` and cancels it when the condition 106 * changes to `false`. 107 * 108 * <p>Doesn't re-start the command if it ends while the condition is still `true`. If the command 109 * should restart, see {@link edu.wpi.first.wpilibj2.command.RepeatCommand}. 110 * 111 * @param command the command to start 112 * @return this trigger, so calls can be chained 113 */ 114 public Trigger whileTrue(Command command) { 115 requireNonNullParam(command, "command", "whileTrue"); 116 m_loop.bind( 117 new Runnable() { 118 private boolean m_pressedLast = m_condition.getAsBoolean(); 119 120 @Override 121 public void run() { 122 boolean pressed = m_condition.getAsBoolean(); 123 124 if (!m_pressedLast && pressed) { 125 command.schedule(); 126 } else if (m_pressedLast && !pressed) { 127 command.cancel(); 128 } 129 130 m_pressedLast = pressed; 131 } 132 }); 133 return this; 134 } 135 136 /** 137 * Starts the given command when the condition changes to `false` and cancels it when the 138 * condition changes to `true`. 139 * 140 * <p>Doesn't re-start the command if it ends while the condition is still `false`. If the command 141 * should restart, see {@link edu.wpi.first.wpilibj2.command.RepeatCommand}. 142 * 143 * @param command the command to start 144 * @return this trigger, so calls can be chained 145 */ 146 public Trigger whileFalse(Command command) { 147 requireNonNullParam(command, "command", "whileFalse"); 148 m_loop.bind( 149 new Runnable() { 150 private boolean m_pressedLast = m_condition.getAsBoolean(); 151 152 @Override 153 public void run() { 154 boolean pressed = m_condition.getAsBoolean(); 155 156 if (m_pressedLast && !pressed) { 157 command.schedule(); 158 } else if (!m_pressedLast && pressed) { 159 command.cancel(); 160 } 161 162 m_pressedLast = pressed; 163 } 164 }); 165 return this; 166 } 167 168 /** 169 * Toggles a command when the condition changes from `false` to `true`. 170 * 171 * @param command the command to toggle 172 * @return this trigger, so calls can be chained 173 */ 174 public Trigger toggleOnTrue(Command command) { 175 requireNonNullParam(command, "command", "toggleOnTrue"); 176 m_loop.bind( 177 new Runnable() { 178 private boolean m_pressedLast = m_condition.getAsBoolean(); 179 180 @Override 181 public void run() { 182 boolean pressed = m_condition.getAsBoolean(); 183 184 if (!m_pressedLast && pressed) { 185 if (command.isScheduled()) { 186 command.cancel(); 187 } else { 188 command.schedule(); 189 } 190 } 191 192 m_pressedLast = pressed; 193 } 194 }); 195 return this; 196 } 197 198 /** 199 * Toggles a command when the condition changes from `true` to `false`. 200 * 201 * @param command the command to toggle 202 * @return this trigger, so calls can be chained 203 */ 204 public Trigger toggleOnFalse(Command command) { 205 requireNonNullParam(command, "command", "toggleOnFalse"); 206 m_loop.bind( 207 new Runnable() { 208 private boolean m_pressedLast = m_condition.getAsBoolean(); 209 210 @Override 211 public void run() { 212 boolean pressed = m_condition.getAsBoolean(); 213 214 if (m_pressedLast && !pressed) { 215 if (command.isScheduled()) { 216 command.cancel(); 217 } else { 218 command.schedule(); 219 } 220 } 221 222 m_pressedLast = pressed; 223 } 224 }); 225 return this; 226 } 227 228 @Override 229 public boolean getAsBoolean() { 230 return m_condition.getAsBoolean(); 231 } 232 233 /** 234 * Composes two triggers with logical AND. 235 * 236 * @param trigger the condition to compose with 237 * @return A trigger which is active when both component triggers are active. 238 */ 239 public Trigger and(BooleanSupplier trigger) { 240 return new Trigger(() -> m_condition.getAsBoolean() && trigger.getAsBoolean()); 241 } 242 243 /** 244 * Composes two triggers with logical OR. 245 * 246 * @param trigger the condition to compose with 247 * @return A trigger which is active when either component trigger is active. 248 */ 249 public Trigger or(BooleanSupplier trigger) { 250 return new Trigger(() -> m_condition.getAsBoolean() || trigger.getAsBoolean()); 251 } 252 253 /** 254 * Creates a new trigger that is active when this trigger is inactive, i.e. that acts as the 255 * negation of this trigger. 256 * 257 * @return the negated trigger 258 */ 259 public Trigger negate() { 260 return new Trigger(() -> !m_condition.getAsBoolean()); 261 } 262 263 /** 264 * Creates a new debounced trigger from this trigger - it will become active when this trigger has 265 * been active for longer than the specified period. 266 * 267 * @param seconds The debounce period. 268 * @return The debounced trigger (rising edges debounced only) 269 */ 270 public Trigger debounce(double seconds) { 271 return debounce(seconds, Debouncer.DebounceType.kRising); 272 } 273 274 /** 275 * Creates a new debounced trigger from this trigger - it will become active when this trigger has 276 * been active for longer than the specified period. 277 * 278 * @param seconds The debounce period. 279 * @param type The debounce type. 280 * @return The debounced trigger. 281 */ 282 public Trigger debounce(double seconds, Debouncer.DebounceType type) { 283 return new Trigger( 284 new BooleanSupplier() { 285 final Debouncer m_debouncer = new Debouncer(seconds, type); 286 287 @Override 288 public boolean getAsBoolean() { 289 return m_debouncer.calculate(m_condition.getAsBoolean()); 290 } 291 }); 292 } 293}