Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.wpilibj.event.BooleanEvent Class Reference

Public Member Functions

 BooleanEvent (EventLoop loop, BooleanSupplier signal)
 
final boolean getAsBoolean ()
 
final void ifHigh (Runnable action)
 
BooleanEvent rising ()
 
BooleanEvent falling ()
 
BooleanEvent debounce (double seconds)
 
BooleanEvent debounce (double seconds, Debouncer.DebounceType type)
 
BooleanEvent negate ()
 
BooleanEvent and (BooleanSupplier other)
 
BooleanEvent or (BooleanSupplier other)
 

Protected Attributes

final EventLoop m_loop
 

Detailed Description

This class provides an easy way to link actions to high-active logic signals. Each object represents a digital signal to which callback actions can be bound using ifHigh(Runnable).

These signals can easily be composed for advanced functionality using and(BooleanSupplier), or(BooleanSupplier), negate() etc.

To get an event that activates only when this one changes, see falling() and rising().

Constructor & Destructor Documentation

◆ BooleanEvent()

edu.wpi.first.wpilibj.event.BooleanEvent.BooleanEvent ( EventLoop loop,
BooleanSupplier signal )

Creates a new event with the given signal determining whether it is active.

Parameters
loopthe loop that polls this event
signalthe digital signal represented by this object.

Member Function Documentation

◆ and()

BooleanEvent edu.wpi.first.wpilibj.event.BooleanEvent.and ( BooleanSupplier other)

Composes this event with another event, returning a new signal that is in the high state when both signals are in the high state.

The events must use the same event loop. If the events use different event loops, the composed signal won't update until both loops are polled.

Parameters
otherthe event to compose with
Returns
the event that is active when both events are active

◆ debounce() [1/2]

BooleanEvent edu.wpi.first.wpilibj.event.BooleanEvent.debounce ( double seconds)

Creates a new debounced event from this event - it will become active when this event has been active for longer than the specified period.

Parameters
secondsThe debounce period.
Returns
The debounced event (rising edges debounced only)

◆ debounce() [2/2]

BooleanEvent edu.wpi.first.wpilibj.event.BooleanEvent.debounce ( double seconds,
Debouncer.DebounceType type )

Creates a new debounced event from this event - it will become active when this event has been active for longer than the specified period.

Parameters
secondsThe debounce period.
typeThe debounce type.
Returns
The debounced event.

◆ falling()

BooleanEvent edu.wpi.first.wpilibj.event.BooleanEvent.falling ( )

Get a new event that triggers only when this one newly changes to false.

Returns
a new event representing when this one newly changes to false.

◆ getAsBoolean()

final boolean edu.wpi.first.wpilibj.event.BooleanEvent.getAsBoolean ( )

Check the state of this signal (high or low) as of the last loop poll.

Returns
true for the high state, false for the low state. If the event was never polled, it returns the state at event construction.

◆ ifHigh()

final void edu.wpi.first.wpilibj.event.BooleanEvent.ifHigh ( Runnable action)

Bind an action to this event.

Parameters
actionthe action to run if this event is active.

◆ negate()

BooleanEvent edu.wpi.first.wpilibj.event.BooleanEvent.negate ( )

Creates a new event that is active when this event is inactive, i.e. that acts as the negation of this event.

Returns
the negated event

◆ or()

BooleanEvent edu.wpi.first.wpilibj.event.BooleanEvent.or ( BooleanSupplier other)

Composes this event with another event, returning a new signal that is high when either signal is high.

The events must use the same event loop. If the events use different event loops, the composed signal won't update until both loops are polled.

Parameters
otherthe event to compose with
Returns
a signal that is high when either signal is high.

◆ rising()

BooleanEvent edu.wpi.first.wpilibj.event.BooleanEvent.rising ( )

Get a new event that events only when this one newly changes to true.

Returns
a new event representing when this one newly changes to true.

Member Data Documentation

◆ m_loop

final EventLoop edu.wpi.first.wpilibj.event.BooleanEvent.m_loop
protected

Poller loop.


The documentation for this class was generated from the following file: