WPILibC++ 2024.1.1-beta-4
Trigger.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <concepts>
8#include <functional>
9#include <memory>
10#include <utility>
11
13#include <frc/event/EventLoop.h>
15#include <units/time.h>
16
19
20namespace frc2 {
21class Command;
22/**
23 * This class provides an easy way to link commands to conditions.
24 *
25 * <p>It is very easy to link a button to a command. For instance, you could
26 * link the trigger button of a joystick to a "score" command.
27 *
28 * <p>Triggers can easily be composed for advanced functionality using the
29 * {@link #operator!}, {@link #operator||}, {@link #operator&&} operators.
30 *
31 * <p>This class is provided by the NewCommands VendorDep
32 */
33class Trigger {
34 public:
35 /**
36 * Creates a new trigger based on the given condition.
37 *
38 * <p>Polled by the default scheduler button loop.
39 *
40 * @param condition the condition represented by this trigger
41 */
42 explicit Trigger(std::function<bool()> condition)
43 : Trigger{CommandScheduler::GetInstance().GetDefaultButtonLoop(),
44 std::move(condition)} {}
45
46 /**
47 * Creates a new trigger based on the given condition.
48 *
49 * @param loop The loop instance that polls this trigger.
50 * @param condition the condition represented by this trigger
51 */
52 Trigger(frc::EventLoop* loop, std::function<bool()> condition)
53 : m_loop{loop}, m_condition{std::move(condition)} {}
54
55 /**
56 * Create a new trigger that is always `false`.
57 */
58 Trigger() : Trigger([] { return false; }) {}
59
60 Trigger(const Trigger& other);
61
62 /**
63 * Starts the given command whenever the condition changes from `false` to
64 * `true`.
65 *
66 * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
67 * lifespan of the command.
68 *
69 * @param command the command to start
70 * @return this trigger, so calls can be chained
71 */
73
74 /**
75 * Starts the given command whenever the condition changes from `false` to
76 * `true`. Moves command ownership to the button scheduler.
77 *
78 * @param command The command to bind.
79 * @return The trigger, for chained calls.
80 */
82
83 /**
84 * Starts the given command whenever the condition changes from `true` to
85 * `false`.
86 *
87 * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
88 * lifespan of the command.
89 *
90 * @param command the command to start
91 * @return this trigger, so calls can be chained
92 */
94
95 /**
96 * Starts the given command whenever the condition changes from `true` to
97 * `false`.
98 *
99 * @param command The command to bind.
100 * @return The trigger, for chained calls.
101 */
103
104 /**
105 * Starts the given command when the condition changes to `true` and cancels
106 * it when the condition changes to `false`.
107 *
108 * <p>Doesn't re-start the command if it ends while the condition is still
109 * `true`. If the command should restart, see RepeatCommand.
110 *
111 * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
112 * lifespan of the command.
113 *
114 * @param command the command to start
115 * @return this trigger, so calls can be chained
116 */
118
119 /**
120 * Starts the given command when the condition changes to `true` and cancels
121 * it when the condition changes to `false`. Moves command ownership to the
122 * button scheduler.
123 *
124 * <p>Doesn't re-start the command if it ends while the condition is still
125 * `true`. If the command should restart, see RepeatCommand.
126 *
127 * @param command The command to bind.
128 * @return The trigger, for chained calls.
129 */
131
132 /**
133 * Starts the given command when the condition changes to `false` and cancels
134 * it when the condition changes to `true`.
135 *
136 * <p>Doesn't re-start the command if it ends while the condition is still
137 * `true`. If the command should restart, see RepeatCommand.
138 *
139 * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
140 * lifespan of the command.
141 *
142 * @param command the command to start
143 * @return this trigger, so calls can be chained
144 */
146
147 /**
148 * Starts the given command when the condition changes to `false` and cancels
149 * it when the condition changes to `true`. Moves command ownership to the
150 * button scheduler.
151 *
152 * <p>Doesn't re-start the command if it ends while the condition is still
153 * `false`. If the command should restart, see RepeatCommand.
154 *
155 * @param command The command to bind.
156 * @return The trigger, for chained calls.
157 */
159
160 /**
161 * Toggles a command when the condition changes from `false` to `true`.
162 *
163 * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
164 * lifespan of the command.
165 *
166 * @param command the command to toggle
167 * @return this trigger, so calls can be chained
168 */
170
171 /**
172 * Toggles a command when the condition changes from `false` to `true`.
173 *
174 * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
175 * lifespan of the command.
176 *
177 * @param command the command to toggle
178 * @return this trigger, so calls can be chained
179 */
181
182 /**
183 * Toggles a command when the condition changes from `true` to the low
184 * state.
185 *
186 * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
187 * lifespan of the command.
188 *
189 * @param command the command to toggle
190 * @return this trigger, so calls can be chained
191 */
193
194 /**
195 * Toggles a command when the condition changes from `true` to `false`.
196 *
197 * <p>Takes a raw pointer, and so is non-owning; users are responsible for the
198 * lifespan of the command.
199 *
200 * @param command the command to toggle
201 * @return this trigger, so calls can be chained
202 */
204
205 /**
206 * Composes two triggers with logical AND.
207 *
208 * @return A trigger which is active when both component triggers are active.
209 */
210 Trigger operator&&(std::function<bool()> rhs) {
211 return Trigger(m_loop, [condition = m_condition, rhs = std::move(rhs)] {
212 return condition() && rhs();
213 });
214 }
215
216 /**
217 * Composes two triggers with logical AND.
218 *
219 * @return A trigger which is active when both component triggers are active.
220 */
222 return Trigger(m_loop, [condition = m_condition, rhs] {
223 return condition() && rhs.m_condition();
224 });
225 }
226
227 /**
228 * Composes two triggers with logical OR.
229 *
230 * @return A trigger which is active when either component trigger is active.
231 */
232 Trigger operator||(std::function<bool()> rhs) {
233 return Trigger(m_loop, [condition = m_condition, rhs = std::move(rhs)] {
234 return condition() || rhs();
235 });
236 }
237
238 /**
239 * Composes two triggers with logical OR.
240 *
241 * @return A trigger which is active when either component trigger is active.
242 */
244 return Trigger(m_loop, [condition = m_condition, rhs] {
245 return condition() || rhs.m_condition();
246 });
247 }
248
249 /**
250 * Composes a trigger with logical NOT.
251 *
252 * @return A trigger which is active when the component trigger is inactive,
253 * and vice-versa.
254 */
256 return Trigger(m_loop, [condition = m_condition] { return !condition(); });
257 }
258
259 /**
260 * Creates a new debounced trigger from this trigger - it will become active
261 * when this trigger has been active for longer than the specified period.
262 *
263 * @param debounceTime The debounce period.
264 * @param type The debounce type.
265 * @return The debounced trigger.
266 */
267 Trigger Debounce(units::second_t debounceTime,
269 frc::Debouncer::DebounceType::kRising);
270
271 /**
272 * Returns the current state of this trigger.
273 * @return A bool representing the current state of the trigger.
274 */
275 bool Get() const;
276
277 private:
278 frc::EventLoop* m_loop;
279 std::function<bool()> m_condition;
280};
281} // namespace frc2
A state machine representing a complete action to be performed by the robot.
Definition: Command.h:41
A wrapper around std::unique_ptr<Command> so commands have move-only semantics.
Definition: CommandPtr.h:29
The scheduler responsible for running Commands.
Definition: CommandScheduler.h:38
This class provides an easy way to link commands to conditions.
Definition: Trigger.h:33
bool Get() const
Returns the current state of this trigger.
Trigger OnFalse(CommandPtr &&command)
Starts the given command whenever the condition changes from true to false.
Trigger()
Create a new trigger that is always false.
Definition: Trigger.h:58
Trigger operator&&(std::function< bool()> rhs)
Composes two triggers with logical AND.
Definition: Trigger.h:210
Trigger WhileTrue(CommandPtr &&command)
Starts the given command when the condition changes to true and cancels it when the condition changes...
Trigger operator!()
Composes a trigger with logical NOT.
Definition: Trigger.h:255
Trigger WhileFalse(Command *command)
Starts the given command when the condition changes to false and cancels it when the condition change...
Trigger OnFalse(Command *command)
Starts the given command whenever the condition changes from true to false.
Trigger operator&&(Trigger rhs)
Composes two triggers with logical AND.
Definition: Trigger.h:221
Trigger Debounce(units::second_t debounceTime, frc::Debouncer::DebounceType type=frc::Debouncer::DebounceType::kRising)
Creates a new debounced trigger from this trigger - it will become active when this trigger has been ...
Trigger OnTrue(CommandPtr &&command)
Starts the given command whenever the condition changes from false to true.
Trigger OnTrue(Command *command)
Starts the given command whenever the condition changes from false to true.
Trigger WhileFalse(CommandPtr &&command)
Starts the given command when the condition changes to false and cancels it when the condition change...
Trigger(const Trigger &other)
Trigger ToggleOnTrue(Command *command)
Toggles a command when the condition changes from false to true.
Trigger operator||(Trigger rhs)
Composes two triggers with logical OR.
Definition: Trigger.h:243
Trigger operator||(std::function< bool()> rhs)
Composes two triggers with logical OR.
Definition: Trigger.h:232
Trigger ToggleOnFalse(CommandPtr &&command)
Toggles a command when the condition changes from true to false.
Trigger WhileTrue(Command *command)
Starts the given command when the condition changes to true and cancels it when the condition changes...
Trigger ToggleOnTrue(CommandPtr &&command)
Toggles a command when the condition changes from false to true.
Trigger(frc::EventLoop *loop, std::function< bool()> condition)
Creates a new trigger based on the given condition.
Definition: Trigger.h:52
Trigger(std::function< bool()> condition)
Creates a new trigger based on the given condition.
Definition: Trigger.h:42
Trigger ToggleOnFalse(Command *command)
Toggles a command when the condition changes from true to the low state.
DebounceType
Definition: Debouncer.h:20
A declarative way to bind a set of actions to a loop and execute them when the loop is polled.
Definition: EventLoop.h:15
type
Definition: core.h:556
Definition: TrapezoidProfileSubsystem.h:12
Definition: array.h:89