Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[cmd] Add deadband trigger methods to CommandGenericHID #7085

Merged
merged 22 commits into from
Oct 11, 2024
Merged
Changes from 8 commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
e0e186e
first draft java
narmstro2020 Sep 15, 2024
dee6b41
first draft java
narmstro2020 Sep 15, 2024
ca10711
Merge branch 'CommandHIDTrigger' of https://github.com/narmstro2020/a…
narmstro2020 Sep 15, 2024
13d5fde
Formatting fixes
github-actions[bot] Sep 15, 2024
09be2ad
method rearrangement
narmstro2020 Sep 15, 2024
08f2ee7
Formatting fixes
github-actions[bot] Sep 15, 2024
b7ac6c3
formatting fixes
narmstro2020 Sep 15, 2024
2e768e7
Merge branch 'CommandHIDTrigger' of https://github.com/narmstro2020/a…
narmstro2020 Sep 15, 2024
82d31e2
Update wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command…
narmstro2020 Sep 16, 2024
63102a2
Update wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command…
narmstro2020 Sep 16, 2024
ab63fac
cache addition and method removal
narmstro2020 Sep 16, 2024
d0a997b
Formatting fixes
github-actions[bot] Sep 16, 2024
b5c2103
C++ first draft.
narmstro2020 Sep 16, 2024
528bba3
method rename, javadoc reconfigure
narmstro2020 Sep 16, 2024
0fb39ca
Formatting fixes
github-actions[bot] Sep 16, 2024
be4196c
Update wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command…
narmstro2020 Sep 18, 2024
ffe0eab
format fix
narmstro2020 Sep 18, 2024
e72f25c
rename fix
narmstro2020 Sep 18, 2024
d668bb5
Merge branch 'wpilibsuite:main' into CommandHIDTrigger
narmstro2020 Sep 21, 2024
c93a986
Merge branch 'wpilibsuite:main' into CommandHIDTrigger
narmstro2020 Sep 29, 2024
49e10fc
Merge branch 'wpilibsuite:main' into CommandHIDTrigger
narmstro2020 Oct 1, 2024
bd0648e
Merge branch 'wpilibsuite:main' into CommandHIDTrigger
narmstro2020 Oct 10, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package edu.wpi.first.wpilibj2.command.button;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.Pair;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.event.EventLoop;
Expand Down Expand Up @@ -260,6 +261,74 @@ public Trigger axisGreaterThan(int axis, double threshold, EventLoop loop) {
Pair.of(axis, threshold), k -> new Trigger(loop, () -> getRawAxis(axis) > threshold));
}

/**
* Constructs a Trigger instance that is true when the axis value is active (non-zero) given a
* {@code deadband}, attached to the given loop.
*
* @param axis The axis to read, starting at 0
* @param deadband The value used to deadband the axis value. The trigger returns true if the
* deadbanded value is non-zero.
* @param loop the event loop instance to attach the trigger to.
* @return a Trigger instance that is true when the deadbanded axis value is active (non-zero).
narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved
*/
public Trigger axisActive(int axis, double deadband, EventLoop loop) {
var cache = m_axisGreaterThanCache.computeIfAbsent(loop, k -> new HashMap<>());
narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved
return cache.computeIfAbsent(
Pair.of(axis, deadband),
k -> new Trigger(loop, () -> MathUtil.applyDeadband(getRawAxis(axis), deadband) != 0.0));
narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved
}

/**
* Constructs a Trigger instance that is true when the axis value is active (non-zero) given a
* {@code deadband}, attached to {@link CommandScheduler#getDefaultButtonLoop() the default
* command scheduler button loop}.
*
* @param axis The axis to read, starting at 0
* @param deadband The value used to deadband the axis value. The trigger returns true if the
* deadbanded value is non-zero.
* @return a Trigger instance that is true when the deadbanded axis value is active (non-zero).
*/
public Trigger axisActive(int axis, double deadband) {
return axisGreaterThan(axis, deadband, CommandScheduler.getInstance().getDefaultButtonLoop());
narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved
}

/**
* Constructs a Trigger instance that is true when the axis value is active (non-zero) given a
* {@code deadband}, attached to the given loop.
*
* @param axis The axis to read, starting at 0
* @param deadband The value used to deadband the axis value. The trigger returns true if the
* deadbanded value is non-zero.
* @param maxMagnitude The maximum magnitude of the input. Can be infinite.
* @param loop the event loop instance to attach the trigger to.
* @return a Trigger instance that is true when the deadbanded axis value is active (non-zero).
*/
public Trigger axisActive(int axis, double deadband, double maxMagnitude, EventLoop loop) {
narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved
var cache = m_axisGreaterThanCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
Pair.of(axis, deadband),
k ->
new Trigger(
loop,
() -> MathUtil.applyDeadband(getRawAxis(axis), deadband, maxMagnitude) != 0.0));
}

/**
* Constructs a Trigger instance that is true when the axis value is active (non-zero) given a
* {@code deadband}, attached to {@link CommandScheduler#getDefaultButtonLoop() the default
* command scheduler button loop}.
*
* @param axis The axis to read, starting at 0
* @param deadband The value used to deadband the axis value. The trigger returns true if the
* deadbanded value is non-zero.
* @param maxMagnitude The maximum magnitude of the input. Can be infinite.
* @return a Trigger instance that is true when the deadbanded axis value is active (non-zero).
*/
public Trigger axisActive(int axis, double deadband, double maxMagnitude) {
narmstro2020 marked this conversation as resolved.
Show resolved Hide resolved
return axisActive(
axis, deadband, maxMagnitude, CommandScheduler.getInstance().getDefaultButtonLoop());
}

/**
* Get the value of the axis.
*
Expand Down
Loading