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

Open
wants to merge 19 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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 @@ -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
Loading