Skip to content

Commit

Permalink
[commands] Add deadband trigger methods to CommandGenericHID (wpilibs…
Browse files Browse the repository at this point in the history
…uite#7085)

Co-authored-by: Joseph Eng <91924258+KangarooKoala@users.noreply.github.com>
  • Loading branch information
2 people authored and spacey-sooty committed Oct 26, 2024
1 parent 5d70986 commit 9d3d05c
Show file tree
Hide file tree
Showing 3 changed files with 55 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@ public class CommandGenericHID {
new HashMap<>();
private final Map<EventLoop, Map<Pair<Integer, Double>, Trigger>> m_axisGreaterThanCache =
new HashMap<>();
private final Map<EventLoop, Map<Pair<Integer, Double>, Trigger>>
m_axisMagnitudeGreaterThanCache = new HashMap<>();
private final Map<EventLoop, Map<Integer, Trigger>> m_povCache = new HashMap<>();

/**
Expand Down Expand Up @@ -260,6 +262,37 @@ 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 magnitude value is greater than {@code
* threshold}, attached to the given loop.
*
* @param axis The axis to read, starting at 0
* @param threshold The value above which this trigger should return true.
* @param loop the event loop instance to attach the trigger to.
* @return a Trigger instance that is true when the axis magnitude value is greater than the
* provided threshold.
*/
public Trigger axisMagnitudeGreaterThan(int axis, double threshold, EventLoop loop) {
var cache = m_axisMagnitudeGreaterThanCache.computeIfAbsent(loop, k -> new HashMap<>());
return cache.computeIfAbsent(
Pair.of(axis, threshold),
k -> new Trigger(loop, () -> Math.abs(getRawAxis(axis)) > threshold));
}

/**
* Constructs a Trigger instance that is true when the axis magnitude value is greater than {@code
* threshold}, attached to {@link CommandScheduler#getDefaultButtonLoop() the default command
* scheduler button loop}.
*
* @param axis The axis to read, starting at 0
* @param threshold The value above which this trigger should return true.
* @return a Trigger instance that is true when the deadbanded axis value is active (non-zero).
*/
public Trigger axisMagnitudeGreaterThan(int axis, double threshold) {
return axisMagnitudeGreaterThan(
axis, threshold, CommandScheduler.getInstance().getDefaultButtonLoop());
}

/**
* Get the value of the axis.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,13 @@ Trigger CommandGenericHID::AxisGreaterThan(int axis, double threshold,
});
}

Trigger CommandGenericHID::AxisMagnitudeGreaterThan(
int axis, double threshold, frc::EventLoop* loop) const {
return Trigger(loop, [this, axis, threshold]() {
return std::abs(m_hid.GetRawAxis(axis)) > threshold;
});
}

void CommandGenericHID::SetRumble(frc::GenericHID::RumbleType type,
double value) {
m_hid.SetRumble(type, value);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -230,6 +230,21 @@ class CommandGenericHID {
frc::EventLoop* loop =
CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;

/**
* Constructs a Trigger instance that is true when the axis magnitude value is
* greater than {@code threshold}, attached to the given loop.
*
* @param axis The axis to read, starting at 0
* @param threshold The value above which this trigger should return true.
* @param loop the event loop instance to attach the trigger to.
* @return a Trigger instance that is true when the axis magnitude value is
* greater than the provided threshold.
*/
Trigger AxisMagnitudeGreaterThan(
int axis, double threshold,
frc::EventLoop* loop =
CommandScheduler::GetInstance().GetDefaultButtonLoop()) const;

/**
* Set the rumble output for the HID.
*
Expand Down

0 comments on commit 9d3d05c

Please sign in to comment.