mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[commands] Add deadband trigger methods to CommandGenericHID (#7085)
Co-authored-by: Joseph Eng <91924258+KangarooKoala@users.noreply.github.com>
This commit is contained in:
committed by
GitHub
parent
f150b36108
commit
968bdf0d06
@@ -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<>();
|
||||
|
||||
/**
|
||||
@@ -260,6 +262,37 @@ public class CommandGenericHID {
|
||||
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.
|
||||
*
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -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.
|
||||
*
|
||||
|
||||
Reference in New Issue
Block a user